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 <geometry_msgs/Twist.h>
55 #include <geometry_msgs/PoseStamped.h>
56 #include <nav_msgs/Odometry.h>
57 #include <nav_msgs/Path.h>
58 #include <std_msgs/Float32.h>
59 #include <std_msgs/Header.h>
60 
61 #include <tf2/utils.h>
64 
66 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
67 #include <trajectory_tracker_msgs/PathWithVelocity.h>
68 
72 
74 {
75 public:
76  TrackerNode();
77  ~TrackerNode();
78  void spin();
79 
80 private:
81  std::string topic_path_;
82  std::string topic_cmd_vel_;
83  std::string frame_robot_;
84  std::string frame_odom_;
85  double hz_;
86  double look_forward_;
87  double curv_forward_;
88  double k_[3];
89  double gain_at_vel_;
90  double d_lim_;
91  double d_stop_;
92  double vel_[2];
93  double acc_[2];
94  double acc_toc_[2];
97  double rotate_ang_;
109  double epsilon_;
111 
122 
124  std_msgs::Header path_header_;
125 
126  template <typename MSG_TYPE>
127  void cbPath(const typename MSG_TYPE::ConstPtr&);
128  void cbSpeed(const std_msgs::Float32::ConstPtr&);
129  void cbTimer(const ros::TimerEvent&);
130  void control();
131 };
132 
134  : nh_()
135  , pnh_("~")
136  , tfl_(tfbuf_)
137 {
139  pnh_.param("frame_robot", frame_robot_, std::string("base_link"));
140  pnh_.param("frame_odom", frame_odom_, std::string("odom"));
141  neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("path"));
142  neonavigation_common::compat::deprecatedParam(pnh_, "cmd_vel", topic_cmd_vel_, std::string("cmd_vel"));
143  pnh_.param("hz", hz_, 50.0);
144  pnh_.param("look_forward", look_forward_, 0.5);
145  pnh_.param("curv_forward", curv_forward_, 0.5);
146  pnh_.param("k_dist", k_[0], 1.0);
147  pnh_.param("k_ang", k_[1], 1.0);
148  pnh_.param("k_avel", k_[2], 1.0);
149  pnh_.param("gain_at_vel", gain_at_vel_, 0.0);
150  pnh_.param("dist_lim", d_lim_, 0.5);
151  pnh_.param("dist_stop", d_stop_, 2.0);
152  pnh_.param("rotate_ang", rotate_ang_, M_PI / 4);
153  pnh_.param("max_vel", vel_[0], 0.5);
154  pnh_.param("max_angvel", vel_[1], 1.0);
155  pnh_.param("max_acc", acc_[0], 1.0);
156  pnh_.param("max_angacc", acc_[1], 2.0);
157  double acc_toc_factor[2];
158  pnh_.param("acc_toc_factor", acc_toc_factor[0], 0.9);
159  pnh_.param("angacc_toc_factor", acc_toc_factor[1], 0.9);
160  acc_toc_[0] = acc_[0] * acc_toc_factor[0];
161  acc_toc_[1] = acc_[1] * acc_toc_factor[1];
162  pnh_.param("path_step", path_step_, 1);
163  pnh_.param("goal_tolerance_dist", goal_tolerance_dist_, 0.2);
164  pnh_.param("goal_tolerance_ang", goal_tolerance_ang_, 0.1);
165  pnh_.param("stop_tolerance_dist", stop_tolerance_dist_, 0.1);
166  pnh_.param("stop_tolerance_ang", stop_tolerance_ang_, 0.05);
167  pnh_.param("no_position_control_dist", no_pos_cntl_dist_, 0.0);
168  pnh_.param("min_tracking_path", min_track_path_, no_pos_cntl_dist_);
169  pnh_.param("allow_backward", allow_backward_, true);
170  pnh_.param("limit_vel_by_avel", limit_vel_by_avel_, false);
171  pnh_.param("check_old_path", check_old_path_, false);
172  pnh_.param("epsilon", epsilon_, 0.001);
173 
174  sub_path_ = neonavigation_common::compat::subscribe<nav_msgs::Path>(
175  nh_, "path",
176  pnh_, topic_path_, 2,
177  boost::bind(&TrackerNode::cbPath<nav_msgs::Path>, this, _1));
178  sub_path_velocity_ = nh_.subscribe<trajectory_tracker_msgs::PathWithVelocity>(
179  "path_velocity", 2,
180  boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>, this, _1));
182  nh_, "speed",
183  pnh_, "speed", 20, &TrackerNode::cbSpeed, this);
184  pub_vel_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
185  nh_, "cmd_vel",
186  pnh_, topic_cmd_vel_, 10);
187  pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>("status", 10);
188  pub_tracking_ = pnh_.advertise<geometry_msgs::PoseStamped>("tracking", 10);
189 }
191 {
192  geometry_msgs::Twist cmd_vel;
193  cmd_vel.linear.x = 0;
194  cmd_vel.angular.z = 0;
195  pub_vel_.publish(cmd_vel);
196 }
197 
198 void TrackerNode::cbSpeed(const std_msgs::Float32::ConstPtr& msg)
199 {
200  vel_[0] = msg->data;
201 }
202 
203 namespace
204 {
205 float getVelocity(const geometry_msgs::PoseStamped& msg)
206 {
207  return std::numeric_limits<float>::quiet_NaN();
208 }
209 float getVelocity(const trajectory_tracker_msgs::PoseStampedWithVelocity& msg)
210 {
211  return msg.linear_velocity.x;
212 }
213 } // namespace
214 
215 template <typename MSG_TYPE>
216 void TrackerNode::cbPath(const typename MSG_TYPE::ConstPtr& msg)
217 {
218  path_header_ = msg->header;
219  path_.clear();
220  path_step_done_ = 0;
221  in_place_turn_ = false;
222  if (msg->poses.size() == 0)
223  return;
224 
225  auto j = msg->poses.begin();
226  path_.push_back(trajectory_tracker::Pose2D(j->pose, getVelocity(*j)));
227  for (auto j = msg->poses.begin(); j != msg->poses.end(); ++j)
228  {
229  const float velocity = getVelocity(*j);
230  if (std::isfinite(velocity) && velocity < -0.0)
231  {
232  ROS_ERROR_THROTTLE(1.0, "path_velocity.velocity.x must be positive");
233  path_.clear();
234  return;
235  }
236  const trajectory_tracker::Pose2D next(j->pose, velocity);
237 
238  if ((path_.back().pos_ - next.pos_).squaredNorm() >= std::pow(epsilon_, 2))
239  path_.push_back(next);
240  }
241 
242  if (path_.size() == 1)
243  {
245  msg->poses.back().pose, std::numeric_limits<float>::quiet_NaN());
246  in_place_turn_ = true;
247  while (path_.size() < 3)
248  {
249  // to make line direction computable, line should have a few points
250  const float yaw = path_.back().yaw_;
251  const trajectory_tracker::Pose2D next(
252  path_.back().pos_ + Eigen::Vector2d(std::cos(yaw), std::sin(yaw)) * epsilon_,
253  yaw, path_.back().velocity_);
254  path_.push_back(next);
255  }
256  }
257 }
259 {
260  control();
261 }
262 
264 {
266 
267  ros::spin();
268 }
269 
271 {
272  trajectory_tracker_msgs::TrajectoryTrackerStatus status;
273  status.header.stamp = ros::Time::now();
274  status.distance_remains = 0.0;
275  status.angle_remains = 0.0;
276 
277  if (path_header_.frame_id.size() == 0 || path_.size() == 0)
278  {
279  v_lim_.clear();
280  w_lim_.clear();
281  geometry_msgs::Twist cmd_vel;
282  cmd_vel.linear.x = 0;
283  cmd_vel.angular.z = 0;
284  pub_vel_.publish(cmd_vel);
285  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
286  pub_status_.publish(status);
287  return;
288  }
289  // Transform
292  double transform_delay = 0;
293  try
294  {
295  tf2::Stamped<tf2::Transform> trans_odom;
296  tf2::fromMsg(
298  tf2::fromMsg(
299  tfbuf_.lookupTransform(frame_odom_, path_header_.frame_id, ros::Time(0)), trans_odom);
300  transform *= trans_odom;
301  transform_delay = (ros::Time::now() - transform.stamp_).toSec();
302  if (std::abs(transform_delay) > 0.1 && check_old_path_)
303  {
305  1.0, "Timestamp of the transform is too old %f %f",
306  ros::Time::now().toSec(), transform.stamp_.toSec());
307  }
308 
309  const float trans_yaw = tf2::getYaw(transform.getRotation());
310  const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> trans =
311  Eigen::Translation2d(
312  Eigen::Vector2d(transform.getOrigin().x(), transform.getOrigin().y())) *
313  Eigen::Rotation2Dd(trans_yaw);
314 
315  for (size_t i = 0; i < path_.size(); i += path_step_)
316  lpath.push_back(
318  trans * path_[i].pos_, trans_yaw + path_[i].yaw_, path_[i].velocity_));
319  }
320  catch (tf2::TransformException& e)
321  {
322  ROS_WARN("TF exception: %s", e.what());
323  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
324  pub_status_.publish(status);
325  return;
326  }
327 
328  const float predicted_yaw = w_lim_.get() * look_forward_ / 2;
329  const Eigen::Vector2d origin =
330  Eigen::Vector2d(std::cos(predicted_yaw), std::sin(predicted_yaw)) * v_lim_.get() * look_forward_;
331 
332  const double path_length = lpath.length();
333 
334  // Find nearest line strip
335  const trajectory_tracker::Path2D::ConstIterator it_local_goal =
336  lpath.findLocalGoal(lpath.begin() + path_step_done_, lpath.end(), allow_backward_);
337 
338  const float max_search_range = (path_step_done_ > 0) ? 1.0 : 0.0;
340  lpath.findNearest(lpath.begin() + path_step_done_, it_local_goal, origin, max_search_range);
341 
342  if (it_nearest == lpath.end())
343  {
344  v_lim_.clear();
345  w_lim_.clear();
346  geometry_msgs::Twist cmd_vel;
347  cmd_vel.linear.x = 0;
348  cmd_vel.angular.z = 0;
349  pub_vel_.publish(cmd_vel);
350  // ROS_WARN("failed to find nearest node");
351  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
352  pub_status_.publish(status);
353  return;
354  }
355 
356  const int i_nearest = std::distance(
357  static_cast<trajectory_tracker::Path2D::ConstIterator>(lpath.begin()), it_nearest);
358  const int i_local_goal = std::distance(
359  static_cast<trajectory_tracker::Path2D::ConstIterator>(lpath.begin()), it_local_goal);
360 
361  const Eigen::Vector2d pos_on_line =
362  trajectory_tracker::projection2d(lpath[i_nearest - 1].pos_, lpath[i_nearest].pos_, origin);
363 
364  const float linear_vel =
365  std::isnan(lpath[i_nearest].velocity_) ? vel_[0] : lpath[i_nearest].velocity_;
366 
367  // Remained distance to the local goal
368  float remain_local = lpath.remainedDistance(lpath.begin(), it_nearest, it_local_goal, pos_on_line);
369  // Remained distance to the final goal
370  float remain = lpath.remainedDistance(lpath.begin(), it_nearest, lpath.end(), pos_on_line);
371  if (path_length < no_pos_cntl_dist_)
372  remain = remain_local = 0;
373 
374  // Signed distance error
375  const float dist_err = trajectory_tracker::lineDistance(
376  lpath[i_nearest - 1].pos_, lpath[i_nearest].pos_, origin);
377 
378  // Angular error
379  const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest - 1].pos_;
380  float angle = -atan2(vec[1], vec[0]);
381  const float angle_pose = allow_backward_ ? lpath[i_nearest].yaw_ : -angle;
382  float sign_vel = 1.0;
383  if (std::cos(-angle) * std::cos(angle_pose) + std::sin(-angle) * std::sin(angle_pose) < 0)
384  {
385  sign_vel = -1.0;
386  angle = angle + M_PI;
387  }
389 
390  // Curvature
391  const float curv = lpath.getCurvature(it_nearest, it_local_goal, pos_on_line, curv_forward_);
392 
393  status.distance_remains = remain;
394  status.angle_remains = angle;
395 
396  ROS_DEBUG(
397  "trajectory_tracker: nearest: %d, local goal: %d, done: %d, goal: %lu, remain: %0.3f, remain_local: %0.3f",
398  i_nearest, i_local_goal, path_step_done_, lpath.size(), remain, remain_local);
399 
400  bool arrive_local_goal(false);
401 
402  const float dt = 1.0 / hz_;
403  // Stop and rotate
404  if ((std::abs(rotate_ang_) < M_PI && std::cos(rotate_ang_) > std::cos(angle)) ||
405  std::abs(remain_local) < stop_tolerance_dist_ ||
406  path_length < min_track_path_ ||
408  {
409  if (path_length < min_track_path_ || std::abs(remain_local) < stop_tolerance_dist_)
410  {
411  angle = trajectory_tracker::angleNormalized(-(it_local_goal - 1)->yaw_);
412  status.angle_remains = angle;
413  if (it_local_goal != lpath.end())
414  arrive_local_goal = true;
415  }
416  v_lim_.set(
417  0.0,
418  linear_vel, acc_[0], dt);
419  w_lim_.set(
420  trajectory_tracker::timeOptimalControl(angle + w_lim_.get() * dt * 1.5, acc_toc_[1]),
421  vel_[1], acc_[1], dt);
422 
423  ROS_DEBUG(
424  "trajectory_tracker: angular residual %0.3f, angular vel %0.3f, tf delay %0.3f",
425  angle, w_lim_.get(), transform_delay);
426 
427  if (path_length < stop_tolerance_dist_ || in_place_turn_)
428  status.distance_remains = remain = 0.0;
429  }
430  else
431  {
432  // Too far from given path
433  float dist_from_path = dist_err;
434  if (i_nearest == 0)
435  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
436  else if (i_nearest + 1 >= static_cast<int>(path_.size()))
437  dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
438  if (std::abs(dist_from_path) > d_stop_)
439  {
440  geometry_msgs::Twist cmd_vel;
441  cmd_vel.linear.x = 0;
442  cmd_vel.angular.z = 0;
443  pub_vel_.publish(cmd_vel);
444  // ROS_WARN("Far from given path");
445  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
446  pub_status_.publish(status);
447  return;
448  }
449 
450  // Path following control
451  const float dist_err_clip = trajectory_tracker::clip(dist_err, d_lim_);
452 
453  v_lim_.set(
454  trajectory_tracker::timeOptimalControl(-remain_local * sign_vel, acc_toc_[0]),
455  linear_vel, acc_[0], dt);
456 
457  float wref = std::abs(v_lim_.get()) * curv;
458 
459  if (limit_vel_by_avel_ && std::abs(wref) > vel_[1])
460  {
461  v_lim_.set(
462  std::copysign(1.0, v_lim_.get()) * std::abs(vel_[1] / curv),
463  linear_vel, acc_[0], dt);
464  wref = std::copysign(1.0, wref) * vel_[1];
465  }
466 
467  const double k_ang = (gain_at_vel_ == 0.0) ? (k_[1]) : (k_[1] * linear_vel / gain_at_vel_);
469  dt * (-dist_err_clip * k_[0] - angle * k_ang - (w_lim_.get() - wref) * k_[2]),
470  vel_[1], acc_[1], dt);
471 
472  ROS_DEBUG(
473  "trajectory_tracker: distance residual %0.3f, angular residual %0.3f, ang vel residual %0.3f"
474  ", v_lim: %0.3f, sign_vel: %0.0f, angle: %0.3f, yaw: %0.3f",
475  dist_err_clip, angle, w_lim_.get() - wref, v_lim_.get(), sign_vel, angle, lpath[i_nearest].yaw_);
476  }
477 
478  geometry_msgs::Twist cmd_vel;
479  if (std::abs(status.distance_remains) < stop_tolerance_dist_ &&
480  std::abs(status.angle_remains) < stop_tolerance_ang_)
481  {
482  v_lim_.clear();
483  w_lim_.clear();
484  }
485 
486  cmd_vel.linear.x = v_lim_.get();
487  cmd_vel.angular.z = w_lim_.get();
488  pub_vel_.publish(cmd_vel);
489  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING;
490  if (std::abs(status.distance_remains) < goal_tolerance_dist_ &&
491  std::abs(status.angle_remains) < goal_tolerance_ang_)
492  {
493  status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
494  }
495  pub_status_.publish(status);
496  geometry_msgs::PoseStamped tracking;
497  tracking.header = status.header;
498  tracking.header.frame_id = frame_robot_;
499  tracking.pose.position.x = pos_on_line[0];
500  tracking.pose.position.y = pos_on_line[1];
501  tracking.pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -angle));
502  pub_tracking_.publish(tracking);
503 
504  path_step_done_ = i_nearest - 1; // i_nearest is the next of the nearest node
505  if (path_step_done_ < 0)
506  path_step_done_ = 0;
507  if (arrive_local_goal)
508  path_step_done_ = i_local_goal + 1;
509 }
510 
511 int main(int argc, char** argv)
512 {
513  ros::init(argc, argv, "trajectory_tracker");
514 
515  TrackerNode track;
516  track.spin();
517 
518  return 0;
519 }
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const
Definition: path2d.h:140
std::string frame_robot_
void publish(const boost::shared_ptr< M > &message) const
std::vector< Pose2D >::const_iterator ConstIterator
Definition: path2d.h:80
float set(float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:77
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_backward_motion) const
Definition: path2d.h:89
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double goal_tolerance_dist_
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())
tf2_ros::Buffer tfbuf_
ros::Publisher pub_tracking_
#define ROS_WARN(...)
void cbSpeed(const std_msgs::Float32::ConstPtr &)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
ros::NodeHandle pnh_
trajectory_tracker::VelAccLimitter w_lim_
ros::Publisher pub_vel_
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const
Definition: path2d.h:174
ros::Publisher pub_status_
tf2_ros::TransformListener tfl_
ros::Subscriber sub_path_
trajectory_tracker::VelAccLimitter v_lim_
ros::NodeHandle nh_
float lineDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:58
ros::Subscriber sub_path_velocity_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ERROR_THROTTLE(period,...)
void fromMsg(const A &, B &b)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
double goal_tolerance_ang_
std::string frame_odom_
void cbTimer(const ros::TimerEvent &)
double getYaw(const A &a)
Eigen::Vector2d projection2d(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Definition: eigen_line.h:78
B toMsg(const A &a)
ros::Subscriber sub_vel_
trajectory_tracker::Path2D path_
float increment(const float v, const float vel, const float acc, const float dt)
Definition: basic_control.h:72
std::string topic_path_
float length() const
Definition: path2d.h:82
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
std_msgs::Header path_header_
static Time now()
void cbPath(const typename MSG_TYPE::ConstPtr &)
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)
std::string topic_cmd_vel_
int main(int argc, char **argv)
float clip(const float v, const float max)
Definition: basic_control.h:43
ConstIterator findNearest(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target, const float max_search_range=0) const
Definition: path2d.h:111
#define ROS_DEBUG(...)


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:09