Public Member Functions | Private Member Functions | Private Attributes | List of all members
dwa_local_planner::DWAPlannerROS Class Reference

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>

Inheritance diagram for dwa_local_planner::DWAPlannerROS:
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...
 
bool dwaComputeVelocityCommands (geometry_msgs::PoseStamped &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, tf2_ros::Buffer *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...
 
- Public Member Functions inherited from nav_core::BaseLocalPlanner
virtual ~BaseLocalPlanner ()
 

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

Private Attributes

costmap_2d::Costmap2DROScostmap_ros_
 
geometry_msgs::PoseStamped current_pose_
 
dwa_local_planner::DWAPlannerConfig default_config_
 
boost::shared_ptr< DWAPlannerdp_
 The trajectory controller. More...
 
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_
 
tf2_ros::Buffertf_
 Used for transforming point clouds. More...
 

Additional Inherited Members

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

Detailed Description

ROS Wrapper for the DWAPlanner that adheres to the BaseLocalPlanner interface and can be used as a plugin for move_base.

Definition at line 101 of file dwa_planner_ros.h.

Constructor & Destructor Documentation

◆ DWAPlannerROS()

dwa_local_planner::DWAPlannerROS::DWAPlannerROS ( )

Constructor for DWAPlannerROS wrapper.

Definition at line 127 of file dwa_planner_ros.cpp.

◆ ~DWAPlannerROS()

dwa_local_planner::DWAPlannerROS::~DWAPlannerROS ( )

Destructor for the wrapper.

Definition at line 216 of file dwa_planner_ros.cpp.

Member Function Documentation

◆ computeVelocityCommands()

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_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 299 of file dwa_planner_ros.cpp.

◆ dwaComputeVelocityCommands()

bool dwa_local_planner::DWAPlannerROS::dwaComputeVelocityCommands ( geometry_msgs::PoseStamped &  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_velWill 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 223 of file dwa_planner_ros.cpp.

◆ initialize()

void dwa_local_planner::DWAPlannerROS::initialize ( std::string  name,
tf2_ros::Buffer tf,
costmap_2d::Costmap2DROS costmap_ros 
)
virtual

Constructs 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 132 of file dwa_planner_ros.cpp.

◆ isGoalReached()

bool dwa_local_planner::DWAPlannerROS::isGoalReached ( )
virtual

Check if the goal pose has been achieved.

Returns
True if achieved, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 189 of file dwa_planner_ros.cpp.

◆ isInitialized()

bool dwa_local_planner::DWAPlannerROS::isInitialized ( )
inline

Definition at line 154 of file dwa_planner_ros.h.

◆ publishGlobalPlan()

void dwa_local_planner::DWAPlannerROS::publishGlobalPlan ( std::vector< geometry_msgs::PoseStamped > &  path)
private

Definition at line 212 of file dwa_planner_ros.cpp.

◆ publishLocalPlan()

void dwa_local_planner::DWAPlannerROS::publishLocalPlan ( std::vector< geometry_msgs::PoseStamped > &  path)
private

Definition at line 207 of file dwa_planner_ros.cpp.

◆ reconfigureCB()

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 92 of file dwa_planner_ros.cpp.

◆ setPlan()

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_planThe plan to pass to the controller
Returns
True if the plan was updated successfully, false otherwise

Implements nav_core::BaseLocalPlanner.

Definition at line 177 of file dwa_planner_ros.cpp.

Member Data Documentation

◆ costmap_ros_

costmap_2d::Costmap2DROS* dwa_local_planner::DWAPlannerROS::costmap_ros_
private

Definition at line 177 of file dwa_planner_ros.h.

◆ current_pose_

geometry_msgs::PoseStamped dwa_local_planner::DWAPlannerROS::current_pose_
private

Definition at line 182 of file dwa_planner_ros.h.

◆ default_config_

dwa_local_planner::DWAPlannerConfig dwa_local_planner::DWAPlannerROS::default_config_
private

Definition at line 180 of file dwa_planner_ros.h.

◆ dp_

boost::shared_ptr<DWAPlanner> dwa_local_planner::DWAPlannerROS::dp_
private

The trajectory controller.

Definition at line 175 of file dwa_planner_ros.h.

◆ dsrv_

dynamic_reconfigure::Server<DWAPlannerConfig>* dwa_local_planner::DWAPlannerROS::dsrv_
private

Definition at line 179 of file dwa_planner_ros.h.

◆ g_plan_pub_

ros::Publisher dwa_local_planner::DWAPlannerROS::g_plan_pub_
private

Definition at line 171 of file dwa_planner_ros.h.

◆ initialized_

bool dwa_local_planner::DWAPlannerROS::initialized_
private

Definition at line 187 of file dwa_planner_ros.h.

◆ l_plan_pub_

ros::Publisher dwa_local_planner::DWAPlannerROS::l_plan_pub_
private

Definition at line 171 of file dwa_planner_ros.h.

◆ latchedStopRotateController_

base_local_planner::LatchedStopRotateController dwa_local_planner::DWAPlannerROS::latchedStopRotateController_
private

Definition at line 184 of file dwa_planner_ros.h.

◆ odom_helper_

base_local_planner::OdometryHelperRos dwa_local_planner::DWAPlannerROS::odom_helper_
private

Definition at line 190 of file dwa_planner_ros.h.

◆ odom_topic_

std::string dwa_local_planner::DWAPlannerROS::odom_topic_
private

Definition at line 191 of file dwa_planner_ros.h.

◆ planner_util_

base_local_planner::LocalPlannerUtil dwa_local_planner::DWAPlannerROS::planner_util_
private

Definition at line 173 of file dwa_planner_ros.h.

◆ setup_

bool dwa_local_planner::DWAPlannerROS::setup_
private

Definition at line 181 of file dwa_planner_ros.h.

◆ tf_

tf2_ros::Buffer* dwa_local_planner::DWAPlannerROS::tf_
private

Used for transforming point clouds.

Definition at line 168 of file dwa_planner_ros.h.


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


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:33