pose_follower.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 *********************************************************************/
37 #include <nav_msgs/Path.h>
40 
42 
43 namespace pose_follower {
44  PoseFollower::PoseFollower(): tf_(NULL), costmap_ros_(NULL) {}
45 
47  tf_ = tf;
48  costmap_ros_ = costmap_ros;
51  ros::NodeHandle node_private("~/" + name);
52 
54 
55  node_private.param("k_trans", K_trans_, 2.0);
56  node_private.param("k_rot", K_rot_, 2.0);
57 
58  //within this distance to the goal, finally rotate to the goal heading (also, we've reached our goal only if we're within this dist)
59  node_private.param("tolerance_trans", tolerance_trans_, 0.02);
60 
61  //we've reached our goal only if we're within this angular distance
62  node_private.param("tolerance_rot", tolerance_rot_, 0.04);
63 
64  //we've reached our goal only if we're within range for this long and stopped
65  node_private.param("tolerance_timeout", tolerance_timeout_, 0.5);
66 
67  //set this to true if you're using a holonomic robot
68  node_private.param("holonomic", holonomic_, true);
69 
70  //number of samples (scaling factors of our current desired twist) to check the validity of
71  node_private.param("samples", samples_, 10);
72 
73  //go no faster than this
74  node_private.param("max_vel_lin", max_vel_lin_, 0.9);
75  node_private.param("max_vel_th", max_vel_th_, 1.4);
76 
77  //minimum velocities to keep from getting stuck
78  node_private.param("min_vel_lin", min_vel_lin_, 0.1);
79  node_private.param("min_vel_th", min_vel_th_, 0.0);
80 
81  //if we're rotating in place, go at least this fast to avoid getting stuck
82  node_private.param("min_in_place_vel_th", min_in_place_vel_th_, 0.0);
83 
84  //when we're near the end and would be trying to go no faster than this translationally, just rotate in place instead
85  node_private.param("in_place_trans_vel", in_place_trans_vel_, 0.0);
86 
87  //we're "stopped" if we're going slower than these velocities
88  node_private.param("trans_stopped_velocity", trans_stopped_velocity_, 1e-4);
89  node_private.param("rot_stopped_velocity", rot_stopped_velocity_, 1e-4);
90 
91  //if this is true, we don't care whether we go backwards or forwards
92  node_private.param("allow_backwards", allow_backwards_, false);
93 
94  //if this is true, turn in place to face the new goal instead of arcing toward it
95  node_private.param("turn_in_place_first", turn_in_place_first_, false);
96 
97  //if turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location
98  node_private.param("max_heading_diff_before_moving", max_heading_diff_before_moving_, 0.17);
99 
100  global_plan_pub_ = node_private.advertise<nav_msgs::Path>("global_plan", 1);
101 
102  ros::NodeHandle node;
103  odom_sub_ = node.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&PoseFollower::odomCallback, this, _1));
104  vel_pub_ = node.advertise<geometry_msgs::Twist>("cmd_vel", 10);
105 
106  ROS_DEBUG("Initialized");
107  }
108 
109  void PoseFollower::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){
110  //we assume that the odometry is published in the frame of the base
111  boost::mutex::scoped_lock lock(odom_lock_);
112  base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
113  base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
114  base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
115  ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
116  base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
117  }
118 
119  double PoseFollower::headingDiff(double x, double y, double pt_x, double pt_y, double heading)
120  {
121  double v1_x = x - pt_x;
122  double v1_y = y - pt_y;
123  double v2_x = cos(heading);
124  double v2_y = sin(heading);
125 
126  double perp_dot = v1_x * v2_y - v1_y * v2_x;
127  double dot = v1_x * v2_x + v1_y * v2_y;
128 
129  //get the signed angle
130  double vector_angle = atan2(perp_dot, dot);
131 
132  return -1.0 * vector_angle;
133  }
134 
136  //copy over the odometry information
137  nav_msgs::Odometry base_odom;
138  {
139  boost::mutex::scoped_lock lock(odom_lock_);
140  base_odom = base_odom_;
141  }
142 
143  return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_
144  && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_
145  && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_;
146  }
147 
148  void PoseFollower::publishPlan(const std::vector<geometry_msgs::PoseStamped> &path,
149  const ros::Publisher &pub) {
150  // given an empty path we won't do anything
151  if (path.empty())
152  return;
153 
154  // create a path message
155  nav_msgs::Path gui_path;
156  gui_path.poses.resize(path.size());
157  gui_path.header.frame_id = path[0].header.frame_id;
158  gui_path.header.stamp = path[0].header.stamp;
159 
160  // Extract the plan in world co-ordinates, we assume the path is all in the same frame
161  for (unsigned int i = 0; i < path.size(); i++) {
162  gui_path.poses[i] = path[i];
163  }
164  pub.publish(gui_path);
165  }
166 
167  bool PoseFollower::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
168  //get the current pose of the robot in the fixed frame
169  tf::Stamped<tf::Pose> robot_pose;
170  if(!costmap_ros_->getRobotPose(robot_pose)){
171  ROS_ERROR("Can't get robot pose");
172  geometry_msgs::Twist empty_twist;
173  cmd_vel = empty_twist;
174  return false;
175  }
176 
177  //we want to compute a velocity command based on our current waypoint
178  tf::Stamped<tf::Pose> target_pose;
180 
181  ROS_DEBUG("PoseFollower: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(), tf::getYaw(robot_pose.getRotation()));
182  ROS_DEBUG("PoseFollower: target robot pose %f %f ==> %f", target_pose.getOrigin().x(), target_pose.getOrigin().y(), tf::getYaw(target_pose.getRotation()));
183 
184  //get the difference between the two poses
185  geometry_msgs::Twist diff = diff2D(target_pose, robot_pose);
186  ROS_DEBUG("PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
187 
188  geometry_msgs::Twist limit_vel = limitTwist(diff);
189 
190  geometry_msgs::Twist test_vel = limit_vel;
191  bool legal_traj = collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, true);
192 
193  double scaling_factor = 1.0;
194  double ds = scaling_factor / samples_;
195 
196  //let's make sure that the velocity command is legal... and if not, scale down
197  if(!legal_traj){
198  for(int i = 0; i < samples_; ++i){
199  test_vel.linear.x = limit_vel.linear.x * scaling_factor;
200  test_vel.linear.y = limit_vel.linear.y * scaling_factor;
201  test_vel.angular.z = limit_vel.angular.z * scaling_factor;
202  test_vel = limitTwist(test_vel);
203  if(collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, false)){
204  legal_traj = true;
205  break;
206  }
207  scaling_factor -= ds;
208  }
209  }
210 
211  if(!legal_traj){
212  ROS_ERROR("Not legal (%.2f, %.2f, %.2f)", limit_vel.linear.x, limit_vel.linear.y, limit_vel.angular.z);
213  geometry_msgs::Twist empty_twist;
214  cmd_vel = empty_twist;
215  return false;
216  }
217 
218  //if it is legal... we'll pass it on
219  cmd_vel = test_vel;
220 
221  bool in_goal_position = false;
222  while(fabs(diff.linear.x) <= tolerance_trans_ &&
223  fabs(diff.linear.y) <= tolerance_trans_ &&
224  fabs(diff.angular.z) <= tolerance_rot_)
225  {
226  if(current_waypoint_ < global_plan_.size() - 1)
227  {
228  current_waypoint_++;
229  tf::poseStampedMsgToTF(global_plan_[current_waypoint_], target_pose);
230  diff = diff2D(target_pose, robot_pose);
231  }
232  else
233  {
234  ROS_INFO("Reached goal: %d", current_waypoint_);
235  in_goal_position = true;
236  break;
237  }
238  }
239 
240  //if we're not in the goal position, we need to update time
241  if(!in_goal_position)
243 
244  //check if we've reached our goal for long enough to succeed
246  geometry_msgs::Twist empty_twist;
247  cmd_vel = empty_twist;
248  }
249 
250  return true;
251  }
252 
253  bool PoseFollower::setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan){
254  current_waypoint_ = 0;
257  ROS_ERROR("Could not transform the global plan to the frame of the controller");
258  return false;
259  }
260 
261  ROS_DEBUG("global plan size: %lu", global_plan_.size());
263  return true;
264  }
265 
268  return true;
269  }
270  return false;
271  }
272 
273  geometry_msgs::Twist PoseFollower::diff2D(const tf::Pose& pose1, const tf::Pose& pose2)
274  {
275  geometry_msgs::Twist res;
276  tf::Pose diff = pose2.inverse() * pose1;
277  res.linear.x = diff.getOrigin().x();
278  res.linear.y = diff.getOrigin().y();
279  res.angular.z = tf::getYaw(diff.getRotation());
280 
281  if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_))
282  return res;
283 
284  //in the case that we're not rotating to our goal position and we have a non-holonomic robot
285  //we'll need to command a rotational velocity that will help us reach our desired heading
286 
287  //we want to compute a goal based on the heading difference between our pose and the target
288  double yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(),
289  pose2.getOrigin().x(), pose2.getOrigin().y(), tf::getYaw(pose2.getRotation()));
290 
291  //we'll also check if we can move more effectively backwards
292  if (allow_backwards_)
293  {
294  double neg_yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(),
295  pose2.getOrigin().x(), pose2.getOrigin().y(), M_PI + tf::getYaw(pose2.getRotation()));
296 
297  //check if its faster to just back up
298  if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
299  ROS_DEBUG("Negative is better: %.2f", neg_yaw_diff);
300  yaw_diff = neg_yaw_diff;
301  }
302  }
303 
304  //compute the desired quaterion
305  tf::Quaternion rot_diff = tf::createQuaternionFromYaw(yaw_diff);
306  tf::Quaternion rot = pose2.getRotation() * rot_diff;
307  tf::Pose new_pose = pose1;
308  new_pose.setRotation(rot);
309 
310  diff = pose2.inverse() * new_pose;
311  res.linear.x = diff.getOrigin().x();
312  res.linear.y = diff.getOrigin().y();
313  res.angular.z = tf::getYaw(diff.getRotation());
314  return res;
315  }
316 
317 
318  geometry_msgs::Twist PoseFollower::limitTwist(const geometry_msgs::Twist& twist)
319  {
320  geometry_msgs::Twist res = twist;
321  res.linear.x *= K_trans_;
322  if(!holonomic_)
323  res.linear.y = 0.0;
324  else
325  res.linear.y *= K_trans_;
326  res.angular.z *= K_rot_;
327 
328  //if turn_in_place_first is true, see if we need to rotate in place to face our goal first
329  if (turn_in_place_first_ && fabs(twist.angular.z) > max_heading_diff_before_moving_)
330  {
331  res.linear.x = 0;
332  res.linear.y = 0;
333  if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z);
334  if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
335  return res;
336  }
337 
338  //make sure to bound things by our velocity limits
339  double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
340  double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
341  if (lin_overshoot > 1.0)
342  {
343  res.linear.x /= lin_overshoot;
344  res.linear.y /= lin_overshoot;
345  }
346 
347  //we only want to enforce a minimum velocity if we're not rotating in place
348  if(lin_undershoot > 1.0)
349  {
350  res.linear.x *= lin_undershoot;
351  res.linear.y *= lin_undershoot;
352  }
353 
354  if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z);
355  if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
356  if (std::isnan(res.linear.x))
357  res.linear.x = 0.0;
358  if (std::isnan(res.linear.y))
359  res.linear.y = 0.0;
360 
361  //we want to check for whether or not we're desired to rotate in place
362  if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_){
363  if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
364  res.linear.x = 0.0;
365  res.linear.y = 0.0;
366  }
367 
368  ROS_DEBUG("Angular command %f", res.angular.z);
369  return res;
370  }
371 
372  bool PoseFollower::transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
373  const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
374  std::vector<geometry_msgs::PoseStamped>& transformed_plan){
375  const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
376 
377  transformed_plan.clear();
378 
379  try{
380  if (global_plan.empty())
381  {
382  ROS_ERROR("Recieved plan with zero length");
383  return false;
384  }
385 
386  tf::StampedTransform transform;
387  tf.lookupTransform(global_frame, ros::Time(),
388  plan_pose.header.frame_id, plan_pose.header.stamp,
389  plan_pose.header.frame_id, transform);
390 
391  tf::Stamped<tf::Pose> tf_pose;
392  geometry_msgs::PoseStamped newer_pose;
393  //now we'll transform until points are outside of our distance threshold
394  for(unsigned int i = 0; i < global_plan.size(); ++i){
395  const geometry_msgs::PoseStamped& pose = global_plan[i];
396  poseStampedMsgToTF(pose, tf_pose);
397  tf_pose.setData(transform * tf_pose);
398  tf_pose.stamp_ = transform.stamp_;
399  tf_pose.frame_id_ = global_frame;
400  poseStampedTFToMsg(tf_pose, newer_pose);
401 
402  transformed_plan.push_back(newer_pose);
403  }
404  }
405  catch(tf::LookupException& ex) {
406  ROS_ERROR("No Transform available Error: %s\n", ex.what());
407  return false;
408  }
409  catch(tf::ConnectivityException& ex) {
410  ROS_ERROR("Connectivity Error: %s\n", ex.what());
411  return false;
412  }
413  catch(tf::ExtrapolationException& ex) {
414  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
415  if (!global_plan.empty())
416  ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
417 
418  return false;
419  }
420 
421  return true;
422  }
423 };
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
ros::Publisher global_plan_pub_
Definition: pose_follower.h:79
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
base_local_planner::TrajectoryPlannerROS collision_planner_
Definition: pose_follower.h:96
void publish(const boost::shared_ptr< M > &message) const
void setData(const T &input)
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
static double getYaw(const Quaternion &bt_q)
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double headingDiff(double pt_x, double pt_y, double x, double y, double heading)
tf::TransformListener * tf_
Definition: pose_follower.h:76
tf::TransformListener * tf_
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: pose_follower.h:95
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2DROS &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
static Quaternion createQuaternionFromYaw(double yaw)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Transform inverse() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Quaternion getRotation() const
geometry_msgs::Twist diff2D(const tf::Pose &pose1, const tf::Pose &pose2)
static Time now()
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
costmap_2d::Costmap2DROS * costmap_ros_
Definition: pose_follower.h:77
#define ROS_ERROR(...)
nav_msgs::Odometry base_odom_
Definition: pose_follower.h:91
#define ROS_DEBUG(...)


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Tue Apr 2 2019 02:34:46