Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <move_slow_and_clear/move_slow_and_clear.h>
00038 #include <pluginlib/class_list_macros.h>
00039
00040 PLUGINLIB_EXPORT_CLASS(move_slow_and_clear::MoveSlowAndClear,
00041 nav_core::RecoveryBehavior)
00042
00043 namespace move_slow_and_clear
00044 {
00045 MoveSlowAndClear::MoveSlowAndClear():global_costmap_(NULL), local_costmap_(NULL),
00046 initialized_(false), remove_limit_thread_(NULL), limit_set_(false){}
00047
00048 MoveSlowAndClear::~MoveSlowAndClear()
00049 {
00050 delete remove_limit_thread_;
00051 }
00052
00053 void MoveSlowAndClear::initialize (std::string n, tf::TransformListener* tf,
00054 costmap_2d::Costmap2DROS* global_costmap,
00055 costmap_2d::Costmap2DROS* local_costmap)
00056 {
00057 global_costmap_ = global_costmap;
00058 local_costmap_ = local_costmap;
00059
00060 ros::NodeHandle private_nh_("~/" + n);
00061 private_nh_.param("clearing_distance", clearing_distance_, 0.5);
00062 private_nh_.param("limited_trans_speed", limited_trans_speed_, 0.25);
00063 private_nh_.param("limited_rot_speed", limited_rot_speed_, 0.45);
00064 private_nh_.param("limited_distance", limited_distance_, 0.3);
00065
00066 std::string planner_namespace;
00067 private_nh_.param("planner_namespace", planner_namespace, std::string("DWAPlannerROS"));
00068 planner_nh_ = ros::NodeHandle("~/" + planner_namespace);
00069 planner_dynamic_reconfigure_service_ = planner_nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters", true);
00070 initialized_ = true;
00071 }
00072
00073 void MoveSlowAndClear::runBehavior()
00074 {
00075 if(!initialized_)
00076 {
00077 ROS_ERROR("This recovery behavior has not been initialized, doing nothing.");
00078 return;
00079 }
00080 ROS_WARN("Move slow and clear recovery behavior started.");
00081 tf::Stamped<tf::Pose> global_pose, local_pose;
00082 global_costmap_->getRobotPose(global_pose);
00083 local_costmap_->getRobotPose(local_pose);
00084
00085 std::vector<geometry_msgs::Point> global_poly, local_poly;
00086
00087 geometry_msgs::Point pt;
00088 for(int i = -1; i <= 1; i+=2)
00089 {
00090 pt.x = global_pose.getOrigin().x() + i * clearing_distance_;
00091 pt.y = global_pose.getOrigin().y() + i * clearing_distance_;
00092 global_poly.push_back(pt);
00093
00094 pt.x = global_pose.getOrigin().x() + i * clearing_distance_;
00095 pt.y = global_pose.getOrigin().y() + -1.0 * i * clearing_distance_;
00096 global_poly.push_back(pt);
00097
00098 pt.x = local_pose.getOrigin().x() + i * clearing_distance_;
00099 pt.y = local_pose.getOrigin().y() + i * clearing_distance_;
00100 local_poly.push_back(pt);
00101
00102 pt.x = local_pose.getOrigin().x() + i * clearing_distance_;
00103 pt.y = local_pose.getOrigin().y() + -1.0 * i * clearing_distance_;
00104 local_poly.push_back(pt);
00105 }
00106
00107
00108 global_costmap_->setConvexPolygonCost(global_poly, costmap_2d::FREE_SPACE);
00109 local_costmap_->setConvexPolygonCost(local_poly, costmap_2d::FREE_SPACE);
00110
00111
00112 boost::mutex::scoped_lock l(mutex_);
00113
00114
00115 if(!limit_set_)
00116 {
00117 if(!planner_nh_.getParam("max_trans_vel", old_trans_speed_))
00118 {
00119 ROS_ERROR("The planner %s, does not have the parameter max_trans_vel", planner_nh_.getNamespace().c_str());
00120 }
00121
00122 if(!planner_nh_.getParam("max_rot_vel", old_rot_speed_))
00123 {
00124 ROS_ERROR("The planner %s, does not have the parameter max_rot_vel", planner_nh_.getNamespace().c_str());
00125 }
00126 }
00127
00128
00129 speed_limit_pose_ = global_pose;
00130
00131
00132 setRobotSpeed(limited_trans_speed_, limited_rot_speed_);
00133 limit_set_ = true;
00134 distance_check_timer_ = private_nh_.createTimer(ros::Duration(0.1), &MoveSlowAndClear::distanceCheck, this);
00135 }
00136
00137 double MoveSlowAndClear::getSqDistance()
00138 {
00139 tf::Stamped<tf::Pose> global_pose;
00140 global_costmap_->getRobotPose(global_pose);
00141 double x1 = global_pose.getOrigin().x();
00142 double y1 = global_pose.getOrigin().y();
00143
00144 double x2 = speed_limit_pose_.getOrigin().x();
00145 double y2 = speed_limit_pose_.getOrigin().y();
00146
00147 return (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1);
00148 }
00149
00150 void MoveSlowAndClear::distanceCheck(const ros::TimerEvent& e)
00151 {
00152 if(limited_distance_ * limited_distance_ <= getSqDistance())
00153 {
00154 ROS_INFO("Moved far enough, removing speed limit.");
00155
00156 if(remove_limit_thread_)
00157 {
00158 remove_limit_thread_->join();
00159 delete remove_limit_thread_;
00160 }
00161 remove_limit_thread_ = new boost::thread(boost::bind(&MoveSlowAndClear::removeSpeedLimit, this));
00162
00163 distance_check_timer_.stop();
00164 }
00165 }
00166
00167 void MoveSlowAndClear::removeSpeedLimit()
00168 {
00169 boost::mutex::scoped_lock l(mutex_);
00170 setRobotSpeed(old_trans_speed_, old_rot_speed_);
00171 limit_set_ = false;
00172 }
00173
00174 void MoveSlowAndClear::setRobotSpeed(double trans_speed, double rot_speed)
00175 {
00176
00177 {
00178 dynamic_reconfigure::Reconfigure vel_reconfigure;
00179 dynamic_reconfigure::DoubleParameter new_trans;
00180 new_trans.name = "max_trans_vel";
00181 new_trans.value = trans_speed;
00182 vel_reconfigure.request.config.doubles.push_back(new_trans);
00183 try {
00184 planner_dynamic_reconfigure_service_.call(vel_reconfigure);
00185 ROS_INFO_STREAM("Recovery setting trans vel: " << trans_speed);
00186 }
00187 catch(...) {
00188 ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure");
00189 }
00190 }
00191 {
00192 dynamic_reconfigure::Reconfigure rot_reconfigure;
00193 dynamic_reconfigure::DoubleParameter new_rot;
00194 new_rot.name = "max_rot_vel";
00195 new_rot.value = rot_speed;
00196 rot_reconfigure.request.config.doubles.push_back(new_rot);
00197 try {
00198 planner_dynamic_reconfigure_service_.call(rot_reconfigure);
00199 ROS_INFO_STREAM("Recovery setting rot vel: " << rot_speed);
00200 }
00201 catch(...) {
00202 ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure");
00203 }
00204 }
00205 }
00206 };