Public Member Functions | Private Member Functions | Private Attributes
eband_local_planner::EBandPlannerROS Class Reference

Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method. More...

#include <eband_local_planner_ros.h>

Inheritance diagram for eband_local_planner::EBandPlannerROS:
Inheritance graph
[legend]

List of all members.

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::Costmap2DROScostmap_ros_
 pointer to costmap
boost::shared_ptr< EBandPlannereband_
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::TransformListenertf_
 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_

Detailed Description

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.


Constructor & Destructor Documentation

Default constructor for the ros wrapper.

Definition at line 54 of file eband_local_planner_ros.cpp.

Constructs the ros wrapper.

Parameters:
nameThe name to give this instance of the elastic band local planner
tfA pointer to a transform listener
costmapThe 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.


Member Function Documentation

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.

Parameters:
cmd_velWill be filled with the velocity command to be passed to the robot base
Returns:
True if a valid trajectory was found, false otherwise

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.

Parameters:
nameThe name to give this instance of the trajectory planner
tfA pointer to a transform listener
costmapThe cost map to use for assigning costs to trajectories

Implements nav_core::BaseLocalPlanner.

Definition at line 68 of file eband_local_planner_ros.cpp.

Check if the goal pose has been achieved.

Returns:
True if achieved, false otherwise

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.

Parameters:
Pointerto 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.

Parameters:
orig_global_planThe plan to pass to the controller
Returns:
True if the plan was updated successfully, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 135 of file eband_local_planner_ros.cpp.


Member Data Documentation

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.

Definition at line 154 of file eband_local_planner_ros.h.

Definition at line 156 of file eband_local_planner_ros.h.

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.

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.

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.

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.

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.

parameters to define region in which goal is treated as reached

Definition at line 139 of file eband_local_planner_ros.h.

Definition at line 139 of file eband_local_planner_ros.h.


The documentation for this class was generated from the following files:


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi
autogenerated on Mon Oct 6 2014 02:47:28