base_planner_cu.png

This node is responsible for calculating a global path, assuming it is provided with a map, a goal location in that map, and the robot's current pose.


API Documentation

base_planner_cu

base_planner_cu is a 2D path planning system. It is based on a modified version of the Field D* algorithm that uses gradient interpolation when possible to extract shorter paths. It is a re-planner---that is, it is specially designed to update an existing path with a minimum of effort, given new map data. In typical rover applications this translates into 1-2 orders of magnitude speed-up vs. algorithms such as A* that must plan from scratch each time the map changes.

For more information on the planning algorithm see Michael Otte's page on path planning.

base_planner_cu requests the initial map from a service and then updates the map using messages sent over a topic. It can also request an entire updated map via the service. Robot pose is also requested via a service at critical times. goal and robot pose updates are available from topics. base_planner_cu publishes a path from robot to goal in map coordinates (/map_cu).

Subscribed Topics

/cu/pose_cu (geometry_msgs/PoseStamped)
  • The robot's best estimate of where it is, given all pose data, in map coordinates (/map_cu).
/cu/goal_cu (geometry_msgs/PoseStamped)
  • Pose of the goal in map coordinates (/map_cu).
/cu/map_changes_cu (sensor_msgs/PointCloud)
  • Each point in the cloud is a triple (x,y,z). x and y are used to denote which map grid is changed (in map coordinates scaled to resolution) and z is the new cost value of that grid. Note: map updates must be positive and non-zero.

Published Topics

/cu/global_path_cu (nav_msgs/Path)
  • This is a global path between robot and goal in map coordinates (/map_cu).

Services Called

/cu/get_map_cu (nav_msgs/GetMap)
  • Provides a map in map coordinates scaled by resolution.
/cu/get_pose_cu (localization_cu/GetPose)
  • The robot's best estimate of where it is, given all pose data, in map coordinates (/map_cu).

Parameters

~obstacle_cost (double, default: 10000)
  • The cost of an obstacle (of probability 1) note: this should be greater than the max path length.
~robot_radius (double, default: 0.2)
  • The radius of the robot in meters.
~safety_distance (double, default: 0.1)
  • Extra clearance required between robot and obstacles in meters, (this) + robot_radius = dilation radius.
~better_path_ratio (double, default: 0.95)
  • If {better_path_ratio <= (new path length)/(old path length) <= 1/(better_path_ratio)} then use the old path (helps keep paths stable).
~replan_jump (double, default: 25 (map grids))
  • If the robot jumps this much or more since the last re-plan, then just rebuild search tree from scratch, instead of adjusting search tree. Units are in map-grids.
~using_extra_safety_distance (bool, default: true)
  • When true, use a linear filter to increase cost within extra_safety_distance of obstacles.
~extra_safety_distance (double, default: 0.2 (m))
  • If using_extra_safety_distance = true, then if cost at grid G_1 is C_1 (after map dilation), and another grid G_2 exists within extra_safety_distance of G_1, then cost C_2 at G_2 is increased to C_1*|G_1 - G_2|/extra_safety_distance. Units are in meters.

Wiki: base_planner_cu (last edited 2010-02-11 21:10:21 by MichaelOtte)