Go to the documentation of this file.
37 #ifndef MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_
38 #define MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_
43 #include <boost/thread.hpp>
44 #include <dynamic_reconfigure/Reconfigure.h>
costmap_2d::Costmap2DROS * local_costmap_
std::string max_trans_param_name_
double limited_trans_speed_
ros::Timer distance_check_timer_
double limited_rot_speed_
geometry_msgs::PoseStamped speed_limit_pose_
ros::NodeHandle planner_nh_
void initialize(std::string n, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.
void setRobotSpeed(double trans_speed, double rot_speed)
ros::NodeHandle private_nh_
boost::thread * remove_limit_thread_
ros::ServiceClient planner_dynamic_reconfigure_service_
costmap_2d::Costmap2DROS * global_costmap_
void distanceCheck(const ros::TimerEvent &e)
std::string max_rot_param_name_
double clearing_distance_
void runBehavior()
Run the behavior.
move_slow_and_clear
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:35