Plugin to the ros base_local_planner. Implements a wrapper for the Elastic Band Method.
More...
#include <eband_local_planner_ros.h>
|
typedef dynamic_reconfigure::Server< eband_local_planner::EBandPlannerConfig > | drs |
|
|
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...
|
|
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.
eband_local_planner::EBandPlannerROS::EBandPlannerROS |
( |
| ) |
|
Constructs the ros wrapper.
- Parameters
-
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.
eband_local_planner::EBandPlannerROS::~EBandPlannerROS |
( |
| ) |
|
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_vel | Will 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.
Initializes the ros wrapper.
- Parameters
-
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 |
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
-
Pointer | to 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
-
config | The dynamic reconfigure node configuration |
level | Reconfiguration 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_plan | The 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.
nav_msgs::Odometry eband_local_planner::EBandPlannerROS::base_odom_ |
|
private |
std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::global_plan_ |
|
private |
bool eband_local_planner::EBandPlannerROS::goal_reached_ |
|
private |
bool eband_local_planner::EBandPlannerROS::initialized_ |
|
private |
boost::mutex eband_local_planner::EBandPlannerROS::odom_mutex_ |
|
private |
std::vector<int> eband_local_planner::EBandPlannerROS::plan_start_end_counter_ |
|
private |
double eband_local_planner::EBandPlannerROS::rot_stopped_vel_ |
|
private |
double eband_local_planner::EBandPlannerROS::trans_stopped_vel_ |
|
private |
std::vector<geometry_msgs::PoseStamped> eband_local_planner::EBandPlannerROS::transformed_plan_ |
|
private |
double eband_local_planner::EBandPlannerROS::xy_goal_tolerance_ |
|
private |
double eband_local_planner::EBandPlannerROS::yaw_goal_tolerance_ |
|
private |
The documentation for this class was generated from the following files: