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


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Jun 22 2020 03:18:15