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>
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. | |
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. | |
DWAPlannerROS () | |
Constructor for DWAPlannerROS wrapper. | |
void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) |
Constructs the ros wrapper. | |
bool | isGoalReached () |
Check if the goal pose has been achieved. | |
bool | isInitialized () |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
Set the plan that the controller is following. | |
~DWAPlannerROS () | |
Destructor for the wrapper. | |
Private Member Functions | |
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. | |
Private Attributes | |
costmap_2d::Costmap2DROS * | costmap_ros_ |
tf::Stamped< tf::Pose > | current_pose_ |
dwa_local_planner::DWAPlannerConfig | default_config_ |
boost::shared_ptr< DWAPlanner > | dp_ |
The trajectory controller. | |
dynamic_reconfigure::Server < DWAPlannerConfig > * | dsrv_ |
ros::Publisher | g_plan_pub_ |
bool | initialized_ |
ros::Publisher | l_plan_pub_ |
base_local_planner::LatchedStopRotateController | latchedStopRotateController_ |
base_local_planner::OdometryHelperRos | odom_helper_ |
std::string | odom_topic_ |
base_local_planner::LocalPlannerUtil | planner_util_ |
bool | setup_ |
tf::TransformListener * | tf_ |
Used for transforming point clouds. |
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.
Constructor for DWAPlannerROS wrapper.
Definition at line 89 of file dwa_planner_ros.cpp.
Destructor for the wrapper.
Definition at line 170 of file dwa_planner_ros.cpp.
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.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Implements nav_core::BaseLocalPlanner.
Definition at line 252 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.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Definition at line 177 of file dwa_planner_ros.cpp.
void dwa_local_planner::DWAPlannerROS::initialize | ( | std::string | name, |
tf::TransformListener * | tf, | ||
costmap_2d::Costmap2DROS * | costmap_ros | ||
) | [virtual] |
Constructs 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 94 of file dwa_planner_ros.cpp.
bool dwa_local_planner::DWAPlannerROS::isGoalReached | ( | ) | [virtual] |
Check if the goal pose has been achieved.
Implements nav_core::BaseLocalPlanner.
Definition at line 143 of file dwa_planner_ros.cpp.
bool dwa_local_planner::DWAPlannerROS::isInitialized | ( | ) | [inline] |
Definition at line 119 of file dwa_planner_ros.h.
void dwa_local_planner::DWAPlannerROS::publishGlobalPlan | ( | std::vector< geometry_msgs::PoseStamped > & | path | ) | [private] |
Definition at line 166 of file dwa_planner_ros.cpp.
void dwa_local_planner::DWAPlannerROS::publishLocalPlan | ( | std::vector< geometry_msgs::PoseStamped > & | path | ) | [private] |
Definition at line 161 of file dwa_planner_ros.cpp.
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.
orig_global_plan | The plan to pass to the controller |
Implements nav_core::BaseLocalPlanner.
Definition at line 131 of file dwa_planner_ros.cpp.
Definition at line 142 of file dwa_planner_ros.h.
Definition at line 147 of file dwa_planner_ros.h.
dwa_local_planner::DWAPlannerConfig dwa_local_planner::DWAPlannerROS::default_config_ [private] |
Definition at line 145 of file dwa_planner_ros.h.
boost::shared_ptr<DWAPlanner> dwa_local_planner::DWAPlannerROS::dp_ [private] |
The trajectory controller.
Definition at line 140 of file dwa_planner_ros.h.
dynamic_reconfigure::Server<DWAPlannerConfig>* dwa_local_planner::DWAPlannerROS::dsrv_ [private] |
Definition at line 144 of file dwa_planner_ros.h.
Definition at line 136 of file dwa_planner_ros.h.
bool dwa_local_planner::DWAPlannerROS::initialized_ [private] |
Definition at line 152 of file dwa_planner_ros.h.
Definition at line 136 of file dwa_planner_ros.h.
base_local_planner::LatchedStopRotateController dwa_local_planner::DWAPlannerROS::latchedStopRotateController_ [private] |
Definition at line 149 of file dwa_planner_ros.h.
Definition at line 155 of file dwa_planner_ros.h.
std::string dwa_local_planner::DWAPlannerROS::odom_topic_ [private] |
Definition at line 156 of file dwa_planner_ros.h.
Definition at line 138 of file dwa_planner_ros.h.
bool dwa_local_planner::DWAPlannerROS::setup_ [private] |
Definition at line 146 of file dwa_planner_ros.h.
Used for transforming point clouds.
Definition at line 133 of file dwa_planner_ros.h.