Search
The main task is to implement a simple grid-based planning approach. You will learn how to plan on the grid such that the robot embodiment is considered.
HexapodExplorer.py
In class HexapodExplorer.py implement the following basic steps of the grid-based navigation pipeline:
grow_obstacles
plan_path
simplify_path
The detailed description and guidelines on individual steps follow.
The purpose of the grow_obstacles function is to pre-process the grid map into a binary map by rejecting obstacles, unknown and inaccessible areas for the robot given its embodiment. The robot is considered to be a circle with $r_\mathrm{robot}$ radius robot_size. The result of the obstacle growing is a binary map with the used binary values 1 (for occupied, inaccessible and unknown cells) and 0 (for traversable cells). For each grid_map cell $m_i$ the new binary value $b_i$ of the grid_map_grow is based on its Bayesian occupancy probability $P(m_i = occupied \vert z) = 0.5$ and distance to the nearby obstacles according to the following rules:
robot_size
grid_map
grid_map_grow
The input parameters of the function are:
The function returns:
The grow_obstacles function in the HexapodExplorer.py class has a following prescription:
def grow_obstacles(self, grid_map, robot_size): """ Method to grow the obstacles to take into account the robot embodiment Args: grid_map: OccupancyGrid - gridmap for obstacle growing robot_size: float - size of the robot Returns: grid_map_grow: OccupancyGrid - gridmap with considered robot body embodiment """
Suggested approach (click to view)
Obstacle growing - The robot has non-zero dimensions that represent its embodiment which has to be taken into account when planning. Moreover, the plan execution in real experiments has a limited precision which further enlarges demands on the clearance to the obstacles for the robot to safely navigate the environment. The planning with a large robot in grid environment is complex, therefore the trick is to grow the borders of the obstacles by a diameter of the robot and plan in the resulting map that ensures a sufficient clearance to the obstacles. The obstacle growing can be achieved by one of the following approaches
scipy.ndimage.distance_transform_edt
The purpose of the plan_path function is to plan the path between the start and goal poses on the pre-processed grid map considering planning with 8-neighborhood. The function returns a path on the output. If the path is not found, the planner returns None.
None
start
goal
position.x
position.y
The plan_path function in the HexapodExplorer.py class has a following prescription:
def plan_path(self, grid_map, start, goal): """ Method to plan the path from start to the goal pose on the grid Args: grid_map: OccupancyGrid - gridmap for obstacle growing start: Pose - robot start pose goal: Pose - robot goal pose Returns: path: Path - path between the start and goal Pose on the map """
Considered planning methods
Path simplification is usually done by excluding navigation points from the path, that are not necessary in the sense that the robot does not have to visit them precisely. A typical approach to trajectory smoothing is to connect the neighboring segments one by one using straight-line segments (using Bresenham line algorithm) up to the point where the straight-line segment collide with an obstacle (grown obstacle) and then follow with another straight-line segment.
path
The simplify_path function in the HexapodExplorer.py class has a following prescription:
def simplify_path(self, grid_map, path): """ Method to simplify the found path on the grid Args: grid_map: OccupancyGrid - gridmap for obstacle growing path: Path - path to be simplified Returns: path_simple: Path - simplified path """
#add the start position path_simple add path[0] #iterate through the path and simplify the path while not path_simple[end] == path[end]: #until the goal is not reached #find the connected segment previous_pose = path_simple[end] for each pose in rest of the path: if bresenham_line(path_simple[end], pose) not collide: #there is no collision previous_pose = pose #the goal is reached if pose = path[end]: path_simple append pose break else: #there is collision path_simple append previous_pose break
The evaluation focus on correct behavior of the above described robot navigation pipeline.
#!/usr/bin/env python3 # -*- coding: utf-8 -*- import matplotlib.pyplot as plt import sys import os import math import numpy as np sys.path.append('hexapod_robot') sys.path.append('hexapod_explorer') #import hexapod robot and explorer import HexapodRobot as hexapod import HexapodExplorer as explorer #import communication messages from messages import * #pickle import pickle ROBOT_SIZE = 0.3 if __name__=="__main__": #instantiate the explorer robot explor = explorer.HexapodExplorer() #load scenarios scenarios = pickle.load( open( "scenarios.bag", "rb" ) ) #evaluate individual scenarios for gridmap, start, goal in scenarios: #obstacle growing gridmap_processed = explor.grow_obstacles(gridmap, ROBOT_SIZE) #path planning path = explor.plan_path(gridmap_processed, start, goal) #path simplification path_simple = explor.simplify_path(gridmap_processed, path) #plot the result def plot_path(path, ax, clr): """ simple method to draw the path """ if path is not None: poses = np.asarray([(pose.position.x,pose.position.y) for pose in path.poses]) ax.plot(poses[:,0], poses[:,1], '.',color=clr) ax.plot(poses[:,0], poses[:,1], '-',color=clr) fig, ax = plt.subplots() gridmap.plot(ax) plot_path(path, ax, 'r') plot_path(path_simple, ax, 'b') plt.xlabel('x[m]') plt.ylabel('y[m]') plt.axis('square') plt.show()
int()
floor()