50 #include <Eigen/Geometry>
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>
67 #include <trajectory_tracker_msgs/PathWithVelocity.h>
68 #include <trajectory_tracker_msgs/TrajectoryTrackerStatus.h>
70 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
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&);
190 void cbParameter(
const TrajectoryTrackerConfig& config,
const uint32_t );
197 , is_path_updated_(false)
210 sub_path_ = neonavigation_common::compat::subscribe<nav_msgs::Path>(
213 boost::bind(&TrackerNode::cbPath<nav_msgs::Path>,
this, _1));
216 boost::bind(&TrackerNode::cbPath<trajectory_tracker_msgs::PathWithVelocity>,
this, _1));
220 pub_vel_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
240 k_[0] = config.k_dist;
241 k_[1] = config.k_ang;
242 k_[2] = config.k_avel;
247 vel_[0] = config.max_vel;
248 vel_[1] = config.max_angvel;
249 acc_[0] = config.max_acc;
250 acc_[1] = config.max_angacc;
274 geometry_msgs::Twist cmd_vel;
275 cmd_vel.linear.x = 0;
276 cmd_vel.angular.z = 0;
285 template <
typename MSG_TYPE>
292 for (
const auto& path_pose :
path_)
294 if (std::isfinite(path_pose.velocity_) && path_pose.velocity_ < -0.0)
307 ROS_WARN(
"frame_odom is invalid. Update from \"%s\" to \"%s\"",
frame_odom_.c_str(), odom->header.frame_id.c_str());
312 ROS_WARN(
"frame_robot is invalid. Update from \"%s\" to \"%s\"",
332 nav_msgs::Odometry odom_compensated = *odom;
333 Eigen::Vector3d prediction_offset(0, 0, 0);
336 const double predict_dt = std::max(0.0, std::min(
max_dt_, (
ros::Time::now() - odom->header.stamp).toSec()));
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);
341 prediction_offset[0] = odom->twist.twist.linear.x * predict_dt;
342 prediction_offset[2] = odom->twist.twist.angular.z * predict_dt;
347 tf2::toMsg(trans, odom_compensated.pose.pose);
351 tf2::fromMsg(odom_compensated.pose.pose, odom_to_robot);
353 control(odom_to_robot_stamped, prediction_offset, odom->twist.twist.linear.x, odom->twist.twist.angular.z, dt);
365 control(transform, Eigen::Vector3d(0, 0, 0), 0, 0, 1.0 /
hz_);
370 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
372 status.distance_remains = 0.0;
373 status.angle_remains = 0.0;
375 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
386 geometry_msgs::Twist cmd_vel;
387 cmd_vel.linear.x = 0.0;
388 cmd_vel.angular.z = 0.0;
391 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
393 status.distance_remains = 0.0;
394 status.angle_remains = 0.0;
396 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
412 const Eigen::Vector3d& prediction_offset,
413 const double odom_linear_vel,
414 const double odom_angular_vel,
417 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
424 getTrackingResult(odom_to_robot, prediction_offset, odom_linear_vel, odom_angular_vel);
429 getTrackingResult(odom_to_robot, prediction_offset, odom_linear_vel, odom_angular_vel);
430 switch (tracking_result.
status)
432 case trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH:
433 case trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH:
437 geometry_msgs::Twist cmd_vel;
438 cmd_vel.linear.x = 0;
439 cmd_vel.angular.z = 0;
451 const double expected_angle_remains =
457 const double wvel_increment =
462 "trajectory_tracker: angular residual %0.3f, angular vel %0.3f",
478 wref = std::copysign(1.0, wref) *
vel_[1];
485 const double wvel_diff =
w_lim_.
get() - wref;
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",
501 geometry_msgs::Twist cmd_vel;
509 status.status = tracking_result.
status;
517 const double odom_linear_vel,
const double odom_angular_vel)
const
521 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
525 double transform_delay = 0;
531 const tf2::Transform path_to_robot = path_to_odom * odom_to_robot;
536 1.0,
"Timestamp of the transform is too old %f %f",
540 const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> path_to_robot_2d =
541 Eigen::Translation2d(
543 Eigen::Rotation2Dd(robot_yaw);
544 const auto robot_to_path_2d = path_to_robot_2d.inverse();
549 robot_to_path_2d *
path_[i].pos_, -robot_yaw +
path_[i].yaw_,
path_[i].velocity_));
553 ROS_WARN(
"TF exception: %s", e.what());
554 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
557 const Eigen::Vector2d origin_raw = prediction_offset.head<2>();
558 const float yaw_raw = prediction_offset[2];
561 const Eigen::Vector2d origin =
564 const double path_length = lpath.
length();
575 if (it_nearest == lpath.end())
577 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
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);
584 const Eigen::Vector2d pos_on_line =
586 const Eigen::Vector2d pos_on_line_raw =
589 const float linear_vel =
590 std::isnan(lpath[i_nearest].velocity_) ?
vel_[0] : lpath[i_nearest].velocity_;
593 float remain_local = lpath.
remainedDistance(lpath.cbegin(), it_nearest, it_local_goal, pos_on_line);
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);
598 distance_remains = distance_remains_raw = remain_local = 0;
602 lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
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)
612 angle_remains = angle_remains + M_PI;
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);
623 bool arrive_local_goal(
false);
624 bool in_place_turning = (vec[1] == 0.0 && vec[0] == 0.0);
626 TrackingResult result(trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
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 ||
635 if (large_angle_error)
637 ROS_INFO_THROTTLE(1.0,
"Stop and rotate due to large angular error: %0.3f", angle_remains);
645 if (it_local_goal != lpath.end())
646 arrive_local_goal =
true;
649 distance_remains = distance_remains_raw = 0.0;
660 float dist_from_path = dist_err;
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_)
671 result.
status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
695 it_local_goal == lpath.end())
697 result.
status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
700 if (arrive_local_goal)
709 int main(
int argc,
char** argv)
711 ros::init(argc, argv,
"trajectory_tracker");