trajectory_tracker.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, ATR, Atsushi Watanabe
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * This research was supported by a contract with the Ministry of Internal
32  Affairs and Communications entitled, 'Novel and innovative R&D making use
33  of brain structures'
34 
35  This software was implemented to accomplish the above research.
36  Original idea of the implemented control scheme was published on:
37  S. Iida, S. Yuta, "Vehicle command system and trajectory control for
38  autonomous mobile robots," in Proceedings of the 1991 IEEE/RSJ
39  International Workshop on Intelligent Robots and Systems (IROS),
40  1991, pp. 212-217.
41  */
42 
43 #include <algorithm>
44 #include <cmath>
45 #include <limits>
46 #include <string>
47 #include <vector>
48 
49 #include <Eigen/Core>
50 #include <Eigen/Geometry>
51 
52 #include <ros/ros.h>
53 
54 #include <dynamic_reconfigure/server.h>
55 #include <geometry_msgs/PoseStamped.h>
56 #include <geometry_msgs/Twist.h>
57 #include <nav_msgs/Odometry.h>
58 #include <nav_msgs/Path.h>
59 #include <std_msgs/Float32.h>
60 #include <std_msgs/Header.h>
61 
62 #include <tf2/utils.h>
65 
67 #include <trajectory_tracker_msgs/PathWithVelocity.h>
68 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
69 
70 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
74 
75 namespace trajectory_tracker
76 {
78 {
79 public:
80  TrackerNode();
81  ~TrackerNode();
82  void spin();
83 
84 private:
85  std::string topic_path_;
86  std::string topic_cmd_vel_;
87  std::string frame_robot_;
88  std::string frame_odom_;
89  double hz_;
90  double look_forward_;
91  double curv_forward_;
92  double k_[3];
93  double gain_at_vel_;
94  double d_lim_;
95  double d_stop_;
96  double vel_[2];
97  double acc_[2];
98  double acc_toc_[2];
101  double rotate_ang_;
113  double epsilon_;
114  double max_dt_;
121 
135 
137  std_msgs::Header path_header_;
139 
140  mutable boost::recursive_mutex parameter_server_mutex_;
141  dynamic_reconfigure::Server<TrajectoryTrackerConfig> parameter_server_;
142 
143  bool use_odom_;
146 
148  {
149  explicit TrackingResult(const int s)
150  : status(s)
151  , distance_remains(0.0)
152  , angle_remains(0.0)
153  , distance_remains_raw(0.0)
154  , angle_remains_raw(0.0)
155  , turning_in_place(false)
156  , signed_local_distance(0.0)
157  , distance_from_target(0.0)
158  , target_linear_vel(0.0)
159  , tracking_point_x(0.0)
160  , tracking_point_y(0.0)
161  , tracking_point_curv(0.0)
162  , path_step_done(0)
163  {
164  }
165 
166  int status; // same as trajectory_tracker_msgs::TrajectoryTrackerStatus::status
169  double distance_remains_raw; // remained distance without prediction
179  };
180 
181  template <typename MSG_TYPE>
182  void cbPath(const typename MSG_TYPE::ConstPtr&);
183  void cbSpeed(const std_msgs::Float32::ConstPtr&);
184  void cbOdometry(const nav_msgs::Odometry::ConstPtr&);
185  void cbTimer(const ros::TimerEvent&);
186  void cbOdomTimeout(const ros::TimerEvent&);
187  void control(const tf2::Stamped<tf2::Transform>&, const Eigen::Vector3d&, const double, const double, const double);
189  const tf2::Stamped<tf2::Transform>&, const Eigen::Vector3d&, const double, const double) const;
190  void cbParameter(const TrajectoryTrackerConfig& config, const uint32_t /* level */);
191 };
192 
194  : nh_()
195  , pnh_("~")
196  , tfl_(tfbuf_)
197  , is_path_updated_(false)
198 {
200  pnh_.param("frame_robot", frame_robot_, std::string("base_link"));
201  pnh_.param("frame_odom", frame_odom_, std::string("odom"));
202  neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("path"));
203  neonavigation_common::compat::deprecatedParam(pnh_, "cmd_vel", topic_cmd_vel_, std::string("cmd_vel"));
204  pnh_.param("hz", hz_, 50.0);
205  pnh_.param("use_odom", use_odom_, false);
206  pnh_.param("predict_odom", predict_odom_, true);
207  pnh_.param("max_dt", max_dt_, 0.1);
208  pnh_.param("odom_timeout_sec", odom_timeout_sec_, 0.1);
209 
210  sub_path_ = neonavigation_common::compat::subscribe<nav_msgs::Path>(
211  nh_, "path",
212  pnh_, topic_path_, 2,
213  boost::bind(&TrackerNode::cbPath<nav_msgs::Path>, this, _1));
214  sub_path_velocity_ = nh_.subscribe<trajectory_tracker_msgs::PathWithVelocity>(
215  "path_velocity", 2,
216  boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>, this, _1));
218  nh_, "speed",
219  pnh_, "speed", 20, &TrackerNode::cbSpeed, this);
220  pub_vel_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
221  nh_, "cmd_vel",
222  pnh_, topic_cmd_vel_, 10);
223  pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>("status", 10, true);
224  pub_tracking_ = pnh_.advertise<geometry_msgs::PoseStamped>("tracking", 10, true);
225  if (use_odom_)
226  {
227  sub_odom_ = nh_.subscribe<nav_msgs::Odometry>("odom", 10, &TrackerNode::cbOdometry, this,
229  }
230 
231  boost::recursive_mutex::scoped_lock lock(parameter_server_mutex_);
232  parameter_server_.setCallback(boost::bind(&TrackerNode::cbParameter, this, _1, _2));
233 }
234 
235 void TrackerNode::cbParameter(const TrajectoryTrackerConfig& config, const uint32_t /* level */)
236 {
237  boost::recursive_mutex::scoped_lock lock(parameter_server_mutex_);
238  look_forward_ = config.look_forward;
239  curv_forward_ = config.curv_forward;
240  k_[0] = config.k_dist;
241  k_[1] = config.k_ang;
242  k_[2] = config.k_avel;
243  gain_at_vel_ = config.gain_at_vel;
244  d_lim_ = config.dist_lim;
245  d_stop_ = config.dist_stop;
246  rotate_ang_ = config.rotate_ang;
247  vel_[0] = config.max_vel;
248  vel_[1] = config.max_angvel;
249  acc_[0] = config.max_acc;
250  acc_[1] = config.max_angacc;
251  acc_toc_[0] = acc_[0] * config.acc_toc_factor;
252  acc_toc_[1] = acc_[1] * config.angacc_toc_factor;
253  path_step_ = config.path_step;
254  goal_tolerance_dist_ = config.goal_tolerance_dist;
255  goal_tolerance_ang_ = config.goal_tolerance_ang;
256  stop_tolerance_dist_ = config.stop_tolerance_dist;
257  stop_tolerance_ang_ = config.stop_tolerance_ang;
258  no_pos_cntl_dist_ = config.no_position_control_dist;
259  min_track_path_ = config.min_tracking_path;
260  allow_backward_ = config.allow_backward;
261  limit_vel_by_avel_ = config.limit_vel_by_avel;
262  check_old_path_ = config.check_old_path;
263  epsilon_ = config.epsilon;
264  use_time_optimal_control_ = config.use_time_optimal_control;
265  time_optimal_control_future_gain_ = config.time_optimal_control_future_gain;
266  k_ang_rotation_ = config.k_ang_rotation;
267  k_avel_rotation_ = config.k_avel_rotation;
268  goal_tolerance_lin_vel_ = config.goal_tolerance_lin_vel;
269  goal_tolerance_ang_vel_ = config.goal_tolerance_ang_vel;
270 }
271 
273 {
274  geometry_msgs::Twist cmd_vel;
275  cmd_vel.linear.x = 0;
276  cmd_vel.angular.z = 0;
277  pub_vel_.publish(cmd_vel);
278 }
279 
280 void TrackerNode::cbSpeed(const std_msgs::Float32::ConstPtr& msg)
281 {
282  vel_[0] = msg->data;
283 }
284 
285 namespace
286 {
287 float getVelocity(const geometry_msgs::PoseStamped& msg)
288 {
289  return std::numeric_limits<float>::quiet_NaN();
290 }
291 float getVelocity(const trajectory_tracker_msgs::PoseStampedWithVelocity& msg)
292 {
293  return msg.linear_velocity.x;
294 }
295 } // namespace
296 
297 template <typename MSG_TYPE>
298 void TrackerNode::cbPath(const typename MSG_TYPE::ConstPtr& msg)
299 {
300  path_header_ = msg->header;
301  path_.clear();
302  is_path_updated_ = true;
303  path_step_done_ = 0;
304  if (msg->poses.size() == 0)
305  return;
306 
307  trajectory_tracker::Pose2D in_place_turn_end;
308  bool in_place_turning = false;
309 
310  auto j = msg->poses.begin();
311  path_.push_back(trajectory_tracker::Pose2D(j->pose, getVelocity(*j)));
312  for (++j; j < msg->poses.end(); ++j)
313  {
314  const float velocity = getVelocity(*j);
315  if (std::isfinite(velocity) && velocity < -0.0)
316  {
317  ROS_ERROR_THROTTLE(1.0, "path_velocity.velocity.x must be positive");
318  path_.clear();
319  return;
320  }
321  const trajectory_tracker::Pose2D next(j->pose, velocity);
322 
323  if ((path_.back().pos_ - next.pos_).squaredNorm() >= std::pow(epsilon_, 2))
324  {
325  if (in_place_turning)
326  {
327  path_.push_back(in_place_turn_end);
328  in_place_turning = false;
329  }
330  path_.push_back(next);
331  }
332  else
333  {
334  in_place_turn_end = trajectory_tracker::Pose2D(
335  path_.back().pos_, next.yaw_, next.velocity_);
336  in_place_turning = true;
337  }
338  }
339  if (in_place_turning)
340  path_.push_back(in_place_turn_end);
341 }
342 
343 void TrackerNode::cbOdometry(const nav_msgs::Odometry::ConstPtr& odom)
344 {
345  if (odom->header.frame_id != frame_odom_)
346  {
347  ROS_WARN("frame_odom is invalid. Update from \"%s\" to \"%s\"", frame_odom_.c_str(), odom->header.frame_id.c_str());
348  frame_odom_ = odom->header.frame_id;
349  }
350  if (odom->child_frame_id != frame_robot_)
351  {
352  ROS_WARN("frame_robot is invalid. Update from \"%s\" to \"%s\"",
353  frame_robot_.c_str(), odom->child_frame_id.c_str());
354  frame_robot_ = odom->child_frame_id;
355  }
356  if (odom_timeout_sec_ != 0.0)
357  {
359  {
361  }
362  else
363  {
366  }
367  }
368 
369  if (prev_odom_stamp_ != ros::Time())
370  {
371  const double dt = std::min(max_dt_, (odom->header.stamp - prev_odom_stamp_).toSec());
372  nav_msgs::Odometry odom_compensated = *odom;
373  Eigen::Vector3d prediction_offset(0, 0, 0);
374  if (predict_odom_)
375  {
376  const double predict_dt = std::max(0.0, std::min(max_dt_, (ros::Time::now() - odom->header.stamp).toSec()));
377  tf2::Transform trans;
378  const tf2::Quaternion rotation(tf2::Vector3(0, 0, 1), odom->twist.twist.angular.z * predict_dt);
379  const tf2::Vector3 translation(odom->twist.twist.linear.x * predict_dt, 0, 0);
380 
381  prediction_offset[0] = odom->twist.twist.linear.x * predict_dt;
382  prediction_offset[2] = odom->twist.twist.angular.z * predict_dt;
383 
384  tf2::fromMsg(odom->pose.pose, trans);
385  trans.setOrigin(trans.getOrigin() + tf2::Transform(trans.getRotation()) * translation);
386  trans.setRotation(trans.getRotation() * rotation);
387  tf2::toMsg(trans, odom_compensated.pose.pose);
388  }
389 
390  tf2::Transform odom_to_robot;
391  tf2::fromMsg(odom_compensated.pose.pose, odom_to_robot);
392  const tf2::Stamped<tf2::Transform> robot_to_odom(
393  odom_to_robot.inverse(),
394  odom->header.stamp, odom->header.frame_id);
395 
396  control(robot_to_odom, prediction_offset, odom->twist.twist.linear.x, odom->twist.twist.angular.z, dt);
397  }
398  prev_odom_stamp_ = odom->header.stamp;
399 }
400 
402 {
403  try
404  {
406  tf2::fromMsg(
408  control(transform, Eigen::Vector3d(0, 0, 0), 0, 0, 1.0 / hz_);
409  }
410  catch (tf2::TransformException& e)
411  {
412  ROS_WARN_THROTTLE(1, "TF exception: %s", e.what());
413  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
414  status.header.stamp = ros::Time::now();
415  status.distance_remains = 0.0;
416  status.angle_remains = 0.0;
417  status.path_header = path_header_;
418  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
419  pub_status_.publish(status);
420  return;
421  }
422 }
423 
425 {
426  ROS_WARN_STREAM("Odometry timeout. Last odometry stamp: " << prev_odom_stamp_);
427  v_lim_.clear();
428  w_lim_.clear();
429  geometry_msgs::Twist cmd_vel;
430  cmd_vel.linear.x = 0.0;
431  cmd_vel.angular.z = 0.0;
432  pub_vel_.publish(cmd_vel);
433 
434  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
435  status.header.stamp = ros::Time::now();
436  status.distance_remains = 0.0;
437  status.angle_remains = 0.0;
438  status.path_header = path_header_;
439  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
440  pub_status_.publish(status);
441 }
442 
444 {
445  ros::Timer timer;
446  if (!use_odom_)
447  {
448  timer = nh_.createTimer(ros::Duration(1.0 / hz_), &TrackerNode::cbTimer, this);
449  }
450  ros::spin();
451 }
452 
454  const tf2::Stamped<tf2::Transform>& robot_to_odom,
455  const Eigen::Vector3d& prediction_offset,
456  const double odom_linear_vel,
457  const double odom_angular_vel,
458  const double dt)
459 {
460  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
461  status.header.stamp = ros::Time::now();
462  status.path_header = path_header_;
463  if (is_path_updated_)
464  {
465  // Call getTrackingResult to update path_step_done_.
466  const TrackingResult initial_tracking_result =
467  getTrackingResult(robot_to_odom, prediction_offset, odom_linear_vel, odom_angular_vel);
468  path_step_done_ = initial_tracking_result.path_step_done;
469  is_path_updated_ = false;
470  }
471  const TrackingResult tracking_result =
472  getTrackingResult(robot_to_odom, prediction_offset, odom_linear_vel, odom_angular_vel);
473  switch (tracking_result.status)
474  {
475  case trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH:
476  case trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH:
477  {
478  v_lim_.clear();
479  w_lim_.clear();
480  geometry_msgs::Twist cmd_vel;
481  cmd_vel.linear.x = 0;
482  cmd_vel.angular.z = 0;
483  pub_vel_.publish(cmd_vel);
484  break;
485  }
486  default:
487  {
488  if (tracking_result.turning_in_place)
489  {
490  v_lim_.set(0.0, tracking_result.target_linear_vel, acc_[0], dt);
491 
493  {
494  const double expected_angle_remains =
495  tracking_result.angle_remains + w_lim_.get() * dt * time_optimal_control_future_gain_;
496  w_lim_.set(trajectory_tracker::timeOptimalControl(expected_angle_remains, acc_toc_[1]), vel_[1], acc_[1], dt);
497  }
498  else
499  {
500  const double wvel_increment =
501  (-tracking_result.angle_remains * k_ang_rotation_ - w_lim_.get() * k_avel_rotation_) * dt;
502  w_lim_.increment(wvel_increment, vel_[1], acc_[1], dt);
503  }
504  ROS_DEBUG(
505  "trajectory_tracker: angular residual %0.3f, angular vel %0.3f",
506  tracking_result.angle_remains, w_lim_.get());
507  }
508  else
509  {
510  v_lim_.set(
512  tracking_result.target_linear_vel, acc_[0], dt);
513 
514  float wref = std::abs(v_lim_.get()) * tracking_result.tracking_point_curv;
515 
516  if (limit_vel_by_avel_ && std::abs(wref) > vel_[1])
517  {
518  v_lim_.set(
519  std::copysign(1.0, v_lim_.get()) * std::abs(vel_[1] / tracking_result.tracking_point_curv),
520  tracking_result.target_linear_vel, acc_[0], dt);
521  wref = std::copysign(1.0, wref) * vel_[1];
522  }
523 
524  const double k_ang =
525  (gain_at_vel_ == 0.0) ? (k_[1]) : (k_[1] * tracking_result.target_linear_vel / gain_at_vel_);
526  const double dist_diff = tracking_result.distance_from_target;
527  const double angle_diff = tracking_result.angle_remains;
528  const double wvel_diff = w_lim_.get() - wref;
529  w_lim_.increment(dt * (-dist_diff * k_[0] - angle_diff * k_ang - wvel_diff * k_[2]), vel_[1], acc_[1], dt);
530 
531  ROS_DEBUG(
532  "trajectory_tracker: distance residual %0.3f, angular residual %0.3f, ang vel residual %0.3f"
533  ", v_lim %0.3f, w_lim %0.3f signed_local_distance %0.3f, k_ang %0.3f",
534  dist_diff, angle_diff, wvel_diff, v_lim_.get(), w_lim_.get(), tracking_result.signed_local_distance, k_ang);
535  }
536  if (std::abs(tracking_result.distance_remains) < stop_tolerance_dist_ &&
537  std::abs(tracking_result.angle_remains) < stop_tolerance_ang_ &&
538  std::abs(tracking_result.distance_remains_raw) < stop_tolerance_dist_ &&
539  std::abs(tracking_result.angle_remains_raw) < stop_tolerance_ang_)
540  {
541  v_lim_.clear();
542  w_lim_.clear();
543  }
544  geometry_msgs::Twist cmd_vel;
545  cmd_vel.linear.x = v_lim_.get();
546  cmd_vel.angular.z = w_lim_.get();
547  pub_vel_.publish(cmd_vel);
548  path_step_done_ = tracking_result.path_step_done;
549  break;
550  }
551  }
552  status.status = tracking_result.status;
553  status.distance_remains = tracking_result.distance_remains;
554  status.angle_remains = tracking_result.angle_remains;
555  pub_status_.publish(status);
556 }
557 
559  const tf2::Stamped<tf2::Transform>& robot_to_odom, const Eigen::Vector3d& prediction_offset,
560  const double odom_linear_vel, const double odom_angular_vel) const
561 {
562  if (path_header_.frame_id.size() == 0 || path_.size() == 0)
563  {
564  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
565  }
566  // Transform
568  double transform_delay = 0;
569  tf2::Stamped<tf2::Transform> transform = robot_to_odom;
570  try
571  {
572  tf2::Stamped<tf2::Transform> odom_to_path;
573  tf2::fromMsg(
574  tfbuf_.lookupTransform(frame_odom_, path_header_.frame_id, ros::Time(0)), odom_to_path);
575  transform *= odom_to_path;
576  transform_delay = (ros::Time::now() - transform.stamp_).toSec();
577  if (std::abs(transform_delay) > 0.1 && check_old_path_)
578  {
580  1.0, "Timestamp of the transform is too old %f %f",
581  ros::Time::now().toSec(), transform.stamp_.toSec());
582  }
583 
584  const float trans_yaw = tf2::getYaw(transform.getRotation());
585  const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> trans =
586  Eigen::Translation2d(
587  Eigen::Vector2d(transform.getOrigin().x(), transform.getOrigin().y())) *
588  Eigen::Rotation2Dd(trans_yaw);
589 
590  for (size_t i = 0; i < path_.size(); i += path_step_)
591  lpath.push_back(
593  trans * path_[i].pos_, trans_yaw + path_[i].yaw_, path_[i].velocity_));
594  }
595  catch (tf2::TransformException& e)
596  {
597  ROS_WARN("TF exception: %s", e.what());
598  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
599  }
600 
601  const Eigen::Vector2d origin_raw = prediction_offset.head<2>();
602  const float yaw_raw = prediction_offset[2];
603 
604  const float yaw_predicted = w_lim_.get() * look_forward_ / 2;
605  const Eigen::Vector2d origin =
606  Eigen::Vector2d(std::cos(yaw_predicted), std::sin(yaw_predicted)) * v_lim_.get() * look_forward_;
607 
608  const double path_length = lpath.length();
609 
610  // Find nearest line strip
611  const trajectory_tracker::Path2D::ConstIterator it_local_goal =
612  lpath.findLocalGoal(lpath.cbegin() + path_step_done_, lpath.cend(), allow_backward_);
613 
614  const float max_search_range = (path_step_done_ > 0) ? 1.0 : 0.0;
616  lpath.findNearest(lpath.cbegin() + path_step_done_, it_local_goal, origin,
617  max_search_range, epsilon_);
618 
619  if (it_nearest == lpath.end())
620  {
621  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
622  }
623 
624  const int i_nearest = std::distance(lpath.cbegin(), it_nearest);
625  const int i_nearest_prev = std::max(0, i_nearest - 1);
626  const int i_local_goal = std::distance(lpath.cbegin(), it_local_goal);
627 
628  const Eigen::Vector2d pos_on_line =
629  trajectory_tracker::projection2d(lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
630  const Eigen::Vector2d pos_on_line_raw =
631  trajectory_tracker::projection2d(lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin_raw);
632 
633  const float linear_vel =
634  std::isnan(lpath[i_nearest].velocity_) ? vel_[0] : lpath[i_nearest].velocity_;
635 
636  // Remained distance to the local goal
637  float remain_local = lpath.remainedDistance(lpath.cbegin(), it_nearest, it_local_goal, pos_on_line);
638  // Remained distance to the final goal
639  float distance_remains = lpath.remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line);
640  float distance_remains_raw = lpath.remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line_raw);
641  if (path_length < no_pos_cntl_dist_)
642  distance_remains = distance_remains_raw = remain_local = 0;
643 
644  // Signed distance error
645  const float dist_err = trajectory_tracker::lineDistance(
646  lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
647 
648  // Angular error
649  const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest_prev].pos_;
650  float angle_remains = -atan2(vec[1], vec[0]);
651  const float angle_pose = allow_backward_ ? lpath[i_nearest].yaw_ : -angle_remains;
652  float sign_vel = 1.0;
653  if (std::cos(-angle_remains) * std::cos(angle_pose) + std::sin(-angle_remains) * std::sin(angle_pose) < 0)
654  {
655  sign_vel = -1.0;
656  angle_remains = angle_remains + M_PI;
657  }
658  angle_remains = trajectory_tracker::angleNormalized(angle_remains);
659 
660  // Curvature
661  const float curv = lpath.getCurvature(it_nearest, it_local_goal, pos_on_line, curv_forward_);
662 
663  ROS_DEBUG(
664  "trajectory_tracker: nearest: %d, local goal: %d, done: %d, goal: %lu, remain: %0.3f, remain_local: %0.3f",
665  i_nearest, i_local_goal, path_step_done_, lpath.size(), distance_remains, remain_local);
666 
667  bool arrive_local_goal(false);
668  bool in_place_turning = (vec[1] == 0.0 && vec[0] == 0.0);
669 
670  TrackingResult result(trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
671 
672  // Stop and rotate
673  const bool large_angle_error = std::abs(rotate_ang_) < M_PI && std::cos(rotate_ang_) > std::cos(angle_remains);
674  if (large_angle_error ||
675  std::abs(remain_local) < stop_tolerance_dist_ ||
676  path_length < min_track_path_ ||
677  in_place_turning)
678  {
679  if (large_angle_error)
680  {
681  ROS_INFO_THROTTLE(1.0, "Stop and rotate due to large angular error: %0.3f", angle_remains);
682  }
683 
684  if (path_length < min_track_path_ ||
685  std::abs(remain_local) < stop_tolerance_dist_ ||
686  in_place_turning)
687  {
688  angle_remains = trajectory_tracker::angleNormalized(-(it_local_goal - 1)->yaw_);
689  if (it_local_goal != lpath.end())
690  arrive_local_goal = true;
691  }
692  if (path_length < stop_tolerance_dist_ || in_place_turning)
693  distance_remains = distance_remains_raw = 0.0;
694 
695  result.turning_in_place = true;
696  result.target_linear_vel = linear_vel;
697  result.distance_remains = distance_remains;
698  result.distance_remains_raw = distance_remains_raw;
699  result.angle_remains = angle_remains;
700  }
701  else
702  {
703  // Too far from given path
704  float dist_from_path = dist_err;
705  if (i_nearest == 0)
706  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
707  else if (i_nearest + 1 >= static_cast<int>(path_.size()))
708  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
709  if (std::abs(dist_from_path) > d_stop_)
710  {
711  result.distance_remains = distance_remains;
712  result.distance_remains_raw = distance_remains_raw;
713  result.angle_remains = angle_remains;
714  result.angle_remains_raw = angle_remains + yaw_raw;
715  result.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
716  return result;
717  }
718 
719  // Path following control
720  result.turning_in_place = false;
721  result.target_linear_vel = linear_vel;
722  result.distance_remains = distance_remains;
723  result.distance_remains_raw = distance_remains_raw;
724  result.angle_remains = angle_remains;
725  result.angle_remains_raw = angle_remains + yaw_raw;
727  result.signed_local_distance = -remain_local * sign_vel;
728  result.tracking_point_curv = curv;
729  result.tracking_point_x = pos_on_line[0];
730  result.tracking_point_y = pos_on_line[1];
731  }
732 
733  if (std::abs(result.distance_remains) < goal_tolerance_dist_ &&
734  std::abs(result.angle_remains) < goal_tolerance_ang_ &&
735  std::abs(result.distance_remains_raw) < goal_tolerance_dist_ &&
736  std::abs(result.angle_remains_raw) < goal_tolerance_ang_ &&
737  (goal_tolerance_lin_vel_ == 0.0 || std::abs(odom_linear_vel) < goal_tolerance_lin_vel_) &&
738  (goal_tolerance_ang_vel_ == 0.0 || std::abs(odom_angular_vel) < goal_tolerance_ang_vel_) &&
739  it_local_goal == lpath.end())
740  {
741  result.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
742  }
743 
744  if (arrive_local_goal)
745  result.path_step_done = i_local_goal;
746  else
747  result.path_step_done = std::max(path_step_done_, i_nearest - 1);
748 
749  return result;
750 }
751 } // namespace trajectory_tracker
752 
753 int main(int argc, char** argv)
754 {
755  ros::init(argc, argv, "trajectory_tracker");
757  track.spin();
758 
759  return 0;
760 }
void cbSpeed(const std_msgs::Float32::ConstPtr &)
ConstIterator findNearest(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target, const float max_search_range=0, const float epsilon=1e-6) const
Definition: path2d.h:129
void cbOdomTimeout(const ros::TimerEvent &)
TransportHints & reliable()
void cbParameter(const TrajectoryTrackerConfig &config, const uint32_t)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void cbTimer(const ros::TimerEvent &)
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
trajectory_tracker::Path2D path_
std::vector< Pose2D >::const_iterator ConstIterator
Definition: path2d.h:95
float set(float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:77
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const
Definition: path2d.h:170
dynamic_reconfigure::Server< TrajectoryTrackerConfig > parameter_server_
void setPeriod(const Duration &period, bool reset=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
trajectory_tracker::VelAccLimitter w_lim_
boost::recursive_mutex parameter_server_mutex_
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
void control(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double, const double)
#define ROS_WARN(...)
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_backward_motion) const
Definition: path2d.h:104
Transform inverse() const
tf2_ros::TransformListener tfl_
TransportHints & tcpNoDelay(bool nodelay=true)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO_THROTTLE(period,...)
#define ROS_WARN_THROTTLE(period,...)
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
float lineDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:58
#define ROS_ERROR_THROTTLE(period,...)
void fromMsg(const A &, B &b)
trajectory_tracker::VelAccLimitter v_lim_
void cbPath(const typename MSG_TYPE::ConstPtr &)
float length() const
Definition: path2d.h:97
ROSCPP_DECL void spin()
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
#define ROS_WARN_STREAM(args)
double getYaw(const A &a)
Eigen::Vector2d projection2d(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:89
B toMsg(const A &a)
void cbOdometry(const nav_msgs::Odometry::ConstPtr &)
bool isValid()
TrackingResult getTrackingResult(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double) const
float increment(const float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:72
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
Quaternion getRotation() const
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const
Definition: path2d.h:204
static Time now()
float angleNormalized(float ang)
Definition: basic_control.h:53
float timeOptimalControl(const float angle, const float acc)
Definition: basic_control.h:38
Eigen::Vector2d pos_
Definition: path2d.h:50
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
int main(int argc, char **argv)
float clip(const float v, const float max)
Definition: basic_control.h:43
#define ROS_DEBUG(...)


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:03