Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
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]

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. More...
 
 EBandPlannerROS ()
 Default constructor for the ros wrapper. More...
 
 EBandPlannerROS (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the ros wrapper. More...
 
void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Initializes the ros wrapper. More...
 
bool isGoalReached ()
 Check if the goal pose has been achieved. More...
 
bool setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
 Set the plan that the controller is following; also reset eband-planner. More...
 
 ~EBandPlannerROS ()
 Destructor for the wrapper. More...
 
- Public Member Functions inherited from nav_core::BaseLocalPlanner
virtual ~BaseLocalPlanner ()
 

Private Types

typedef dynamic_reconfigure::Server< eband_local_planner::EBandPlannerConfig > drs
 

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. More...
 
void reconfigureCallback (EBandPlannerConfig &config, uint32_t level)
 Reconfigures node parameters. More...
 

Private Attributes

nav_msgs::Odometry base_odom_
 
costmap_2d::Costmap2DROScostmap_ros_
 pointer to costmap More...
 
boost::shared_ptr< drsdrs_
 dynamic reconfigure server ptr More...
 
boost::shared_ptr< EBandPlannereband_
 
boost::shared_ptr< EBandTrajectoryCtrleband_trj_ctrl_
 
boost::shared_ptr< EBandVisualizationeband_visual_
 
ros::Publisher g_plan_pub_
 publishes modified global plan More...
 
std::vector< geometry_msgs::PoseStamped > global_plan_
 
bool goal_reached_
 
bool initialized_
 
ros::Publisher l_plan_pub_
 publishes prediction for local commands More...
 
boost::mutex odom_mutex_
 
ros::Subscriber odom_sub_
 subscribes to the odometry topic in global namespace More...
 
std::vector< int > plan_start_end_counter_
 
double rot_stopped_vel_
 
tf::TransformListenertf_
 pointer to Transform Listener More...
 
double trans_stopped_vel_
 lower bound for absolute value of velocity (with respect to stick-slip behaviour) More...
 
std::vector< geometry_msgs::PoseStamped > transformed_plan_
 
double xy_goal_tolerance_
 parameters to define region in which goal is treated as reached More...
 
double yaw_goal_tolerance_
 

Additional Inherited Members

- Protected Member Functions inherited from nav_core::BaseLocalPlanner
 BaseLocalPlanner ()
 

Detailed Description

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

Definition at line 85 of file eband_local_planner_ros.h.

Member Typedef Documentation

typedef dynamic_reconfigure::Server< eband_local_planner::EBandPlannerConfig> eband_local_planner::EBandPlannerROS::drs
private

Definition at line 146 of file eband_local_planner_ros.h.

Constructor & Destructor Documentation

eband_local_planner::EBandPlannerROS::EBandPlannerROS ( )

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.

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.

eband_local_planner::EBandPlannerROS::~EBandPlannerROS ( )

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 218 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.

bool eband_local_planner::EBandPlannerROS::isGoalReached ( )
virtual

Check if the goal pose has been achieved.

Returns
True if achieved, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 370 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 405 of file eband_local_planner_ros.cpp.

void eband_local_planner::EBandPlannerROS::reconfigureCallback ( EBandPlannerConfig &  config,
uint32_t  level 
)
private

Reconfigures node parameters.

Parameters
configThe dynamic reconfigure node configuration
levelReconfiguration level

Definition at line 128 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 154 of file eband_local_planner_ros.cpp.

Member Data Documentation

nav_msgs::Odometry eband_local_planner::EBandPlannerROS::base_odom_
private

Definition at line 164 of file eband_local_planner_ros.h.

costmap_2d::Costmap2DROS* eband_local_planner::EBandPlannerROS::costmap_ros_
private

pointer to costmap

Definition at line 151 of file eband_local_planner_ros.h.

boost::shared_ptr<drs> eband_local_planner::EBandPlannerROS::drs_
private

dynamic reconfigure server ptr

Definition at line 148 of file eband_local_planner_ros.h.

boost::shared_ptr<EBandPlanner> eband_local_planner::EBandPlannerROS::eband_
private

Definition at line 170 of file eband_local_planner_ros.h.

boost::shared_ptr<EBandTrajectoryCtrl> eband_local_planner::EBandPlannerROS::eband_trj_ctrl_
private

Definition at line 172 of file eband_local_planner_ros.h.

boost::shared_ptr<EBandVisualization> eband_local_planner::EBandPlannerROS::eband_visual_
private

Definition at line 171 of file eband_local_planner_ros.h.

ros::Publisher eband_local_planner::EBandPlannerROS::g_plan_pub_
private

publishes modified global plan

Definition at line 159 of file eband_local_planner_ros.h.

std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::global_plan_
private

Definition at line 165 of file eband_local_planner_ros.h.

bool eband_local_planner::EBandPlannerROS::goal_reached_
private

Definition at line 174 of file eband_local_planner_ros.h.

bool eband_local_planner::EBandPlannerROS::initialized_
private

Definition at line 177 of file eband_local_planner_ros.h.

ros::Publisher eband_local_planner::EBandPlannerROS::l_plan_pub_
private

publishes prediction for local commands

Definition at line 160 of file eband_local_planner_ros.h.

boost::mutex eband_local_planner::EBandPlannerROS::odom_mutex_
private

Definition at line 178 of file eband_local_planner_ros.h.

ros::Subscriber eband_local_planner::EBandPlannerROS::odom_sub_
private

subscribes to the odometry topic in global namespace

Definition at line 161 of file eband_local_planner_ros.h.

std::vector<int> eband_local_planner::EBandPlannerROS::plan_start_end_counter_
private

Definition at line 167 of file eband_local_planner_ros.h.

double eband_local_planner::EBandPlannerROS::rot_stopped_vel_
private

Definition at line 156 of file eband_local_planner_ros.h.

tf::TransformListener* eband_local_planner::EBandPlannerROS::tf_
private

pointer to Transform Listener

Definition at line 152 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 156 of file eband_local_planner_ros.h.

std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::transformed_plan_
private

Definition at line 166 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 155 of file eband_local_planner_ros.h.

double eband_local_planner::EBandPlannerROS::yaw_goal_tolerance_
private

Definition at line 155 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, Piyush Khandelwal
autogenerated on Sat Feb 22 2020 04:03:28