[Documentation] [TitleIndex] [WordIndex

  Show EOL distros: 

navigation_experimental: assisted_teleop | goal_passer | pose_base_controller | pose_follower | sbpl_lattice_planner | sbpl_recovery | twist_recovery

Package Summary

The sbpl_lattice_planner is a global planner plugin for move_base and wraps the SBPL search-based planning library.

navigation_experimental: assisted_teleop | goal_passer | pose_base_controller | pose_follower | sbpl_lattice_planner | sbpl_recovery | twist_recovery

Package Summary

The sbpl_lattice_planner is a global planner plugin for move_base and wraps the SBPL search-based planning library.

sbpl_lattice_planner is a ROS wrapper for the SBPL lattice environment and adheres to the nav_core::BaseGlobalPlanner interface specified in nav_core. The lattice planner can therefore be used as the global planner for move_base. The planner will generate a path from the robot's current position to a desired goal pose. Paths are generated by combining a series of "motion primitives" which are short, kinematically feasible motions. Planning is therefore done in x, y, and theta dimensions, resulting in smooth paths that take robot orientation into account, which is especially important if the robot is not assumed to be circular or has nonholonomic constraints. Plans can be found using the ARA* planner or AD* planner.

SBPL_Lattice_Planner

Video

How to use

This global planner can be used with move_base simply by setting the "base_global_planner" parameter to "SBPLLatticePlanner". Additionally, at the very least the path to a motion primitive file must be specified shown below in the list of parameters.

Example in Stage

The package contains a launch file for testing the sbpl_lattice_planner as the global planner for move_base using stage for 2D simulation:

roslaunch sbpl_lattice_planner  move_base_sbpl_fake_localization_2.5cm.launch

ROS API

Published Topics

~/SBPLLatticePlanner/plan (nav_msgs/Path) ~/SBPLLatticePlanner/sbpl_lattice_planner_stats (sbpl_lattice_planner/SBPLLatticePlannerStats)

Parameters

~/SBPLLatticePlanner/planner_type (string, default: "ARAPlanner") ~/SBPLLatticePlanner/allocated_time (double, default: 10) ~/SBPLLatticePlanner/initial_epsilon (double, default: 3.0) ~/SBPLLatticePlanner/environment_type (string, default: "XYThetaLattice") ~/SBPLLatticePlanner/forward_search (bool, default: false) ~/SBPLLatticePlanner/primitive_filename (string, default: "") ~/SBPLLatticePlanner/force_scratch_limit (int, default: 500) ~/SBPLLatticePlanner/nominalvel_mpersecs (double, default: 0.4) ~/SBPLLatticePlanner/timetoturn45degsinplace_secs (double, default: 0.6) ~/SBPLLatticePlanner/lethal_obstacle (unsigned char, default: 20)

Customizing your Motion Primitives

Please refer to the SBPL documentation for pre-made motion primitives for the PR2 (and other robots) as well as instructions on how to generate your own custom motions.


2019-08-17 13:15