The freespace_planner Package 
freespace_planner_node 
freespace_planner_node is a global path planner node that plans trajectory
in the space having static/dynamic obstacles. This node is currently based on
Hybrid A* search algorithm in freespace_planning_algorithms package.
Other algorithms such as rrt* will be also added and selectable in the future.
Note 
Due to the constraint of trajectory following, the output trajectory will be split to include only the single direction path.
In other words, the output trajectory doesn't include both forward and backward trajectories at once.
Name 
Type 
Description 
 
 
~input/routeautoware_planning_msgs::Route 
route and goal pose 
 
~input/occupancy_gridnav_msgs::OccupancyGrid 
costmap, for drivable areas 
 
~input/twistgeometry_msgs::TwistStamped 
vehicle velocity, for checking whether vehicle is stopped 
 
~input/scenarioautoware_planning_msgs::Scenario 
scenarios to be activated, for node activation 
 
 
Output topics 
Name 
Type 
Description 
 
 
~output/trajectoryautoware_planning_msgs::Trajectory 
trajectory to be followed 
 
is_completedbool (implemented as rosparam) 
whether all split trajectory are published 
 
 
Output TFs 
None
How to launch 
Write your remapping info in freespace_planner.launch or add args when executing roslaunch 
roslaunch freespace_planner freespace_planner.launch 
Parameters 
Node parameters 
Parameter 
Type 
Description 
 
 
update_ratedouble 
timer's update rate 
 
waypoints_velocitydouble 
velocity in output trajectory (currently, only constant velocity is supported) 
 
th_arrived_distance_mdouble 
threshold distance to check if vehicle has arrived at the trajectory's endpoint 
 
th_stopped_time_secdouble 
threshold time to check if vehicle is stopped 
 
th_stopped_velocity_mpsdouble 
threshold velocity to check if vehicle is stopped 
 
th_course_out_distance_mdouble 
threshold distance to check if vehicle is out of course 
 
replan_when_obstacle_foundbool 
whether replanning when obstacle has found on the trajectory 
 
replan_when_course_outbool 
whether replanning when vehicle is out of course 
 
 
Planner common parameters 
Parameter 
Type 
Description 
 
 
planning_algorithmsstring 
algorithms used in the node 
 
time_limitdouble 
time limit of planning 
 
robot_lengthdouble 
robot length 
 
robot_widthdouble 
robot width 
 
robot_base2backdouble 
distance from robot's back to robot's base_link 
 
minimum_turning_radiusdouble 
minimum turning radius of robot 
 
theta_sizedouble 
the number of angle's discretization 
 
lateral_goal_rangedouble 
goal range of lateral position 
 
longitudinal_goal_rangedouble 
goal range of longitudinal position 
 
angle_goal_rangedouble 
goal range of angle 
 
curve_weightdouble 
additional cost factor for curve actions 
 
reverse_weightdouble 
additional cost factor for reverse actions 
 
obstacle_thresholddouble 
threshold for regarding a certain grid as obstacle 
 
 
A* search parameters 
Parameter 
Type 
Description 
 
 
only_behind_solutionsbool 
whether restricting the solutions to be behind the goal 
 
use_backbool 
whether using backward trajectory 
 
distance_heuristic_weightdouble 
heuristic weight for estimating node's cost 
 
 
Flowchart