Go to the documentation of this file.
37 #ifndef DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
38 #define DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
40 #include <boost/shared_ptr.hpp>
41 #include <boost/thread.hpp>
45 #include <dynamic_reconfigure/server.h>
46 #include <dwa_local_planner/DWAPlannerConfig.h>
50 #include <nav_msgs/Odometry.h>
109 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
127 void reconfigureCB(DWAPlannerConfig &config, uint32_t level);
144 dynamic_reconfigure::Server<DWAPlannerConfig> *
dsrv_;
tf2_ros::Buffer * tf_
Used for transforming point clouds.
base_local_planner::OdometryHelperRos odom_helper_
dwa_local_planner::DWAPlannerConfig default_config_
ros::Publisher l_plan_pub_
void reconfigureCB(DWAPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
base_local_planner::LatchedStopRotateController latchedStopRotateController_
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
~DWAPlannerROS()
Destructor for the wrapper.
geometry_msgs::PoseStamped current_pose_
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
void publishLocalPlan(std::vector< geometry_msgs::PoseStamped > &path)
ros::Publisher g_plan_pub_
DWAPlannerROS()
Constructor for DWAPlannerROS wrapper.
void publishGlobalPlan(std::vector< geometry_msgs::PoseStamped > &path)
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...
boost::shared_ptr< DWAPlanner > dp_
The trajectory controller.
costmap_2d::Costmap2DROS * costmap_ros_
bool isGoalReached()
Check if the goal pose has been achieved.
dynamic_reconfigure::Server< DWAPlannerConfig > * dsrv_
base_local_planner::LocalPlannerUtil planner_util_
dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:33