ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a plugin for move_base.
More...
#include <dwa_planner_ros.h>
|
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...
|
|
bool | dwaComputeVelocityCommands (tf::Stamped< tf::Pose > &global_pose, geometry_msgs::Twist &cmd_vel) |
| Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base, using dynamic window approach. More...
|
|
| DWAPlannerROS () |
| Constructor for DWAPlannerROS wrapper. More...
|
|
void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) |
| Constructs the ros wrapper. More...
|
|
bool | isGoalReached () |
| Check if the goal pose has been achieved. More...
|
|
bool | isInitialized () |
|
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
| Set the plan that the controller is following. More...
|
|
| ~DWAPlannerROS () |
| Destructor for the wrapper. More...
|
|
virtual | ~BaseLocalPlanner () |
|
|
void | publishGlobalPlan (std::vector< geometry_msgs::PoseStamped > &path) |
|
void | publishLocalPlan (std::vector< geometry_msgs::PoseStamped > &path) |
|
void | reconfigureCB (DWAPlannerConfig &config, uint32_t level) |
| Callback to update the local planner's parameters based on dynamic reconfigure. More...
|
|
ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a plugin for move_base.
Definition at line 66 of file dwa_planner_ros.h.
dwa_local_planner::DWAPlannerROS::DWAPlannerROS |
( |
| ) |
|
dwa_local_planner::DWAPlannerROS::~DWAPlannerROS |
( |
| ) |
|
bool dwa_local_planner::DWAPlannerROS::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 254 of file dwa_planner_ros.cpp.
bool dwa_local_planner::DWAPlannerROS::dwaComputeVelocityCommands |
( |
tf::Stamped< tf::Pose > & |
global_pose, |
|
|
geometry_msgs::Twist & |
cmd_vel |
|
) |
| |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base, using dynamic window approach.
- 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
Definition at line 179 of file dwa_planner_ros.cpp.
Constructs 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 94 of file dwa_planner_ros.cpp.
bool dwa_local_planner::DWAPlannerROS::isGoalReached |
( |
| ) |
|
|
virtual |
bool dwa_local_planner::DWAPlannerROS::isInitialized |
( |
| ) |
|
|
inline |
void dwa_local_planner::DWAPlannerROS::publishGlobalPlan |
( |
std::vector< geometry_msgs::PoseStamped > & |
path | ) |
|
|
private |
void dwa_local_planner::DWAPlannerROS::publishLocalPlan |
( |
std::vector< geometry_msgs::PoseStamped > & |
path | ) |
|
|
private |
void dwa_local_planner::DWAPlannerROS::reconfigureCB |
( |
DWAPlannerConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
Callback to update the local planner's parameters based on dynamic reconfigure.
Definition at line 54 of file dwa_planner_ros.cpp.
bool dwa_local_planner::DWAPlannerROS::setPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
orig_global_plan | ) |
|
|
virtual |
Set the plan that the controller is following.
- 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 133 of file dwa_planner_ros.cpp.
dwa_local_planner::DWAPlannerConfig dwa_local_planner::DWAPlannerROS::default_config_ |
|
private |
dynamic_reconfigure::Server<DWAPlannerConfig>* dwa_local_planner::DWAPlannerROS::dsrv_ |
|
private |
bool dwa_local_planner::DWAPlannerROS::initialized_ |
|
private |
std::string dwa_local_planner::DWAPlannerROS::odom_topic_ |
|
private |
bool dwa_local_planner::DWAPlannerROS::setup_ |
|
private |
The documentation for this class was generated from the following files: