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 template <typename MSG_TYPE>
286 void TrackerNode::cbPath(const typename MSG_TYPE::ConstPtr& msg)
287 {
288  path_header_ = msg->header;
289  is_path_updated_ = true;
290  path_step_done_ = 0;
291  path_.fromMsg(*msg, epsilon_);
292  for (const auto& path_pose : path_)
293  {
294  if (std::isfinite(path_pose.velocity_) && path_pose.velocity_ < -0.0)
295  {
296  ROS_ERROR_THROTTLE(1.0, "path_velocity.velocity.x must be positive");
297  path_.clear();
298  return;
299  }
300  }
301 }
302 
303 void TrackerNode::cbOdometry(const nav_msgs::Odometry::ConstPtr& odom)
304 {
305  if (odom->header.frame_id != frame_odom_)
306  {
307  ROS_WARN("frame_odom is invalid. Update from \"%s\" to \"%s\"", frame_odom_.c_str(), odom->header.frame_id.c_str());
308  frame_odom_ = odom->header.frame_id;
309  }
310  if (odom->child_frame_id != frame_robot_)
311  {
312  ROS_WARN("frame_robot is invalid. Update from \"%s\" to \"%s\"",
313  frame_robot_.c_str(), odom->child_frame_id.c_str());
314  frame_robot_ = odom->child_frame_id;
315  }
316  if (odom_timeout_sec_ != 0.0)
317  {
319  {
321  }
322  else
323  {
326  }
327  }
328 
329  if (prev_odom_stamp_ != ros::Time())
330  {
331  const double dt = std::min(max_dt_, (odom->header.stamp - prev_odom_stamp_).toSec());
332  nav_msgs::Odometry odom_compensated = *odom;
333  Eigen::Vector3d prediction_offset(0, 0, 0);
334  if (predict_odom_)
335  {
336  const double predict_dt = std::max(0.0, std::min(max_dt_, (ros::Time::now() - odom->header.stamp).toSec()));
337  tf2::Transform trans;
338  const tf2::Quaternion rotation(tf2::Vector3(0, 0, 1), odom->twist.twist.angular.z * predict_dt);
339  const tf2::Vector3 translation(odom->twist.twist.linear.x * predict_dt, 0, 0);
340 
341  prediction_offset[0] = odom->twist.twist.linear.x * predict_dt;
342  prediction_offset[2] = odom->twist.twist.angular.z * predict_dt;
343 
344  tf2::fromMsg(odom->pose.pose, trans);
345  trans.setOrigin(trans.getOrigin() + tf2::Transform(trans.getRotation()) * translation);
346  trans.setRotation(trans.getRotation() * rotation);
347  tf2::toMsg(trans, odom_compensated.pose.pose);
348  }
349 
350  tf2::Transform odom_to_robot;
351  tf2::fromMsg(odom_compensated.pose.pose, odom_to_robot);
352  const tf2::Stamped<tf2::Transform> odom_to_robot_stamped(odom_to_robot, odom->header.stamp, odom->header.frame_id);
353  control(odom_to_robot_stamped, prediction_offset, odom->twist.twist.linear.x, odom->twist.twist.angular.z, dt);
354  }
355  prev_odom_stamp_ = odom->header.stamp;
356 }
357 
359 {
360  try
361  {
363  tf2::fromMsg(
365  control(transform, Eigen::Vector3d(0, 0, 0), 0, 0, 1.0 / hz_);
366  }
367  catch (tf2::TransformException& e)
368  {
369  ROS_WARN_THROTTLE(1, "TF exception: %s", e.what());
370  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
371  status.header.stamp = ros::Time::now();
372  status.distance_remains = 0.0;
373  status.angle_remains = 0.0;
374  status.path_header = path_header_;
375  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
376  pub_status_.publish(status);
377  return;
378  }
379 }
380 
382 {
383  ROS_WARN_STREAM("Odometry timeout. Last odometry stamp: " << prev_odom_stamp_);
384  v_lim_.clear();
385  w_lim_.clear();
386  geometry_msgs::Twist cmd_vel;
387  cmd_vel.linear.x = 0.0;
388  cmd_vel.angular.z = 0.0;
389  pub_vel_.publish(cmd_vel);
390 
391  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
392  status.header.stamp = ros::Time::now();
393  status.distance_remains = 0.0;
394  status.angle_remains = 0.0;
395  status.path_header = path_header_;
396  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
397  pub_status_.publish(status);
398 }
399 
401 {
402  ros::Timer timer;
403  if (!use_odom_)
404  {
405  timer = nh_.createTimer(ros::Duration(1.0 / hz_), &TrackerNode::cbTimer, this);
406  }
407  ros::spin();
408 }
409 
411  const tf2::Stamped<tf2::Transform>& odom_to_robot,
412  const Eigen::Vector3d& prediction_offset,
413  const double odom_linear_vel,
414  const double odom_angular_vel,
415  const double dt)
416 {
417  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
418  status.header.stamp = ros::Time::now();
419  status.path_header = path_header_;
420  if (is_path_updated_)
421  {
422  // Call getTrackingResult to update path_step_done_.
423  const TrackingResult initial_tracking_result =
424  getTrackingResult(odom_to_robot, prediction_offset, odom_linear_vel, odom_angular_vel);
425  path_step_done_ = initial_tracking_result.path_step_done;
426  is_path_updated_ = false;
427  }
428  const TrackingResult tracking_result =
429  getTrackingResult(odom_to_robot, prediction_offset, odom_linear_vel, odom_angular_vel);
430  switch (tracking_result.status)
431  {
432  case trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH:
433  case trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH:
434  {
435  v_lim_.clear();
436  w_lim_.clear();
437  geometry_msgs::Twist cmd_vel;
438  cmd_vel.linear.x = 0;
439  cmd_vel.angular.z = 0;
440  pub_vel_.publish(cmd_vel);
441  break;
442  }
443  default:
444  {
445  if (tracking_result.turning_in_place)
446  {
447  v_lim_.set(0.0, tracking_result.target_linear_vel, acc_[0], dt);
448 
450  {
451  const double expected_angle_remains =
452  tracking_result.angle_remains + w_lim_.get() * dt * time_optimal_control_future_gain_;
453  w_lim_.set(trajectory_tracker::timeOptimalControl(expected_angle_remains, acc_toc_[1]), vel_[1], acc_[1], dt);
454  }
455  else
456  {
457  const double wvel_increment =
458  (-tracking_result.angle_remains * k_ang_rotation_ - w_lim_.get() * k_avel_rotation_) * dt;
459  w_lim_.increment(wvel_increment, vel_[1], acc_[1], dt);
460  }
461  ROS_DEBUG(
462  "trajectory_tracker: angular residual %0.3f, angular vel %0.3f",
463  tracking_result.angle_remains, w_lim_.get());
464  }
465  else
466  {
467  v_lim_.set(
469  tracking_result.target_linear_vel, acc_[0], dt);
470 
471  float wref = std::abs(v_lim_.get()) * tracking_result.tracking_point_curv;
472 
473  if (limit_vel_by_avel_ && std::abs(wref) > vel_[1])
474  {
475  v_lim_.set(
476  std::copysign(1.0, v_lim_.get()) * std::abs(vel_[1] / tracking_result.tracking_point_curv),
477  tracking_result.target_linear_vel, acc_[0], dt);
478  wref = std::copysign(1.0, wref) * vel_[1];
479  }
480 
481  const double k_ang =
482  (gain_at_vel_ == 0.0) ? (k_[1]) : (k_[1] * tracking_result.target_linear_vel / gain_at_vel_);
483  const double dist_diff = tracking_result.distance_from_target;
484  const double angle_diff = tracking_result.angle_remains;
485  const double wvel_diff = w_lim_.get() - wref;
486  w_lim_.increment(dt * (-dist_diff * k_[0] - angle_diff * k_ang - wvel_diff * k_[2]), vel_[1], acc_[1], dt);
487 
488  ROS_DEBUG(
489  "trajectory_tracker: distance residual %0.3f, angular residual %0.3f, ang vel residual %0.3f"
490  ", v_lim %0.3f, w_lim %0.3f signed_local_distance %0.3f, k_ang %0.3f",
491  dist_diff, angle_diff, wvel_diff, v_lim_.get(), w_lim_.get(), tracking_result.signed_local_distance, k_ang);
492  }
493  if (std::abs(tracking_result.distance_remains) < stop_tolerance_dist_ &&
494  std::abs(tracking_result.angle_remains) < stop_tolerance_ang_ &&
495  std::abs(tracking_result.distance_remains_raw) < stop_tolerance_dist_ &&
496  std::abs(tracking_result.angle_remains_raw) < stop_tolerance_ang_)
497  {
498  v_lim_.clear();
499  w_lim_.clear();
500  }
501  geometry_msgs::Twist cmd_vel;
502  cmd_vel.linear.x = v_lim_.get();
503  cmd_vel.angular.z = w_lim_.get();
504  pub_vel_.publish(cmd_vel);
505  path_step_done_ = tracking_result.path_step_done;
506  break;
507  }
508  }
509  status.status = tracking_result.status;
510  status.distance_remains = tracking_result.distance_remains;
511  status.angle_remains = tracking_result.angle_remains;
512  pub_status_.publish(status);
513 }
514 
516  const tf2::Stamped<tf2::Transform>& odom_to_robot, const Eigen::Vector3d& prediction_offset,
517  const double odom_linear_vel, const double odom_angular_vel) const
518 {
519  if (path_header_.frame_id.size() == 0 || path_.size() == 0)
520  {
521  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
522  }
523  // Transform
525  double transform_delay = 0;
526  try
527  {
528  tf2::Stamped<tf2::Transform> path_to_odom;
529  tf2::fromMsg(
530  tfbuf_.lookupTransform(path_header_.frame_id, frame_odom_, ros::Time(0)), path_to_odom);
531  const tf2::Transform path_to_robot = path_to_odom * odom_to_robot;
532  transform_delay = (ros::Time::now() - path_to_odom.stamp_).toSec();
533  if (std::abs(transform_delay) > 0.1 && check_old_path_)
534  {
536  1.0, "Timestamp of the transform is too old %f %f",
537  ros::Time::now().toSec(), path_to_odom.stamp_.toSec());
538  }
539  const float robot_yaw = tf2::getYaw(path_to_robot.getRotation());
540  const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> path_to_robot_2d =
541  Eigen::Translation2d(
542  Eigen::Vector2d(path_to_robot.getOrigin().x(), path_to_robot.getOrigin().y())) *
543  Eigen::Rotation2Dd(robot_yaw);
544  const auto robot_to_path_2d = path_to_robot_2d.inverse();
545 
546  for (size_t i = 0; i < path_.size(); i += path_step_)
547  lpath.push_back(
549  robot_to_path_2d * path_[i].pos_, -robot_yaw + path_[i].yaw_, path_[i].velocity_));
550  }
551  catch (tf2::TransformException& e)
552  {
553  ROS_WARN("TF exception: %s", e.what());
554  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
555  }
556 
557  const Eigen::Vector2d origin_raw = prediction_offset.head<2>();
558  const float yaw_raw = prediction_offset[2];
559 
560  const float yaw_predicted = w_lim_.get() * look_forward_ / 2;
561  const Eigen::Vector2d origin =
562  Eigen::Vector2d(std::cos(yaw_predicted), std::sin(yaw_predicted)) * v_lim_.get() * look_forward_;
563 
564  const double path_length = lpath.length();
565 
566  // Find nearest line strip
567  const trajectory_tracker::Path2D::ConstIterator it_local_goal =
568  lpath.findLocalGoal(lpath.cbegin() + path_step_done_, lpath.cend(), allow_backward_);
569 
570  const float max_search_range = (path_step_done_ > 0) ? 1.0 : 0.0;
572  lpath.findNearest(lpath.cbegin() + path_step_done_, it_local_goal, origin,
573  max_search_range, epsilon_);
574 
575  if (it_nearest == lpath.end())
576  {
577  return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
578  }
579 
580  const int i_nearest = std::distance(lpath.cbegin(), it_nearest);
581  const int i_nearest_prev = std::max(0, i_nearest - 1);
582  const int i_local_goal = std::distance(lpath.cbegin(), it_local_goal);
583 
584  const Eigen::Vector2d pos_on_line =
585  trajectory_tracker::projection2d(lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
586  const Eigen::Vector2d pos_on_line_raw =
587  trajectory_tracker::projection2d(lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin_raw);
588 
589  const float linear_vel =
590  std::isnan(lpath[i_nearest].velocity_) ? vel_[0] : lpath[i_nearest].velocity_;
591 
592  // Remained distance to the local goal
593  float remain_local = lpath.remainedDistance(lpath.cbegin(), it_nearest, it_local_goal, pos_on_line);
594  // Remained distance to the final goal
595  float distance_remains = lpath.remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line);
596  float distance_remains_raw = lpath.remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line_raw);
597  if (path_length < no_pos_cntl_dist_)
598  distance_remains = distance_remains_raw = remain_local = 0;
599 
600  // Signed distance error
601  const float dist_err = trajectory_tracker::lineDistance(
602  lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
603 
604  // Angular error
605  const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest_prev].pos_;
606  float angle_remains = -atan2(vec[1], vec[0]);
607  const float angle_pose = allow_backward_ ? lpath[i_nearest].yaw_ : -angle_remains;
608  float sign_vel = 1.0;
609  if (std::cos(-angle_remains) * std::cos(angle_pose) + std::sin(-angle_remains) * std::sin(angle_pose) < 0)
610  {
611  sign_vel = -1.0;
612  angle_remains = angle_remains + M_PI;
613  }
614  angle_remains = trajectory_tracker::angleNormalized(angle_remains);
615 
616  // Curvature
617  const float curv = lpath.getCurvature(it_nearest, it_local_goal, pos_on_line, curv_forward_);
618 
619  ROS_DEBUG(
620  "trajectory_tracker: nearest: %d, local goal: %d, done: %d, goal: %lu, remain: %0.3f, remain_local: %0.3f",
621  i_nearest, i_local_goal, path_step_done_, lpath.size(), distance_remains, remain_local);
622 
623  bool arrive_local_goal(false);
624  bool in_place_turning = (vec[1] == 0.0 && vec[0] == 0.0);
625 
626  TrackingResult result(trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
627 
628  // Stop and rotate
629  const bool large_angle_error = std::abs(rotate_ang_) < M_PI && std::cos(rotate_ang_) > std::cos(angle_remains);
630  if (large_angle_error ||
631  std::abs(remain_local) < stop_tolerance_dist_ ||
632  path_length < min_track_path_ ||
633  in_place_turning)
634  {
635  if (large_angle_error)
636  {
637  ROS_INFO_THROTTLE(1.0, "Stop and rotate due to large angular error: %0.3f", angle_remains);
638  }
639 
640  if (path_length < min_track_path_ ||
641  std::abs(remain_local) < stop_tolerance_dist_ ||
642  in_place_turning)
643  {
644  angle_remains = trajectory_tracker::angleNormalized(-(it_local_goal - 1)->yaw_);
645  if (it_local_goal != lpath.end())
646  arrive_local_goal = true;
647  }
648  if (path_length < stop_tolerance_dist_ || in_place_turning)
649  distance_remains = distance_remains_raw = 0.0;
650 
651  result.turning_in_place = true;
652  result.target_linear_vel = linear_vel;
653  result.distance_remains = distance_remains;
654  result.distance_remains_raw = distance_remains_raw;
655  result.angle_remains = angle_remains;
656  }
657  else
658  {
659  // Too far from given path
660  float dist_from_path = dist_err;
661  if (i_nearest == 0)
662  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
663  else if (i_nearest + 1 >= static_cast<int>(path_.size()))
664  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
665  if (std::abs(dist_from_path) > d_stop_)
666  {
667  result.distance_remains = distance_remains;
668  result.distance_remains_raw = distance_remains_raw;
669  result.angle_remains = angle_remains;
670  result.angle_remains_raw = angle_remains + yaw_raw;
671  result.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
672  return result;
673  }
674 
675  // Path following control
676  result.turning_in_place = false;
677  result.target_linear_vel = linear_vel;
678  result.distance_remains = distance_remains;
679  result.distance_remains_raw = distance_remains_raw;
680  result.angle_remains = angle_remains;
681  result.angle_remains_raw = angle_remains + yaw_raw;
683  result.signed_local_distance = -remain_local * sign_vel;
684  result.tracking_point_curv = curv;
685  result.tracking_point_x = pos_on_line[0];
686  result.tracking_point_y = pos_on_line[1];
687  }
688 
689  if (std::abs(result.distance_remains) < goal_tolerance_dist_ &&
690  std::abs(result.angle_remains) < goal_tolerance_ang_ &&
691  std::abs(result.distance_remains_raw) < goal_tolerance_dist_ &&
692  std::abs(result.angle_remains_raw) < goal_tolerance_ang_ &&
693  (goal_tolerance_lin_vel_ == 0.0 || std::abs(odom_linear_vel) < goal_tolerance_lin_vel_) &&
694  (goal_tolerance_ang_vel_ == 0.0 || std::abs(odom_angular_vel) < goal_tolerance_ang_vel_) &&
695  it_local_goal == lpath.end())
696  {
697  result.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
698  }
699 
700  if (arrive_local_goal)
701  result.path_step_done = i_local_goal;
702  else
703  result.path_step_done = std::max(path_step_done_, i_nearest - 1);
704 
705  return result;
706 }
707 } // namespace trajectory_tracker
708 
709 int main(int argc, char** argv)
710 {
711  ros::init(argc, argv, "trajectory_tracker");
713  track.spin();
714 
715  return 0;
716 }
trajectory_tracker::TrackerNode::acc_toc_
double acc_toc_[2]
Definition: trajectory_tracker.cpp:98
ROS_ERROR_THROTTLE
#define ROS_ERROR_THROTTLE(period,...)
trajectory_tracker::TrackerNode::TrackingResult::TrackingResult
TrackingResult(const int s)
Definition: trajectory_tracker.cpp:149
trajectory_tracker::TrackerNode::TrackingResult::target_linear_vel
double target_linear_vel
Definition: trajectory_tracker.cpp:174
trajectory_tracker::TrackerNode::cbOdomTimeout
void cbOdomTimeout(const ros::TimerEvent &)
Definition: trajectory_tracker.cpp:381
trajectory_tracker::VelAccLimitter::increment
float increment(const float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:72
trajectory_tracker::TrackerNode::frame_odom_
std::string frame_odom_
Definition: trajectory_tracker.cpp:88
ros::Publisher
trajectory_tracker::TrackerNode::path_step_done_
int path_step_done_
Definition: trajectory_tracker.cpp:109
trajectory_tracker::TrackerNode::parameter_server_mutex_
boost::recursive_mutex parameter_server_mutex_
Definition: trajectory_tracker.cpp:140
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
trajectory_tracker::TrackerNode::goal_tolerance_ang_
double goal_tolerance_ang_
Definition: trajectory_tracker.cpp:103
trajectory_tracker::Path2D::remainedDistance
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const
Definition: path2d.h:226
trajectory_tracker::TrackerNode::pub_vel_
ros::Publisher pub_vel_
Definition: trajectory_tracker.cpp:126
trajectory_tracker::TrackerNode::min_track_path_
double min_track_path_
Definition: trajectory_tracker.cpp:107
tf2::getYaw
double getYaw(const A &a)
tf2::fromMsg
void fromMsg(const A &, B &b)
utils.h
s
XmlRpcServer s
trajectory_tracker::TrackerNode::time_optimal_control_future_gain_
double time_optimal_control_future_gain_
Definition: trajectory_tracker.cpp:116
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
ros.h
trajectory_tracker::TrackerNode::topic_cmd_vel_
std::string topic_cmd_vel_
Definition: trajectory_tracker.cpp:86
trajectory_tracker::TrackerNode::use_time_optimal_control_
bool use_time_optimal_control_
Definition: trajectory_tracker.cpp:115
trajectory_tracker::TrackerNode::cbSpeed
void cbSpeed(const std_msgs::Float32::ConstPtr &)
Definition: trajectory_tracker.cpp:280
trajectory_tracker::TrackerNode::no_pos_cntl_dist_
double no_pos_cntl_dist_
Definition: trajectory_tracker.cpp:106
trajectory_tracker::TrackerNode::goal_tolerance_ang_vel_
double goal_tolerance_ang_vel_
Definition: trajectory_tracker.cpp:120
trajectory_tracker::Pose2D
Definition: path2d.h:52
trajectory_tracker::TrackerNode::pub_tracking_
ros::Publisher pub_tracking_
Definition: trajectory_tracker.cpp:128
trajectory_tracker::TrackerNode::TrackerNode
TrackerNode()
Definition: trajectory_tracker.cpp:193
trajectory_tracker::TrackerNode::TrackingResult::distance_remains
double distance_remains
Definition: trajectory_tracker.cpp:167
tf2::Transform::setRotation
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
trajectory_tracker::TrackerNode::tfl_
tf2_ros::TransformListener tfl_
Definition: trajectory_tracker.cpp:132
trajectory_tracker::Path2D
Definition: path2d.h:118
ros::Timer::isValid
bool isValid()
ros::TransportHints
TimeBase< Time, Duration >::toSec
double toSec() const
trajectory_tracker::TrackerNode::odom_timeout_timer_
ros::Timer odom_timeout_timer_
Definition: trajectory_tracker.cpp:133
tf2::Transform::getOrigin
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
tf2::Stamped
compatibility.h
trajectory_tracker::TrackerNode::sub_odom_
ros::Subscriber sub_odom_
Definition: trajectory_tracker.cpp:125
trajectory_tracker::TrackerNode::check_old_path_
bool check_old_path_
Definition: trajectory_tracker.cpp:112
trajectory_tracker::TrackerNode::goal_tolerance_dist_
double goal_tolerance_dist_
Definition: trajectory_tracker.cpp:102
basic_control.h
trajectory_tracker::TrackerNode::TrackingResult::angle_remains
double angle_remains
Definition: trajectory_tracker.cpp:168
trajectory_tracker::VelAccLimitter
Definition: basic_control.h:62
trajectory_tracker::TrackerNode::predict_odom_
bool predict_odom_
Definition: trajectory_tracker.cpp:144
trajectory_tracker::TrackerNode::sub_path_
ros::Subscriber sub_path_
Definition: trajectory_tracker.cpp:122
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
trajectory_tracker::Path2D::ConstIterator
std::vector< Pose2D >::const_iterator ConstIterator
Definition: path2d.h:125
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
trajectory_tracker::Path2D::findLocalGoal
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_switch_back, const bool allow_in_place_turn=true, const double epsilon=1e-6) const
Definition: path2d.h:134
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
trajectory_tracker::TrackerNode::~TrackerNode
~TrackerNode()
Definition: trajectory_tracker.cpp:272
tf2_ros::TransformListener
trajectory_tracker::TrackerNode::TrackingResult::signed_local_distance
double signed_local_distance
Definition: trajectory_tracker.cpp:172
trajectory_tracker::TrackerNode::TrackingResult
Definition: trajectory_tracker.cpp:147
ros::TransportHints::reliable
TransportHints & reliable()
trajectory_tracker::TrackerNode::TrackingResult::distance_remains_raw
double distance_remains_raw
Definition: trajectory_tracker.cpp:169
trajectory_tracker::TrackerNode::max_dt_
double max_dt_
Definition: trajectory_tracker.cpp:114
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
neonavigation_common::compat::subscribe
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, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints())
trajectory_tracker
Definition: average.h:34
trajectory_tracker::VelAccLimitter::set
float set(float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:77
trajectory_tracker::TrackerNode::w_lim_
trajectory_tracker::VelAccLimitter w_lim_
Definition: trajectory_tracker.cpp:100
ROS_DEBUG
#define ROS_DEBUG(...)
trajectory_tracker::TrackerNode::epsilon_
double epsilon_
Definition: trajectory_tracker.cpp:113
tf2::Transform::setOrigin
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
ros::Timer::setPeriod
void setPeriod(const Duration &period, bool reset=true)
trajectory_tracker::TrackerNode::TrackingResult::angle_remains_raw
double angle_remains_raw
Definition: trajectory_tracker.cpp:170
trajectory_tracker::TrackerNode::k_avel_rotation_
double k_avel_rotation_
Definition: trajectory_tracker.cpp:118
trajectory_tracker::TrackerNode::vel_
double vel_[2]
Definition: trajectory_tracker.cpp:96
trajectory_tracker::TrackerNode::hz_
double hz_
Definition: trajectory_tracker.cpp:89
trajectory_tracker::TrackerNode::frame_robot_
std::string frame_robot_
Definition: trajectory_tracker.cpp:87
trajectory_tracker::Path2D::fromMsg
void fromMsg(const PATH_TYPE &path, const double in_place_turn_eps=1.0e-6)
Definition: path2d.h:306
trajectory_tracker::TrackerNode::TrackingResult::turning_in_place
bool turning_in_place
Definition: trajectory_tracker.cpp:171
trajectory_tracker::TrackerNode::stop_tolerance_dist_
double stop_tolerance_dist_
Definition: trajectory_tracker.cpp:104
tf2::Transform
trajectory_tracker::TrackerNode::odom_timeout_sec_
double odom_timeout_sec_
Definition: trajectory_tracker.cpp:134
tf2::Transform::getRotation
Quaternion getRotation() const
trajectory_tracker::TrackerNode::sub_path_velocity_
ros::Subscriber sub_path_velocity_
Definition: trajectory_tracker.cpp:123
trajectory_tracker::TrackerNode::d_stop_
double d_stop_
Definition: trajectory_tracker.cpp:95
trajectory_tracker::lineDistance
float lineDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:58
tf2::Stamped::stamp_
ros::Time stamp_
trajectory_tracker::TrackerNode::look_forward_
double look_forward_
Definition: trajectory_tracker.cpp:90
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
trajectory_tracker::TrackerNode::spin
void spin()
Definition: trajectory_tracker.cpp:400
trajectory_tracker::TrackerNode::k_ang_rotation_
double k_ang_rotation_
Definition: trajectory_tracker.cpp:117
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
trajectory_tracker::TrackerNode::TrackingResult::distance_from_target
double distance_from_target
Definition: trajectory_tracker.cpp:173
ros::TimerEvent
trajectory_tracker::TrackerNode::path_step_
int path_step_
Definition: trajectory_tracker.cpp:108
trajectory_tracker::TrackerNode::v_lim_
trajectory_tracker::VelAccLimitter v_lim_
Definition: trajectory_tracker.cpp:99
trajectory_tracker::TrackerNode::limit_vel_by_avel_
bool limit_vel_by_avel_
Definition: trajectory_tracker.cpp:111
trajectory_tracker::VelAccLimitter::clear
void clear()
Definition: basic_control.h:97
trajectory_tracker::TrackerNode::getTrackingResult
TrackingResult getTrackingResult(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double) const
Definition: trajectory_tracker.cpp:515
trajectory_tracker::projection2d
Eigen::Vector2d projection2d(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:89
trajectory_tracker::TrackerNode::path_header_
std_msgs::Header path_header_
Definition: trajectory_tracker.cpp:137
trajectory_tracker::TrackerNode::allow_backward_
bool allow_backward_
Definition: trajectory_tracker.cpp:110
trajectory_tracker::TrackerNode::pnh_
ros::NodeHandle pnh_
Definition: trajectory_tracker.cpp:130
trajectory_tracker::TrackerNode
Definition: trajectory_tracker.cpp:77
trajectory_tracker::VelAccLimitter::get
float get() const
Definition: basic_control.h:93
trajectory_tracker::TrackerNode::cbOdometry
void cbOdometry(const nav_msgs::Odometry::ConstPtr &)
Definition: trajectory_tracker.cpp:303
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
trajectory_tracker::TrackerNode::rotate_ang_
double rotate_ang_
Definition: trajectory_tracker.cpp:101
trajectory_tracker::TrackerNode::cbPath
void cbPath(const typename MSG_TYPE::ConstPtr &)
Definition: trajectory_tracker.cpp:286
main
int main(int argc, char **argv)
Definition: trajectory_tracker.cpp:709
transform_listener.h
trajectory_tracker::TrackerNode::acc_
double acc_[2]
Definition: trajectory_tracker.cpp:97
eigen_line.h
trajectory_tracker::TrackerNode::TrackingResult::tracking_point_curv
double tracking_point_curv
Definition: trajectory_tracker.cpp:177
trajectory_tracker::timeOptimalControl
float timeOptimalControl(const float angle, const float acc)
Definition: basic_control.h:38
ros::Time
trajectory_tracker::TrackerNode::topic_path_
std::string topic_path_
Definition: trajectory_tracker.cpp:85
trajectory_tracker::Path2D::length
float length() const
Definition: path2d.h:127
trajectory_tracker::TrackerNode::d_lim_
double d_lim_
Definition: trajectory_tracker.cpp:94
neonavigation_common::compat::deprecatedParam
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
trajectory_tracker::TrackerNode::goal_tolerance_lin_vel_
double goal_tolerance_lin_vel_
Definition: trajectory_tracker.cpp:119
trajectory_tracker::TrackerNode::parameter_server_
dynamic_reconfigure::Server< TrajectoryTrackerConfig > parameter_server_
Definition: trajectory_tracker.cpp:141
trajectory_tracker::TrackerNode::gain_at_vel_
double gain_at_vel_
Definition: trajectory_tracker.cpp:93
trajectory_tracker::clip
float clip(const float v, const float max)
Definition: basic_control.h:43
trajectory_tracker::TrackerNode::sub_vel_
ros::Subscriber sub_vel_
Definition: trajectory_tracker.cpp:124
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
trajectory_tracker::TrackerNode::TrackingResult::status
int status
Definition: trajectory_tracker.cpp:166
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
trajectory_tracker::TrackerNode::tfbuf_
tf2_ros::Buffer tfbuf_
Definition: trajectory_tracker.cpp:131
trajectory_tracker::Path2D::getCurvature
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const
Definition: path2d.h:260
ros::spin
ROSCPP_DECL void spin()
trajectory_tracker::TrackerNode::nh_
ros::NodeHandle nh_
Definition: trajectory_tracker.cpp:129
trajectory_tracker::TrackerNode::prev_odom_stamp_
ros::Time prev_odom_stamp_
Definition: trajectory_tracker.cpp:145
trajectory_tracker::TrackerNode::curv_forward_
double curv_forward_
Definition: trajectory_tracker.cpp:91
trajectory_tracker::TrackerNode::control
void control(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double, const double)
Definition: trajectory_tracker.cpp:410
trajectory_tracker::TrackerNode::TrackingResult::tracking_point_y
double tracking_point_y
Definition: trajectory_tracker.cpp:176
tf2::TransformException
path2d.h
trajectory_tracker::Path2D::findNearest
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:171
trajectory_tracker::TrackerNode::pub_status_
ros::Publisher pub_status_
Definition: trajectory_tracker.cpp:127
trajectory_tracker::TrackerNode::path_
trajectory_tracker::Path2D path_
Definition: trajectory_tracker.cpp:136
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
trajectory_tracker::TrackerNode::TrackingResult::tracking_point_x
double tracking_point_x
Definition: trajectory_tracker.cpp:175
trajectory_tracker::TrackerNode::TrackingResult::path_step_done
int path_step_done
Definition: trajectory_tracker.cpp:178
ros::Duration
ros::Timer
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
trajectory_tracker::TrackerNode::k_
double k_[3]
Definition: trajectory_tracker.cpp:92
trajectory_tracker::TrackerNode::stop_tolerance_ang_
double stop_tolerance_ang_
Definition: trajectory_tracker.cpp:105
trajectory_tracker::TrackerNode::use_odom_
bool use_odom_
Definition: trajectory_tracker.cpp:143
ros::NodeHandle
ros::Subscriber
trajectory_tracker::TrackerNode::is_path_updated_
bool is_path_updated_
Definition: trajectory_tracker.cpp:138
trajectory_tracker::TrackerNode::cbTimer
void cbTimer(const ros::TimerEvent &)
Definition: trajectory_tracker.cpp:358
trajectory_tracker::TrackerNode::cbParameter
void cbParameter(const TrajectoryTrackerConfig &config, const uint32_t)
Definition: trajectory_tracker.cpp:235
trajectory_tracker::angleNormalized
float angleNormalized(float ang)
Definition: basic_control.h:53
ros::Time::now
static Time now()
ROS_INFO_THROTTLE
#define ROS_INFO_THROTTLE(period,...)


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Wed Mar 19 2025 02:14:15