move_slow_and_clear.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
40 
42 
43 namespace move_slow_and_clear
44 {
45  MoveSlowAndClear::MoveSlowAndClear():global_costmap_(NULL), local_costmap_(NULL),
46  initialized_(false), remove_limit_thread_(NULL), limit_set_(false){}
47 
49  {
50  delete remove_limit_thread_;
51  }
52 
54  costmap_2d::Costmap2DROS* global_costmap,
55  costmap_2d::Costmap2DROS* local_costmap)
56  {
57  global_costmap_ = global_costmap;
58  local_costmap_ = local_costmap;
59 
60  ros::NodeHandle private_nh_("~/" + n);
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 
66  std::string planner_namespace;
67  private_nh_.param("planner_namespace", planner_namespace, std::string("DWAPlannerROS"));
68  planner_nh_ = ros::NodeHandle("~/" + planner_namespace);
69  planner_dynamic_reconfigure_service_ = planner_nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters", true);
70  initialized_ = true;
71  }
72 
74  {
75  if(!initialized_)
76  {
77  ROS_ERROR("This recovery behavior has not been initialized, doing nothing.");
78  return;
79  }
80  ROS_WARN("Move slow and clear recovery behavior started.");
81  tf::Stamped<tf::Pose> global_pose, local_pose;
82  global_costmap_->getRobotPose(global_pose);
83  local_costmap_->getRobotPose(local_pose);
84 
85  std::vector<geometry_msgs::Point> global_poly, local_poly;
86  geometry_msgs::Point pt;
87 
88  for(int i = -1; i <= 1; i+=2)
89  {
90  pt.x = global_pose.getOrigin().x() + i * clearing_distance_;
91  pt.y = global_pose.getOrigin().y() + i * clearing_distance_;
92  global_poly.push_back(pt);
93 
94  pt.x = global_pose.getOrigin().x() + i * clearing_distance_;
95  pt.y = global_pose.getOrigin().y() + -1.0 * i * clearing_distance_;
96  global_poly.push_back(pt);
97 
98  pt.x = local_pose.getOrigin().x() + i * clearing_distance_;
99  pt.y = local_pose.getOrigin().y() + i * clearing_distance_;
100  local_poly.push_back(pt);
101 
102  pt.x = local_pose.getOrigin().x() + i * clearing_distance_;
103  pt.y = local_pose.getOrigin().y() + -1.0 * i * clearing_distance_;
104  local_poly.push_back(pt);
105  }
106 
107  //clear the desired space in the costmaps
108  std::vector<boost::shared_ptr<costmap_2d::Layer> >* plugins = global_costmap_->getLayeredCostmap()->getPlugins();
109  for (std::vector<boost::shared_ptr<costmap_2d::Layer> >::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) {
110  boost::shared_ptr<costmap_2d::Layer> plugin = *pluginp;
111  if(plugin->getName().find("obstacles")!=std::string::npos){
113  costmap = boost::static_pointer_cast<costmap_2d::ObstacleLayer>(plugin);
114  costmap->setConvexPolygonCost(global_poly, costmap_2d::FREE_SPACE);
115  }
116  }
117 
119  for (std::vector<boost::shared_ptr<costmap_2d::Layer> >::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) {
120  boost::shared_ptr<costmap_2d::Layer> plugin = *pluginp;
121  if(plugin->getName().find("obstacles")!=std::string::npos){
123  costmap = boost::static_pointer_cast<costmap_2d::ObstacleLayer>(plugin);
124  costmap->setConvexPolygonCost(local_poly, costmap_2d::FREE_SPACE);
125  }
126  }
127 
128  //lock... just in case we're already speed limited
129  boost::mutex::scoped_lock l(mutex_);
130 
131  //get the old maximum speed for the robot... we'll want to set it back
132  if(!limit_set_)
133  {
134  if(!planner_nh_.getParam("max_trans_vel", old_trans_speed_))
135  {
136  ROS_ERROR("The planner %s, does not have the parameter max_trans_vel", planner_nh_.getNamespace().c_str());
137  }
138 
139  if(!planner_nh_.getParam("max_rot_vel", old_rot_speed_))
140  {
141  ROS_ERROR("The planner %s, does not have the parameter max_rot_vel", planner_nh_.getNamespace().c_str());
142  }
143  }
144 
145  //we also want to save our current position so that we can remove the speed limit we impose later on
146  speed_limit_pose_ = global_pose;
147 
148  //limit the speed of the robot until it moves a certain distance
150  limit_set_ = true;
152  }
153 
155  {
156  tf::Stamped<tf::Pose> global_pose;
157  global_costmap_->getRobotPose(global_pose);
158  double x1 = global_pose.getOrigin().x();
159  double y1 = global_pose.getOrigin().y();
160 
161  double x2 = speed_limit_pose_.getOrigin().x();
162  double y2 = speed_limit_pose_.getOrigin().y();
163 
164  return (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1);
165  }
166 
168  {
170  {
171  ROS_INFO("Moved far enough, removing speed limit.");
172  //have to do this because a system call within a timer cb does not seem to play nice
174  {
175  remove_limit_thread_->join();
176  delete remove_limit_thread_;
177  }
178  remove_limit_thread_ = new boost::thread(boost::bind(&MoveSlowAndClear::removeSpeedLimit, this));
179 
181  }
182  }
183 
185  {
186  boost::mutex::scoped_lock l(mutex_);
188  limit_set_ = false;
189  }
190 
191  void MoveSlowAndClear::setRobotSpeed(double trans_speed, double rot_speed)
192  {
193 
194  {
195  dynamic_reconfigure::Reconfigure vel_reconfigure;
196  dynamic_reconfigure::DoubleParameter new_trans;
197  new_trans.name = "max_trans_vel";
198  new_trans.value = trans_speed;
199  vel_reconfigure.request.config.doubles.push_back(new_trans);
200  try {
202  ROS_INFO_STREAM("Recovery setting trans vel: " << trans_speed);
203  }
204  catch(...) {
205  ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure");
206  }
207  }
208  {
209  dynamic_reconfigure::Reconfigure rot_reconfigure;
210  dynamic_reconfigure::DoubleParameter new_rot;
211  new_rot.name = "max_rot_vel";
212  new_rot.value = rot_speed;
213  rot_reconfigure.request.config.doubles.push_back(new_rot);
214  try {
216  ROS_INFO_STREAM("Recovery setting rot vel: " << rot_speed);
217  }
218  catch(...) {
219  ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure");
220  }
221  }
222  }
223 };
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
costmap_2d::Costmap2DROS * local_costmap_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
void stop()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
bool call(MReq &req, MRes &res)
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.
std::vector< boost::shared_ptr< Layer > > * getPlugins()
static const unsigned char FREE_SPACE
#define ROS_WARN(...)
void setRobotSpeed(double trans_speed, double rot_speed)
void distanceCheck(const ros::TimerEvent &e)
#define ROS_INFO(...)
costmap_2d::Costmap2DROS * global_costmap_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
const std::string & getNamespace() const
ros::ServiceClient planner_dynamic_reconfigure_service_
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)
LayeredCostmap * getLayeredCostmap()


move_slow_and_clear
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:37