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


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Aug 26 2022 02:17:51