The srl_global_planner
ROS
package provides an implementation of the sampling based motion planners (RRT
, RRT*
, Theta*-RRT
) as global planner plugin for move_base
, a ROS
framework. Please refer to http://wiki.ros.org/move_base, for a detailed description of the move_base
framework.
All the algorithms exploit the POSQ steer function, but other steer functions are available (single and double integrator, Dubins curve).
For additional info regarding the POSQ steer function and the learned distance metric used by srl_global_planner
refer to the following papers:
- Distance Metric Learning for RRT-Based Motion Planning with Constant-Time Inference, IEEE International Conference on Robotics and Automation (ICRA'15), Seattle, USA, 2015.
- A Novel RRT Extend Function for Efficient and Smooth Mobile Robot Motion Planning, IEEE/RSJ Int. Conference on Intelligent Robots and Systems (IROS'14), Chicago, USA, 2014.
- ROS (including visualization rools -> rviz), tested on Indigo and Hydro
- ros-hydro-navigation or ros-indigo-navigation
- Eigen3
- Boost >= 1.46
- C++11 compiler
Clone the package into you catkin workspace
cd [workspace]/src
git clone https://github.com/srl-freiburg/srl_global_planner.git
cd ../
catkin_make
orcatkin build
- roslaunch srl_global_planner move_base_global_srl.launch will launch the global planner node. You can launch the planner with different configurations, by varying some parameters:
TYPE_PLANNER
, set to:- 0, use
RRT
- 1, use
RRT*
only partial rewiring - 2, use
RRT*
- 0, use
NUMBER_UPDATE_TRAJ
, set to:- Choose after how many cost improvements the planner could stop, currently set at 2. Minimum value is 1. Higher the value, higher the computaion time required to generate a trajectory
BOX
:- if it is set to 1, the nearest vertex is selected from a weighted box according to the Ball-Box Theorem.
RADIUS
:- the size of the radius where the near neighbor set is generated, in case you use
RRT*
select -1 so to have theRRT*
shrinking ball.
- the size of the radius where the near neighbor set is generated, in case you use
RHO
:- end condition for the POSQ steer function, should be set to a value of few cm.
DT
:- integration time step of the POSQ steer function, maximum value 0.5s
TYPE_SAMPLING
:- if
TYPE_SAMPLING
== 0 support set as uniform over a strips following a discrete path generate by aTheta*
algorithm - If
TYPE_SAMPLING
== 1 support set as Gaussian Mixture over theTheta*
path - if
TYPE_SAMPLING
== 2 support set as gaussians over a spline fitting theTheta*
waypoints - if
TYPE_SAMPLING
== 3 support forTheta*-RRT
, if set need to specify the range where to set orientationsOR_RANGE
and the width of the strip along theTheta*
pathWIDTH_STRIP
- if
TYPE_SAMPLING
== 4 support set as the entire state space, the dimension of the state space are read from the grid generate by the move_base framework - if
TYPE_SAMPLING
== 5 Path Biasing along the current available trajectory. If used need to set also the biasing probabilityBIAS_PROB
and theDISPERSION
- if
GOAL_BIASING
- if set to 1 activate goal biasing.
GOAL_BIASING_THS
- set the probability to select a state not in the state space
ADD_COST_FROM_COSTMAP
, set to true if you want to add cost from global cost mapADD_COST_PATHLENGTH
, set to true if you want to add the cost associated to path length and changes of headingADD_COST_THETASTAR
, set to true if you want to add cost resembling closeness to thetastar path- Params related to the distance metric, only one of them shoul be set to 1.
LEARNED
andNOTLEARNED
select the best vertex from the spherical neighborhood with radius equal to the parameterRADIUS
:LEARNED
, set to 1, if you want to find the nearest vertex according to the learned costFINDNEAREST
, set to 1 if you want to find the nearest vertex according to the Kd Tree Euclidean DistanceNOTLEARNED
, set to 1 if you want to find the nearest vertex according to the cost computed over extensions of POSQ path
TIMECOUNTER
, set to 1 if you want to specify the maximum amount of seconds your planner should work.MAXTIME
, max number of seconds allowed to find a pathmax_iterations
, ifTIMECOUNTER
is 0, this is the maximum number of iterations the planner will execute to find a path,
Any contribution to the software is welcome. Contact the current developers for any info:
- Luigi Palmieri (https://github.com/palmieri, palmieri(at)informatik.uni-freiburg.de)
- Rewrite the code to be conform to the ROS Cpp style guide, see http://wiki.ros.org/CppStyleGuide
- Use dynamic reconfiguration of the parameters, see http://wiki.ros.org/dynamic_reconfigure
- Improve documentation
- Include
RRTx