50 #include <Eigen/Geometry> 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> 66 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h> 67 #include <trajectory_tracker_msgs/PathWithVelocity.h> 126 template <
typename MSG_TYPE>
127 void cbPath(
const typename MSG_TYPE::ConstPtr&);
128 void cbSpeed(
const std_msgs::Float32::ConstPtr&);
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);
174 sub_path_ = neonavigation_common::compat::subscribe<nav_msgs::Path>(
177 boost::bind(&TrackerNode::cbPath<nav_msgs::Path>,
this, _1));
180 boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>,
this, _1));
184 pub_vel_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
187 pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>(
"status", 10);
188 pub_tracking_ = pnh_.advertise<geometry_msgs::PoseStamped>(
"tracking", 10);
192 geometry_msgs::Twist cmd_vel;
193 cmd_vel.linear.x = 0;
194 cmd_vel.angular.z = 0;
205 float getVelocity(
const geometry_msgs::PoseStamped& msg)
207 return std::numeric_limits<float>::quiet_NaN();
209 float getVelocity(
const trajectory_tracker_msgs::PoseStampedWithVelocity& msg)
211 return msg.linear_velocity.x;
215 template <
typename MSG_TYPE>
222 if (msg->poses.size() == 0)
225 auto j = msg->poses.begin();
227 for (
auto j = msg->poses.begin(); j != msg->poses.end(); ++j)
229 const float velocity = getVelocity(*j);
230 if (std::isfinite(velocity) && velocity < -0.0)
239 path_.push_back(next);
242 if (
path_.size() == 1)
245 msg->poses.back().pose, std::numeric_limits<float>::quiet_NaN());
247 while (
path_.size() < 3)
250 const float yaw =
path_.back().yaw_;
252 path_.back().pos_ + Eigen::Vector2d(std::cos(yaw), std::sin(yaw)) *
epsilon_,
253 yaw,
path_.back().velocity_);
254 path_.push_back(next);
272 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
274 status.distance_remains = 0.0;
275 status.angle_remains = 0.0;
281 geometry_msgs::Twist cmd_vel;
282 cmd_vel.linear.x = 0;
283 cmd_vel.angular.z = 0;
285 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
292 double transform_delay = 0;
300 transform *= trans_odom;
305 1.0,
"Timestamp of the transform is too old %f %f",
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);
318 trans *
path_[i].pos_, trans_yaw +
path_[i].yaw_,
path_[i].velocity_));
322 ROS_WARN(
"TF exception: %s", e.what());
323 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
329 const Eigen::Vector2d origin =
332 const double path_length = lpath.
length();
342 if (it_nearest == lpath.end())
346 geometry_msgs::Twist cmd_vel;
347 cmd_vel.linear.x = 0;
348 cmd_vel.angular.z = 0;
351 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
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);
361 const Eigen::Vector2d pos_on_line =
364 const float linear_vel =
365 std::isnan(lpath[i_nearest].velocity_) ?
vel_[0] : lpath[i_nearest].velocity_;
368 float remain_local = lpath.
remainedDistance(lpath.begin(), it_nearest, it_local_goal, pos_on_line);
370 float remain = lpath.
remainedDistance(lpath.begin(), it_nearest, lpath.end(), pos_on_line);
372 remain = remain_local = 0;
376 lpath[i_nearest - 1].pos_, lpath[i_nearest].pos_, origin);
379 const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest - 1].pos_;
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)
386 angle = angle + M_PI;
393 status.distance_remains = remain;
394 status.angle_remains = angle;
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);
400 bool arrive_local_goal(
false);
402 const float dt = 1.0 /
hz_;
412 status.angle_remains = angle;
413 if (it_local_goal != lpath.end())
414 arrive_local_goal =
true;
418 linear_vel,
acc_[0], dt);
424 "trajectory_tracker: angular residual %0.3f, angular vel %0.3f, tf delay %0.3f",
428 status.distance_remains = remain = 0.0;
433 float dist_from_path = dist_err;
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_)
440 geometry_msgs::Twist cmd_vel;
441 cmd_vel.linear.x = 0;
442 cmd_vel.angular.z = 0;
445 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
455 linear_vel,
acc_[0], dt);
457 float wref = std::abs(
v_lim_.
get()) * curv;
463 linear_vel,
acc_[0], dt);
464 wref = std::copysign(1.0, wref) *
vel_[1];
469 dt * (-dist_err_clip *
k_[0] - angle * k_ang - (
w_lim_.
get() - wref) *
k_[2]),
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_);
478 geometry_msgs::Twist cmd_vel;
489 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING;
493 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
496 geometry_msgs::PoseStamped tracking;
497 tracking.header = status.header;
499 tracking.pose.position.x = pos_on_line[0];
500 tracking.pose.position.y = pos_on_line[1];
507 if (arrive_local_goal)
511 int main(
int argc,
char** argv)
513 ros::init(argc, argv,
"trajectory_tracker");
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const
void publish(const boost::shared_ptr< M > &message) const
std::vector< Pose2D >::const_iterator ConstIterator
float set(float v, const float vel, const float acc, const float dt)
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_backward_motion) 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
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())
ros::Publisher pub_tracking_
void cbSpeed(const std_msgs::Float32::ConstPtr &)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
ROSCPP_DECL void spin(Spinner &spinner)
trajectory_tracker::VelAccLimitter w_lim_
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const
ros::Publisher pub_status_
tf2_ros::TransformListener tfl_
ros::Subscriber sub_path_
trajectory_tracker::VelAccLimitter v_lim_
float lineDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
ros::Subscriber sub_path_velocity_
bool param(const std::string ¶m_name, T ¶m_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_
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)
trajectory_tracker::Path2D path_
double stop_tolerance_dist_
float increment(const float v, const float vel, const float acc, const float dt)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
std_msgs::Header path_header_
void cbPath(const typename MSG_TYPE::ConstPtr &)
float angleNormalized(float ang)
float timeOptimalControl(const float angle, const float acc)
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)
std::string topic_cmd_vel_
int main(int argc, char **argv)
float clip(const float v, const float max)
ConstIterator findNearest(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target, const float max_search_range=0) const
double stop_tolerance_ang_