trajectory_tracker.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014, ATR, Atsushi Watanabe
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*
00031    * This research was supported by a contract with the Ministry of Internal
00032    Affairs and Communications entitled, 'Novel and innovative R&D making use
00033    of brain structures'
00034 
00035    This software was implemented to accomplish the above research.
00036    Original idea of the implemented control scheme was published on:
00037    S. Iida, S. Yuta, "Vehicle command system and trajectory control for
00038    autonomous mobile robots," in Proceedings of the 1991 IEEE/RSJ
00039    International Workshop on Intelligent Robots and Systems (IROS),
00040    1991, pp. 212-217.
00041  */
00042 
00043 #include <algorithm>
00044 #include <cmath>
00045 #include <limits>
00046 #include <string>
00047 #include <vector>
00048 
00049 #include <Eigen/Core>
00050 #include <Eigen/Geometry>
00051 
00052 #include <ros/ros.h>
00053 
00054 #include <geometry_msgs/Twist.h>
00055 #include <geometry_msgs/PoseStamped.h>
00056 #include <nav_msgs/Odometry.h>
00057 #include <nav_msgs/Path.h>
00058 #include <std_msgs/Float32.h>
00059 #include <std_msgs/Header.h>
00060 
00061 #include <tf2/utils.h>
00062 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00063 #include <tf2_ros/transform_listener.h>
00064 
00065 #include <neonavigation_common/compatibility.h>
00066 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
00067 #include <trajectory_tracker_msgs/PathWithVelocity.h>
00068 
00069 #include <trajectory_tracker/basic_control.h>
00070 #include <trajectory_tracker/eigen_line.h>
00071 #include <trajectory_tracker/path2d.h>
00072 
00073 class TrackerNode
00074 {
00075 public:
00076   TrackerNode();
00077   ~TrackerNode();
00078   void spin();
00079 
00080 private:
00081   std::string topic_path_;
00082   std::string topic_cmd_vel_;
00083   std::string frame_robot_;
00084   std::string frame_odom_;
00085   double hz_;
00086   double look_forward_;
00087   double curv_forward_;
00088   double k_[3];
00089   double gain_at_vel_;
00090   double d_lim_;
00091   double d_stop_;
00092   double vel_[2];
00093   double acc_[2];
00094   double acc_toc_[2];
00095   trajectory_tracker::VelAccLimitter v_lim_;
00096   trajectory_tracker::VelAccLimitter w_lim_;
00097   double rotate_ang_;
00098   double goal_tolerance_dist_;
00099   double goal_tolerance_ang_;
00100   double stop_tolerance_dist_;
00101   double stop_tolerance_ang_;
00102   double no_pos_cntl_dist_;
00103   double min_track_path_;
00104   int path_step_;
00105   int path_step_done_;
00106   bool allow_backward_;
00107   bool limit_vel_by_avel_;
00108   bool check_old_path_;
00109   double epsilon_;
00110   bool in_place_turn_;
00111 
00112   ros::Subscriber sub_path_;
00113   ros::Subscriber sub_path_velocity_;
00114   ros::Subscriber sub_vel_;
00115   ros::Publisher pub_vel_;
00116   ros::Publisher pub_status_;
00117   ros::Publisher pub_tracking_;
00118   ros::NodeHandle nh_;
00119   ros::NodeHandle pnh_;
00120   tf2_ros::Buffer tfbuf_;
00121   tf2_ros::TransformListener tfl_;
00122 
00123   trajectory_tracker::Path2D path_;
00124   std_msgs::Header path_header_;
00125 
00126   template <typename MSG_TYPE>
00127   void cbPath(const typename MSG_TYPE::ConstPtr&);
00128   void cbSpeed(const std_msgs::Float32::ConstPtr&);
00129   void cbTimer(const ros::TimerEvent&);
00130   void control();
00131 };
00132 
00133 TrackerNode::TrackerNode()
00134   : nh_()
00135   , pnh_("~")
00136   , tfl_(tfbuf_)
00137 {
00138   neonavigation_common::compat::checkCompatMode();
00139   pnh_.param("frame_robot", frame_robot_, std::string("base_link"));
00140   pnh_.param("frame_odom", frame_odom_, std::string("odom"));
00141   neonavigation_common::compat::deprecatedParam(pnh_, "path", topic_path_, std::string("path"));
00142   neonavigation_common::compat::deprecatedParam(pnh_, "cmd_vel", topic_cmd_vel_, std::string("cmd_vel"));
00143   pnh_.param("hz", hz_, 50.0);
00144   pnh_.param("look_forward", look_forward_, 0.5);
00145   pnh_.param("curv_forward", curv_forward_, 0.5);
00146   pnh_.param("k_dist", k_[0], 1.0);
00147   pnh_.param("k_ang", k_[1], 1.0);
00148   pnh_.param("k_avel", k_[2], 1.0);
00149   pnh_.param("gain_at_vel", gain_at_vel_, 0.0);
00150   pnh_.param("dist_lim", d_lim_, 0.5);
00151   pnh_.param("dist_stop", d_stop_, 2.0);
00152   pnh_.param("rotate_ang", rotate_ang_, M_PI / 4);
00153   pnh_.param("max_vel", vel_[0], 0.5);
00154   pnh_.param("max_angvel", vel_[1], 1.0);
00155   pnh_.param("max_acc", acc_[0], 1.0);
00156   pnh_.param("max_angacc", acc_[1], 2.0);
00157   double acc_toc_factor[2];
00158   pnh_.param("acc_toc_factor", acc_toc_factor[0], 0.9);
00159   pnh_.param("angacc_toc_factor", acc_toc_factor[1], 0.9);
00160   acc_toc_[0] = acc_[0] * acc_toc_factor[0];
00161   acc_toc_[1] = acc_[1] * acc_toc_factor[1];
00162   pnh_.param("path_step", path_step_, 1);
00163   pnh_.param("goal_tolerance_dist", goal_tolerance_dist_, 0.2);
00164   pnh_.param("goal_tolerance_ang", goal_tolerance_ang_, 0.1);
00165   pnh_.param("stop_tolerance_dist", stop_tolerance_dist_, 0.1);
00166   pnh_.param("stop_tolerance_ang", stop_tolerance_ang_, 0.05);
00167   pnh_.param("no_position_control_dist", no_pos_cntl_dist_, 0.0);
00168   pnh_.param("min_tracking_path", min_track_path_, no_pos_cntl_dist_);
00169   pnh_.param("allow_backward", allow_backward_, true);
00170   pnh_.param("limit_vel_by_avel", limit_vel_by_avel_, false);
00171   pnh_.param("check_old_path", check_old_path_, false);
00172   pnh_.param("epsilon", epsilon_, 0.001);
00173 
00174   sub_path_ = neonavigation_common::compat::subscribe<nav_msgs::Path>(
00175       nh_, "path",
00176       pnh_, topic_path_, 2,
00177       boost::bind(&TrackerNode::cbPath<nav_msgs::Path>, this, _1));
00178   sub_path_velocity_ = nh_.subscribe<trajectory_tracker_msgs::PathWithVelocity>(
00179       "path_velocity", 2,
00180       boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>, this, _1));
00181   sub_vel_ = neonavigation_common::compat::subscribe(
00182       nh_, "speed",
00183       pnh_, "speed", 20, &TrackerNode::cbSpeed, this);
00184   pub_vel_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
00185       nh_, "cmd_vel",
00186       pnh_, topic_cmd_vel_, 10);
00187   pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>("status", 10);
00188   pub_tracking_ = pnh_.advertise<geometry_msgs::PoseStamped>("tracking", 10);
00189 }
00190 TrackerNode::~TrackerNode()
00191 {
00192   geometry_msgs::Twist cmd_vel;
00193   cmd_vel.linear.x = 0;
00194   cmd_vel.angular.z = 0;
00195   pub_vel_.publish(cmd_vel);
00196 }
00197 
00198 void TrackerNode::cbSpeed(const std_msgs::Float32::ConstPtr& msg)
00199 {
00200   vel_[0] = msg->data;
00201 }
00202 
00203 namespace
00204 {
00205 float getVelocity(const geometry_msgs::PoseStamped& msg)
00206 {
00207   return std::numeric_limits<float>::quiet_NaN();
00208 }
00209 float getVelocity(const trajectory_tracker_msgs::PoseStampedWithVelocity& msg)
00210 {
00211   return msg.linear_velocity.x;
00212 }
00213 }  // namespace
00214 
00215 template <typename MSG_TYPE>
00216 void TrackerNode::cbPath(const typename MSG_TYPE::ConstPtr& msg)
00217 {
00218   path_header_ = msg->header;
00219   path_.clear();
00220   path_step_done_ = 0;
00221   in_place_turn_ = false;
00222   if (msg->poses.size() == 0)
00223     return;
00224 
00225   auto j = msg->poses.begin();
00226   path_.push_back(trajectory_tracker::Pose2D(j->pose, getVelocity(*j)));
00227   for (auto j = msg->poses.begin(); j != msg->poses.end(); ++j)
00228   {
00229     const float velocity = getVelocity(*j);
00230     if (std::isfinite(velocity) && velocity < -0.0)
00231     {
00232       ROS_ERROR_THROTTLE(1.0, "path_velocity.velocity.x must be positive");
00233       path_.clear();
00234       return;
00235     }
00236     const trajectory_tracker::Pose2D next(j->pose, velocity);
00237 
00238     if ((path_.back().pos_ - next.pos_).squaredNorm() >= std::pow(epsilon_, 2))
00239       path_.push_back(next);
00240   }
00241 
00242   if (path_.size() == 1)
00243   {
00244     path_.back() = trajectory_tracker::Pose2D(
00245         msg->poses.back().pose, std::numeric_limits<float>::quiet_NaN());
00246     in_place_turn_ = true;
00247     while (path_.size() < 3)
00248     {
00249       // to make line direction computable, line should have a few points
00250       const float yaw = path_.back().yaw_;
00251       const trajectory_tracker::Pose2D next(
00252           path_.back().pos_ + Eigen::Vector2d(std::cos(yaw), std::sin(yaw)) * epsilon_,
00253           yaw, path_.back().velocity_);
00254       path_.push_back(next);
00255     }
00256   }
00257 }
00258 void TrackerNode::cbTimer(const ros::TimerEvent& event)
00259 {
00260   control();
00261 }
00262 
00263 void TrackerNode::spin()
00264 {
00265   ros::Timer timer = nh_.createTimer(ros::Duration(1.0 / hz_), &TrackerNode::cbTimer, this);
00266 
00267   ros::spin();
00268 }
00269 
00270 void TrackerNode::control()
00271 {
00272   trajectory_tracker_msgs::TrajectoryTrackerStatus status;
00273   status.header.stamp = ros::Time::now();
00274   status.distance_remains = 0.0;
00275   status.angle_remains = 0.0;
00276 
00277   if (path_header_.frame_id.size() == 0 || path_.size() == 0)
00278   {
00279     v_lim_.clear();
00280     w_lim_.clear();
00281     geometry_msgs::Twist cmd_vel;
00282     cmd_vel.linear.x = 0;
00283     cmd_vel.angular.z = 0;
00284     pub_vel_.publish(cmd_vel);
00285     status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
00286     pub_status_.publish(status);
00287     return;
00288   }
00289   // Transform
00290   trajectory_tracker::Path2D lpath;
00291   tf2::Stamped<tf2::Transform> transform;
00292   double transform_delay = 0;
00293   try
00294   {
00295     tf2::Stamped<tf2::Transform> trans_odom;
00296     tf2::fromMsg(
00297         tfbuf_.lookupTransform(frame_robot_, frame_odom_, ros::Time(0)), transform);
00298     tf2::fromMsg(
00299         tfbuf_.lookupTransform(frame_odom_, path_header_.frame_id, ros::Time(0)), trans_odom);
00300     transform *= trans_odom;
00301     transform_delay = (ros::Time::now() - transform.stamp_).toSec();
00302     if (std::abs(transform_delay) > 0.1 && check_old_path_)
00303     {
00304       ROS_ERROR_THROTTLE(
00305           1.0, "Timestamp of the transform is too old %f %f",
00306           ros::Time::now().toSec(), transform.stamp_.toSec());
00307     }
00308 
00309     const float trans_yaw = tf2::getYaw(transform.getRotation());
00310     const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> trans =
00311         Eigen::Translation2d(
00312             Eigen::Vector2d(transform.getOrigin().x(), transform.getOrigin().y())) *
00313         Eigen::Rotation2Dd(trans_yaw);
00314 
00315     for (size_t i = 0; i < path_.size(); i += path_step_)
00316       lpath.push_back(
00317           trajectory_tracker::Pose2D(
00318               trans * path_[i].pos_, trans_yaw + path_[i].yaw_, path_[i].velocity_));
00319   }
00320   catch (tf2::TransformException& e)
00321   {
00322     ROS_WARN("TF exception: %s", e.what());
00323     status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
00324     pub_status_.publish(status);
00325     return;
00326   }
00327 
00328   const float predicted_yaw = w_lim_.get() * look_forward_ / 2;
00329   const Eigen::Vector2d origin =
00330       Eigen::Vector2d(std::cos(predicted_yaw), std::sin(predicted_yaw)) * v_lim_.get() * look_forward_;
00331 
00332   const double path_length = lpath.length();
00333 
00334   // Find nearest line strip
00335   const trajectory_tracker::Path2D::ConstIterator it_local_goal =
00336       lpath.findLocalGoal(lpath.begin() + path_step_done_, lpath.end(), allow_backward_);
00337 
00338   const float max_search_range = (path_step_done_ > 0) ? 1.0 : 0.0;
00339   const trajectory_tracker::Path2D::ConstIterator it_nearest =
00340       lpath.findNearest(lpath.begin() + path_step_done_, it_local_goal, origin, max_search_range);
00341 
00342   if (it_nearest == lpath.end())
00343   {
00344     v_lim_.clear();
00345     w_lim_.clear();
00346     geometry_msgs::Twist cmd_vel;
00347     cmd_vel.linear.x = 0;
00348     cmd_vel.angular.z = 0;
00349     pub_vel_.publish(cmd_vel);
00350     // ROS_WARN("failed to find nearest node");
00351     status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
00352     pub_status_.publish(status);
00353     return;
00354   }
00355 
00356   const int i_nearest = std::distance(
00357       static_cast<trajectory_tracker::Path2D::ConstIterator>(lpath.begin()), it_nearest);
00358   const int i_local_goal = std::distance(
00359       static_cast<trajectory_tracker::Path2D::ConstIterator>(lpath.begin()), it_local_goal);
00360 
00361   const Eigen::Vector2d pos_on_line =
00362       trajectory_tracker::projection2d(lpath[i_nearest - 1].pos_, lpath[i_nearest].pos_, origin);
00363 
00364   const float linear_vel =
00365       std::isnan(lpath[i_nearest].velocity_) ? vel_[0] : lpath[i_nearest].velocity_;
00366 
00367   // Remained distance to the local goal
00368   float remain_local = lpath.remainedDistance(lpath.begin(), it_nearest, it_local_goal, pos_on_line);
00369   // Remained distance to the final goal
00370   float remain = lpath.remainedDistance(lpath.begin(), it_nearest, lpath.end(), pos_on_line);
00371   if (path_length < no_pos_cntl_dist_)
00372     remain = remain_local = 0;
00373 
00374   // Signed distance error
00375   const float dist_err = trajectory_tracker::lineDistance(
00376       lpath[i_nearest - 1].pos_, lpath[i_nearest].pos_, origin);
00377 
00378   // Angular error
00379   const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest - 1].pos_;
00380   float angle = -atan2(vec[1], vec[0]);
00381   const float angle_pose = allow_backward_ ? lpath[i_nearest].yaw_ : -angle;
00382   float sign_vel = 1.0;
00383   if (std::cos(-angle) * std::cos(angle_pose) + std::sin(-angle) * std::sin(angle_pose) < 0)
00384   {
00385     sign_vel = -1.0;
00386     angle = angle + M_PI;
00387   }
00388   angle = trajectory_tracker::angleNormalized(angle);
00389 
00390   // Curvature
00391   const float curv = lpath.getCurvature(it_nearest, it_local_goal, pos_on_line, curv_forward_);
00392 
00393   status.distance_remains = remain;
00394   status.angle_remains = angle;
00395 
00396   ROS_DEBUG(
00397       "trajectory_tracker: nearest: %d, local goal: %d, done: %d, goal: %lu, remain: %0.3f, remain_local: %0.3f",
00398       i_nearest, i_local_goal, path_step_done_, lpath.size(), remain, remain_local);
00399 
00400   bool arrive_local_goal(false);
00401 
00402   const float dt = 1.0 / hz_;
00403   // Stop and rotate
00404   if ((std::abs(rotate_ang_) < M_PI && std::cos(rotate_ang_) > std::cos(angle)) ||
00405       std::abs(remain_local) < stop_tolerance_dist_ ||
00406       path_length < min_track_path_ ||
00407       in_place_turn_)
00408   {
00409     if (path_length < min_track_path_ || std::abs(remain_local) < stop_tolerance_dist_)
00410     {
00411       angle = trajectory_tracker::angleNormalized(-(it_local_goal - 1)->yaw_);
00412       status.angle_remains = angle;
00413       if (it_local_goal != lpath.end())
00414         arrive_local_goal = true;
00415     }
00416     v_lim_.set(
00417         0.0,
00418         linear_vel, acc_[0], dt);
00419     w_lim_.set(
00420         trajectory_tracker::timeOptimalControl(angle + w_lim_.get() * dt * 1.5, acc_toc_[1]),
00421         vel_[1], acc_[1], dt);
00422 
00423     ROS_DEBUG(
00424         "trajectory_tracker: angular residual %0.3f, angular vel %0.3f, tf delay %0.3f",
00425         angle, w_lim_.get(), transform_delay);
00426 
00427     if (path_length < stop_tolerance_dist_ || in_place_turn_)
00428       status.distance_remains = remain = 0.0;
00429   }
00430   else
00431   {
00432     // Too far from given path
00433     float dist_from_path = dist_err;
00434     if (i_nearest == 0)
00435       dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
00436     else if (i_nearest + 1 >= static_cast<int>(path_.size()))
00437       dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
00438     if (std::abs(dist_from_path) > d_stop_)
00439     {
00440       geometry_msgs::Twist cmd_vel;
00441       cmd_vel.linear.x = 0;
00442       cmd_vel.angular.z = 0;
00443       pub_vel_.publish(cmd_vel);
00444       // ROS_WARN("Far from given path");
00445       status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
00446       pub_status_.publish(status);
00447       return;
00448     }
00449 
00450     // Path following control
00451     const float dist_err_clip = trajectory_tracker::clip(dist_err, d_lim_);
00452 
00453     v_lim_.set(
00454         trajectory_tracker::timeOptimalControl(-remain_local * sign_vel, acc_toc_[0]),
00455         linear_vel, acc_[0], dt);
00456 
00457     float wref = std::abs(v_lim_.get()) * curv;
00458 
00459     if (limit_vel_by_avel_ && std::abs(wref) > vel_[1])
00460     {
00461       v_lim_.set(
00462           std::copysign(1.0, v_lim_.get()) * std::abs(vel_[1] / curv),
00463           linear_vel, acc_[0], dt);
00464       wref = std::copysign(1.0, wref) * vel_[1];
00465     }
00466 
00467     const double k_ang = (gain_at_vel_ == 0.0) ? (k_[1]) : (k_[1] * linear_vel / gain_at_vel_);
00468     w_lim_.increment(
00469         dt * (-dist_err_clip * k_[0] - angle * k_ang - (w_lim_.get() - wref) * k_[2]),
00470         vel_[1], acc_[1], dt);
00471 
00472     ROS_DEBUG(
00473         "trajectory_tracker: distance residual %0.3f, angular residual %0.3f, ang vel residual %0.3f"
00474         ", v_lim: %0.3f, sign_vel: %0.0f, angle: %0.3f, yaw: %0.3f",
00475         dist_err_clip, angle, w_lim_.get() - wref, v_lim_.get(), sign_vel, angle, lpath[i_nearest].yaw_);
00476   }
00477 
00478   geometry_msgs::Twist cmd_vel;
00479   if (std::abs(status.distance_remains) < stop_tolerance_dist_ &&
00480       std::abs(status.angle_remains) < stop_tolerance_ang_)
00481   {
00482     v_lim_.clear();
00483     w_lim_.clear();
00484   }
00485 
00486   cmd_vel.linear.x = v_lim_.get();
00487   cmd_vel.angular.z = w_lim_.get();
00488   pub_vel_.publish(cmd_vel);
00489   status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING;
00490   if (std::abs(status.distance_remains) < goal_tolerance_dist_ &&
00491       std::abs(status.angle_remains) < goal_tolerance_ang_)
00492   {
00493     status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
00494   }
00495   pub_status_.publish(status);
00496   geometry_msgs::PoseStamped tracking;
00497   tracking.header = status.header;
00498   tracking.header.frame_id = frame_robot_;
00499   tracking.pose.position.x = pos_on_line[0];
00500   tracking.pose.position.y = pos_on_line[1];
00501   tracking.pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -angle));
00502   pub_tracking_.publish(tracking);
00503 
00504   path_step_done_ = i_nearest - 1;  // i_nearest is the next of the nearest node
00505   if (path_step_done_ < 0)
00506     path_step_done_ = 0;
00507   if (arrive_local_goal)
00508     path_step_done_ = i_local_goal + 1;
00509 }
00510 
00511 int main(int argc, char** argv)
00512 {
00513   ros::init(argc, argv, "trajectory_tracker");
00514 
00515   TrackerNode track;
00516   track.spin();
00517 
00518   return 0;
00519 }


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:25