A local planner plugin for move_base of ROS, for car like robots. More...
#include <rsband_local_planner_ros.h>

Public Types | |
| enum | EbandToRSStrategy { startToEnd, startToNext, pointToPoint, skipFailures, startToRecedingEnd } |
| eband to rs planning strategy enum More... | |
Public Member Functions | |
| bool | computeVelocityCommands (geometry_msgs::Twist &cmd) |
| Computes the velocity command for the robot base. More... | |
| void | initialize (std::string name, tf::TransformListener *tfListener, costmap_2d::Costmap2DROS *costmapROS) |
| Initializes planner. More... | |
| bool | isGoalReached () |
| Checks whether the goal is reached. More... | |
| RSBandPlannerROS () | |
| Constructor. More... | |
| bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &globalPlan) |
| Sets the global plan to be followed by this planner. More... | |
| ~RSBandPlannerROS () | |
| Destructor. More... | |
Private Types | |
| typedef dynamic_reconfigure::Server < rsband_local_planner::RSBandPlannerConfig > | drs |
Private Member Functions | |
| bool | emergencyPlan (std::vector< geometry_msgs::PoseStamped > &ebandPlan, std::vector< geometry_msgs::PoseStamped > &emergencyPlan) |
| Attempts an emergency plan in case actual plan failed. More... | |
| void | interpolateOrientations (std::vector< geometry_msgs::PoseStamped > &plan) |
| Interpolates pose orientations of the given plan. More... | |
| void | reconfigureCallback (RSBandPlannerConfig &config, uint32_t level) |
| Reconfigures node parameters. More... | |
| bool | updateEBand () |
| Updates eband. More... | |
Private Attributes | |
| costmap_2d::Costmap2DROS * | costmapROS_ |
| costmap ROS wrapper ptr More... | |
| boost::shared_ptr< drs > | drs_ |
| dynamic reconfigure server ptr More... | |
| boost::shared_ptr < eband_local_planner::EBandPlanner > | ebandPlanner_ |
| eband planner ptr More... | |
| ros::Publisher | ebandPlanPub_ |
| eband plan publisher More... | |
| EbandToRSStrategy | ebandToRSStrategy_ |
| eband to reeds shepp band conversion strategy More... | |
| bool | emergencyMode_ |
| emergency plan poses More... | |
| bool | emergencyPlanning_ |
| emergency mode More... | |
| std::vector < geometry_msgs::PoseStamped > | emergencyPoses_ |
| std::vector < geometry_msgs::PoseStamped > | globalPlan_ |
| global plan More... | |
| ros::Publisher | globalPlanPub_ |
| global plan publisher More... | |
| bool | initialized_ |
| ros::Publisher | localPlanPub_ |
| local plan publisher More... | |
| std::vector< int > | planStartEndCounters_ |
| eband plan start and end indexes regarding global plan More... | |
| boost::shared_ptr< FuzzyPTC > | ptc_ |
| path tracking controller ptr More... | |
| boost::shared_ptr < ReedsSheppPlanner > | rsPlanner_ |
| reeds shepp planner ptr More... | |
| ros::Publisher | rsPlanPub_ |
| rs plan publisher More... | |
| tf::TransformListener * | tfListener_ |
| tf transform listener ptr More... | |
| std::vector < geometry_msgs::PoseStamped > | transformedPlan_ |
| transformed plan More... | |
| double | updateSubGoalDistThreshold_ |
| dist threshold used when updating sub goal More... | |
| double | xyGoalTolerance_ |
| distance to goal tolerance More... | |
| double | yawGoalTolerance_ |
| angular deviation from goal pose tolerance More... | |
A local planner plugin for move_base of ROS, for car like robots.
Definition at line 63 of file rsband_local_planner_ros.h.
|
private |
Definition at line 150 of file rsband_local_planner_ros.h.
eband to rs planning strategy enum
| Enumerator | |
|---|---|
| startToEnd | |
| startToNext | |
| pointToPoint | |
| skipFailures | |
| startToRecedingEnd | |
Definition at line 108 of file rsband_local_planner_ros.h.
| rsband_local_planner::RSBandPlannerROS::RSBandPlannerROS | ( | ) |
Constructor.
Definition at line 50 of file rsband_local_planner_ros.cpp.
| rsband_local_planner::RSBandPlannerROS::~RSBandPlannerROS | ( | ) |
Destructor.
Definition at line 55 of file rsband_local_planner_ros.cpp.
| bool rsband_local_planner::RSBandPlannerROS::computeVelocityCommands | ( | geometry_msgs::Twist & | cmd | ) |
Computes the velocity command for the robot base.
| cmd | The computed command container |
Definition at line 180 of file rsband_local_planner_ros.cpp.
|
private |
Attempts an emergency plan in case actual plan failed.
| ebandPlan | the eband plan |
| emergencyPlan | the emergency plan container |
Definition at line 437 of file rsband_local_planner_ros.cpp.
| void rsband_local_planner::RSBandPlannerROS::initialize | ( | std::string | name, |
| tf::TransformListener * | tfListener, | ||
| costmap_2d::Costmap2DROS * | costmapROS | ||
| ) |
Initializes planner.
| name | The name of the planner |
| tfListener | ptr to a tf transform listener |
| costmapROS | ptr to a costmap ros wrapper |
Definition at line 60 of file rsband_local_planner_ros.cpp.
|
private |
Interpolates pose orientations of the given plan.
| plan | The plan, for which to interpolate the poses |
Definition at line 464 of file rsband_local_planner_ros.cpp.
| bool rsband_local_planner::RSBandPlannerROS::isGoalReached | ( | ) |
Checks whether the goal is reached.
Definition at line 324 of file rsband_local_planner_ros.cpp.
|
private |
Reconfigures node parameters.
| config | The dynamic reconfigure node configuration |
| level | reconfiguration level |
Definition at line 108 of file rsband_local_planner_ros.cpp.
| bool rsband_local_planner::RSBandPlannerROS::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | globalPlan | ) |
Sets the global plan to be followed by this planner.
| globalPlan | The plan to follow |
Definition at line 132 of file rsband_local_planner_ros.cpp.
|
private |
Updates eband.
Prunes the eband and adds new target frames
Definition at line 356 of file rsband_local_planner_ros.cpp.
|
private |
costmap ROS wrapper ptr
Definition at line 157 of file rsband_local_planner_ros.h.
|
private |
dynamic reconfigure server ptr
Definition at line 152 of file rsband_local_planner_ros.h.
|
private |
eband planner ptr
Definition at line 160 of file rsband_local_planner_ros.h.
|
private |
eband plan publisher
Definition at line 189 of file rsband_local_planner_ros.h.
|
private |
eband to reeds shepp band conversion strategy
determines whether emergency planning will be used in case of failure
Definition at line 174 of file rsband_local_planner_ros.h.
|
private |
emergency plan poses
Definition at line 179 of file rsband_local_planner_ros.h.
|
private |
emergency mode
Definition at line 177 of file rsband_local_planner_ros.h.
|
private |
Definition at line 181 of file rsband_local_planner_ros.h.
|
private |
global plan
Definition at line 194 of file rsband_local_planner_ros.h.
|
private |
global plan publisher
Definition at line 185 of file rsband_local_planner_ros.h.
|
private |
Definition at line 201 of file rsband_local_planner_ros.h.
|
private |
local plan publisher
Definition at line 187 of file rsband_local_planner_ros.h.
|
private |
eband plan start and end indexes regarding global plan
Definition at line 199 of file rsband_local_planner_ros.h.
|
private |
path tracking controller ptr
Definition at line 164 of file rsband_local_planner_ros.h.
|
private |
reeds shepp planner ptr
Definition at line 162 of file rsband_local_planner_ros.h.
|
private |
rs plan publisher
Definition at line 191 of file rsband_local_planner_ros.h.
|
private |
tf transform listener ptr
Definition at line 155 of file rsband_local_planner_ros.h.
|
private |
transformed plan
Definition at line 196 of file rsband_local_planner_ros.h.
|
private |
dist threshold used when updating sub goal
Definition at line 171 of file rsband_local_planner_ros.h.
|
private |
distance to goal tolerance
Definition at line 167 of file rsband_local_planner_ros.h.
|
private |
angular deviation from goal pose tolerance
Definition at line 169 of file rsband_local_planner_ros.h.