46 initialized_(false), remove_limit_thread_(NULL), limit_set_(false){}
48 MoveSlowAndClear::~MoveSlowAndClear()
50 delete remove_limit_thread_;
57 global_costmap_ = global_costmap;
58 local_costmap_ = local_costmap;
61 private_nh_.param(
"clearing_distance", clearing_distance_, 0.5);
62 private_nh_.param(
"limited_trans_speed", limited_trans_speed_, 0.25);
63 private_nh_.param(
"limited_rot_speed", limited_rot_speed_, 0.45);
64 private_nh_.param(
"limited_distance", limited_distance_, 0.3);
65 private_nh_.param(
"max_trans_param_name", max_trans_param_name_, std::string(
"max_trans_vel"));
66 private_nh_.param(
"max_rot_param_name", max_rot_param_name_, std::string(
"max_rot_vel"));
68 std::string planner_namespace;
69 private_nh_.param(
"planner_namespace", planner_namespace, std::string(
"DWAPlannerROS"));
71 planner_dynamic_reconfigure_service_ = planner_nh_.serviceClient<dynamic_reconfigure::Reconfigure>(
"set_parameters",
true);
75 void MoveSlowAndClear::runBehavior()
79 ROS_ERROR(
"This recovery behavior has not been initialized, doing nothing.");
82 ROS_WARN(
"Move slow and clear recovery behavior started.");
83 geometry_msgs::PoseStamped global_pose, local_pose;
84 global_costmap_->getRobotPose(global_pose);
85 local_costmap_->getRobotPose(local_pose);
87 std::vector<geometry_msgs::Point> global_poly, local_poly;
88 geometry_msgs::Point pt;
90 for(
int i = -1; i <= 1; i+=2)
92 pt.x = global_pose.pose.position.x + i * clearing_distance_;
93 pt.y = global_pose.pose.position.y + i * clearing_distance_;
94 global_poly.push_back(pt);
96 pt.x = global_pose.pose.position.x + i * clearing_distance_;
97 pt.y = global_pose.pose.position.y + -1.0 * i * clearing_distance_;
98 global_poly.push_back(pt);
100 pt.x = local_pose.pose.position.x + i * clearing_distance_;
101 pt.y = local_pose.pose.position.y + i * clearing_distance_;
102 local_poly.push_back(pt);
104 pt.x = local_pose.pose.position.x + i * clearing_distance_;
105 pt.y = local_pose.pose.position.y + -1.0 * i * clearing_distance_;
106 local_poly.push_back(pt);
110 std::vector<boost::shared_ptr<costmap_2d::Layer> >* plugins = global_costmap_->getLayeredCostmap()->getPlugins();
113 if(plugin->getName().find(
"obstacles")!=std::string::npos){
115 costmap = boost::static_pointer_cast<costmap_2d::ObstacleLayer>(plugin);
120 plugins = local_costmap_->getLayeredCostmap()->getPlugins();
123 if(plugin->getName().find(
"obstacles")!=std::string::npos){
125 costmap = boost::static_pointer_cast<costmap_2d::ObstacleLayer>(plugin);
131 boost::mutex::scoped_lock l(mutex_);
136 if(!planner_nh_.getParam(max_trans_param_name_, old_trans_speed_))
138 ROS_ERROR(
"The planner %s, does not have the parameter %s", planner_nh_.getNamespace().c_str(), max_trans_param_name_.c_str());
141 if(!planner_nh_.getParam(max_rot_param_name_, old_rot_speed_))
143 ROS_ERROR(
"The planner %s, does not have the parameter %s", planner_nh_.getNamespace().c_str(), max_rot_param_name_.c_str());
148 speed_limit_pose_ = global_pose;
151 setRobotSpeed(limited_trans_speed_, limited_rot_speed_);
153 distance_check_timer_ = private_nh_.createTimer(
ros::Duration(0.1), &MoveSlowAndClear::distanceCheck,
this);
156 double MoveSlowAndClear::getSqDistance()
158 geometry_msgs::PoseStamped global_pose;
159 global_costmap_->getRobotPose(global_pose);
160 double x1 = global_pose.pose.position.x;
161 double y1 = global_pose.pose.position.y;
163 double x2 = speed_limit_pose_.pose.position.x;
164 double y2 = speed_limit_pose_.pose.position.y;
166 return (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1);
171 if(limited_distance_ * limited_distance_ <= getSqDistance())
173 ROS_INFO(
"Moved far enough, removing speed limit.");
175 if(remove_limit_thread_)
177 remove_limit_thread_->join();
178 delete remove_limit_thread_;
180 remove_limit_thread_ =
new boost::thread(boost::bind(&MoveSlowAndClear::removeSpeedLimit,
this));
182 distance_check_timer_.stop();
186 void MoveSlowAndClear::removeSpeedLimit()
188 boost::mutex::scoped_lock l(mutex_);
189 setRobotSpeed(old_trans_speed_, old_rot_speed_);
193 void MoveSlowAndClear::setRobotSpeed(
double trans_speed,
double rot_speed)
197 dynamic_reconfigure::Reconfigure vel_reconfigure;
198 dynamic_reconfigure::DoubleParameter new_trans;
199 new_trans.name = max_trans_param_name_;
200 new_trans.value = trans_speed;
201 vel_reconfigure.request.config.doubles.push_back(new_trans);
203 planner_dynamic_reconfigure_service_.call(vel_reconfigure);
207 ROS_ERROR(
"Something went wrong in the service call to dynamic_reconfigure");
211 dynamic_reconfigure::Reconfigure rot_reconfigure;
212 dynamic_reconfigure::DoubleParameter new_rot;
213 new_rot.name = max_rot_param_name_;
214 new_rot.value = rot_speed;
215 rot_reconfigure.request.config.doubles.push_back(new_rot);
217 planner_dynamic_reconfigure_service_.call(rot_reconfigure);
221 ROS_ERROR(
"Something went wrong in the service call to dynamic_reconfigure");