Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method. More...
#include <eband_local_planner_ros.h>

Public Member Functions | |
| bool | computeVelocityCommands (geometry_msgs::Twist &cmd_vel) | 
| Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.   | |
| EBandPlannerROS () | |
| Default constructor for the ros wrapper.   | |
| EBandPlannerROS (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) | |
| Constructs the ros wrapper.   | |
| void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) | 
| Initializes the ros wrapper.   | |
| bool | isGoalReached () | 
| Check if the goal pose has been achieved.   | |
| bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) | 
| Set the plan that the controller is following; also reset eband-planner.   | |
| ~EBandPlannerROS () | |
| Destructor for the wrapper.   | |
Private Member Functions | |
| void | odomCallback (const nav_msgs::Odometry::ConstPtr &msg) | 
| Odometry-Callback: function is called whenever a new odometry msg is published on that topic.   | |
Private Attributes | |
| nav_msgs::Odometry | base_odom_ | 
| costmap_2d::Costmap2DROS * | costmap_ros_ | 
| pointer to costmap   | |
| boost::shared_ptr< EBandPlanner > | eband_ | 
| boost::shared_ptr < EBandTrajectoryCtrl >  | eband_trj_ctrl_ | 
| boost::shared_ptr < EBandVisualization >  | eband_visual_ | 
| ros::Publisher | g_plan_pub_ | 
| publishes modified global plan   | |
| std::vector < geometry_msgs::PoseStamped >  | global_plan_ | 
| bool | initialized_ | 
| ros::Publisher | l_plan_pub_ | 
| publishes prediction for local commands   | |
| boost::mutex | odom_mutex_ | 
| ros::Subscriber | odom_sub_ | 
| subscribes to the odometry topic in global namespace   | |
| std::vector< int > | plan_start_end_counter_ | 
| double | rot_stopped_vel_ | 
| tf::TransformListener * | tf_ | 
| pointer to Transform Listener   | |
| double | trans_stopped_vel_ | 
| lower bound for absolute value of velocity (with respect to stick-slip behaviour)   | |
| std::vector < geometry_msgs::PoseStamped >  | transformed_plan_ | 
| double | xy_goal_tolerance_ | 
| parameters to define region in which goal is treated as reached   | |
| double | yaw_goal_tolerance_ | 
Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method.
Definition at line 81 of file eband_local_planner_ros.h.
Default constructor for the ros wrapper.
Definition at line 54 of file eband_local_planner_ros.cpp.
| eband_local_planner::EBandPlannerROS::EBandPlannerROS | ( | std::string | name, | 
| tf::TransformListener * | tf, | ||
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) | 
Constructs the ros wrapper.
| name | The name to give this instance of the elastic band local planner | 
| tf | A pointer to a transform listener | 
| costmap | The cost map to use for assigning costs to trajectories | 
Definition at line 57 of file eband_local_planner_ros.cpp.
Destructor for the wrapper.
Definition at line 65 of file eband_local_planner_ros.cpp.
| bool eband_local_planner::EBandPlannerROS::computeVelocityCommands | ( | geometry_msgs::Twist & | cmd_vel | ) |  [virtual] | 
        
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
| cmd_vel | Will be filled with the velocity command to be passed to the robot base | 
Implements nav_core::BaseLocalPlanner.
Definition at line 193 of file eband_local_planner_ros.cpp.
| void eband_local_planner::EBandPlannerROS::initialize | ( | std::string | name, | 
| tf::TransformListener * | tf, | ||
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) |  [virtual] | 
        
Initializes the ros wrapper.
| name | The name to give this instance of the trajectory planner | 
| tf | A pointer to a transform listener | 
| costmap | The cost map to use for assigning costs to trajectories | 
Implements nav_core::BaseLocalPlanner.
Definition at line 68 of file eband_local_planner_ros.cpp.
| bool eband_local_planner::EBandPlannerROS::isGoalReached | ( | ) |  [virtual] | 
        
Check if the goal pose has been achieved.
Implements nav_core::BaseLocalPlanner.
Definition at line 347 of file eband_local_planner_ros.cpp.
| void eband_local_planner::EBandPlannerROS::odomCallback | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |  [private] | 
        
Odometry-Callback: function is called whenever a new odometry msg is published on that topic.
| Pointer | to the received message | 
Definition at line 370 of file eband_local_planner_ros.cpp.
| bool eband_local_planner::EBandPlannerROS::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | orig_global_plan | ) |  [virtual] | 
        
Set the plan that the controller is following; also reset eband-planner.
| orig_global_plan | The plan to pass to the controller | 
Implements nav_core::BaseLocalPlanner.
Definition at line 135 of file eband_local_planner_ros.cpp.
nav_msgs::Odometry eband_local_planner::EBandPlannerROS::base_odom_ [private] | 
        
Definition at line 148 of file eband_local_planner_ros.h.
pointer to costmap
Definition at line 135 of file eband_local_planner_ros.h.
boost::shared_ptr<EBandPlanner> eband_local_planner::EBandPlannerROS::eband_ [private] | 
        
Definition at line 154 of file eband_local_planner_ros.h.
boost::shared_ptr<EBandTrajectoryCtrl> eband_local_planner::EBandPlannerROS::eband_trj_ctrl_ [private] | 
        
Definition at line 156 of file eband_local_planner_ros.h.
boost::shared_ptr<EBandVisualization> eband_local_planner::EBandPlannerROS::eband_visual_ [private] | 
        
Definition at line 155 of file eband_local_planner_ros.h.
publishes modified global plan
Definition at line 143 of file eband_local_planner_ros.h.
std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::global_plan_ [private] | 
        
Definition at line 149 of file eband_local_planner_ros.h.
bool eband_local_planner::EBandPlannerROS::initialized_ [private] | 
        
Definition at line 159 of file eband_local_planner_ros.h.
publishes prediction for local commands
Definition at line 144 of file eband_local_planner_ros.h.
boost::mutex eband_local_planner::EBandPlannerROS::odom_mutex_ [private] | 
        
Definition at line 160 of file eband_local_planner_ros.h.
subscribes to the odometry topic in global namespace
Definition at line 145 of file eband_local_planner_ros.h.
Definition at line 151 of file eband_local_planner_ros.h.
double eband_local_planner::EBandPlannerROS::rot_stopped_vel_ [private] | 
        
Definition at line 140 of file eband_local_planner_ros.h.
pointer to Transform Listener
Definition at line 136 of file eband_local_planner_ros.h.
double eband_local_planner::EBandPlannerROS::trans_stopped_vel_ [private] | 
        
lower bound for absolute value of velocity (with respect to stick-slip behaviour)
Definition at line 140 of file eband_local_planner_ros.h.
std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::transformed_plan_ [private] | 
        
Definition at line 150 of file eband_local_planner_ros.h.
double eband_local_planner::EBandPlannerROS::xy_goal_tolerance_ [private] | 
        
parameters to define region in which goal is treated as reached
Definition at line 139 of file eband_local_planner_ros.h.
double eband_local_planner::EBandPlannerROS::yaw_goal_tolerance_ [private] | 
        
Definition at line 139 of file eband_local_planner_ros.h.