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 );
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>(
223 pub_status_ = pnh_.advertise<trajectory_tracker_msgs::TrajectoryTrackerStatus>(
"status", 10,
true);
224 pub_tracking_ = pnh_.advertise<geometry_msgs::PoseStamped>(
"tracking", 10,
true);
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;
287 float getVelocity(
const geometry_msgs::PoseStamped& msg)
289 return std::numeric_limits<float>::quiet_NaN();
291 float getVelocity(
const trajectory_tracker_msgs::PoseStampedWithVelocity& msg)
293 return msg.linear_velocity.x;
297 template <
typename MSG_TYPE>
304 if (msg->poses.size() == 0)
308 bool in_place_turning =
false;
310 auto j = msg->poses.begin();
312 for (++j; j < msg->poses.end(); ++j)
314 const float velocity = getVelocity(*j);
315 if (std::isfinite(velocity) && velocity < -0.0)
325 if (in_place_turning)
327 path_.push_back(in_place_turn_end);
328 in_place_turning =
false;
330 path_.push_back(next);
336 in_place_turning =
true;
339 if (in_place_turning)
340 path_.push_back(in_place_turn_end);
347 ROS_WARN(
"frame_odom is invalid. Update from \"%s\" to \"%s\"",
frame_odom_.c_str(), odom->header.frame_id.c_str());
352 ROS_WARN(
"frame_robot is invalid. Update from \"%s\" to \"%s\"",
372 nav_msgs::Odometry odom_compensated = *odom;
373 Eigen::Vector3d prediction_offset(0, 0, 0);
376 const double predict_dt = std::max(0.0, std::min(
max_dt_, (
ros::Time::now() - odom->header.stamp).toSec()));
378 const tf2::Quaternion rotation(tf2::Vector3(0, 0, 1), odom->twist.twist.angular.z * predict_dt);
379 const tf2::Vector3 translation(odom->twist.twist.linear.x * predict_dt, 0, 0);
381 prediction_offset[0] = odom->twist.twist.linear.x * predict_dt;
382 prediction_offset[2] = odom->twist.twist.angular.z * predict_dt;
387 tf2::toMsg(trans, odom_compensated.pose.pose);
391 tf2::fromMsg(odom_compensated.pose.pose, odom_to_robot);
394 odom->header.stamp, odom->header.frame_id);
396 control(robot_to_odom, prediction_offset, odom->twist.twist.linear.x, odom->twist.twist.angular.z, dt);
408 control(transform, Eigen::Vector3d(0, 0, 0), 0, 0, 1.0 /
hz_);
413 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
415 status.distance_remains = 0.0;
416 status.angle_remains = 0.0;
418 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
429 geometry_msgs::Twist cmd_vel;
430 cmd_vel.linear.x = 0.0;
431 cmd_vel.angular.z = 0.0;
434 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
436 status.distance_remains = 0.0;
437 status.angle_remains = 0.0;
439 status.status = trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH;
455 const Eigen::Vector3d& prediction_offset,
456 const double odom_linear_vel,
457 const double odom_angular_vel,
460 trajectory_tracker_msgs::TrajectoryTrackerStatus status;
467 getTrackingResult(robot_to_odom, prediction_offset, odom_linear_vel, odom_angular_vel);
472 getTrackingResult(robot_to_odom, prediction_offset, odom_linear_vel, odom_angular_vel);
473 switch (tracking_result.
status)
475 case trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH:
476 case trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH:
480 geometry_msgs::Twist cmd_vel;
481 cmd_vel.linear.x = 0;
482 cmd_vel.angular.z = 0;
494 const double expected_angle_remains =
500 const double wvel_increment =
505 "trajectory_tracker: angular residual %0.3f, angular vel %0.3f",
521 wref = std::copysign(1.0, wref) *
vel_[1];
528 const double wvel_diff =
w_lim_.
get() - wref;
532 "trajectory_tracker: distance residual %0.3f, angular residual %0.3f, ang vel residual %0.3f" 533 ", v_lim %0.3f, w_lim %0.3f signed_local_distance %0.3f, k_ang %0.3f",
544 geometry_msgs::Twist cmd_vel;
552 status.status = tracking_result.
status;
560 const double odom_linear_vel,
const double odom_angular_vel)
const 564 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
568 double transform_delay = 0;
575 transform *= odom_to_path;
580 1.0,
"Timestamp of the transform is too old %f %f",
584 const float trans_yaw =
tf2::getYaw(transform.getRotation());
585 const Eigen::Transform<double, 2, Eigen::TransformTraits::AffineCompact> trans =
586 Eigen::Translation2d(
587 Eigen::Vector2d(transform.getOrigin().x(), transform.getOrigin().y())) *
588 Eigen::Rotation2Dd(trans_yaw);
593 trans *
path_[i].pos_, trans_yaw +
path_[i].yaw_,
path_[i].velocity_));
597 ROS_WARN(
"TF exception: %s", e.what());
598 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
601 const Eigen::Vector2d origin_raw = prediction_offset.head<2>();
602 const float yaw_raw = prediction_offset[2];
605 const Eigen::Vector2d origin =
608 const double path_length = lpath.
length();
619 if (it_nearest == lpath.end())
621 return TrackingResult(trajectory_tracker_msgs::TrajectoryTrackerStatus::NO_PATH);
624 const int i_nearest = std::distance(lpath.cbegin(), it_nearest);
625 const int i_nearest_prev = std::max(0, i_nearest - 1);
626 const int i_local_goal = std::distance(lpath.cbegin(), it_local_goal);
628 const Eigen::Vector2d pos_on_line =
630 const Eigen::Vector2d pos_on_line_raw =
633 const float linear_vel =
634 std::isnan(lpath[i_nearest].velocity_) ?
vel_[0] : lpath[i_nearest].velocity_;
637 float remain_local = lpath.
remainedDistance(lpath.cbegin(), it_nearest, it_local_goal, pos_on_line);
639 float distance_remains = lpath.
remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line);
640 float distance_remains_raw = lpath.
remainedDistance(lpath.cbegin(), it_nearest, lpath.cend(), pos_on_line_raw);
642 distance_remains = distance_remains_raw = remain_local = 0;
646 lpath[i_nearest_prev].pos_, lpath[i_nearest].pos_, origin);
649 const Eigen::Vector2d vec = lpath[i_nearest].pos_ - lpath[i_nearest_prev].pos_;
650 float angle_remains = -
atan2(vec[1], vec[0]);
651 const float angle_pose =
allow_backward_ ? lpath[i_nearest].yaw_ : -angle_remains;
652 float sign_vel = 1.0;
653 if (std::cos(-angle_remains) * std::cos(angle_pose) + std::sin(-angle_remains) * std::sin(angle_pose) < 0)
656 angle_remains = angle_remains + M_PI;
664 "trajectory_tracker: nearest: %d, local goal: %d, done: %d, goal: %lu, remain: %0.3f, remain_local: %0.3f",
665 i_nearest, i_local_goal,
path_step_done_, lpath.size(), distance_remains, remain_local);
667 bool arrive_local_goal(
false);
668 bool in_place_turning = (vec[1] == 0.0 && vec[0] == 0.0);
670 TrackingResult result(trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
673 const bool large_angle_error = std::abs(
rotate_ang_) < M_PI && std::cos(
rotate_ang_) > std::cos(angle_remains);
674 if (large_angle_error ||
679 if (large_angle_error)
681 ROS_INFO_THROTTLE(1.0,
"Stop and rotate due to large angular error: %0.3f", angle_remains);
689 if (it_local_goal != lpath.end())
690 arrive_local_goal =
true;
693 distance_remains = distance_remains_raw = 0.0;
704 float dist_from_path = dist_err;
706 dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
707 else if (i_nearest + 1 >= static_cast<int>(
path_.size()))
708 dist_from_path = -(lpath[i_nearest].pos_ - origin).norm();
709 if (std::abs(dist_from_path) >
d_stop_)
715 result.
status = trajectory_tracker_msgs::TrajectoryTrackerStatus::FAR_FROM_PATH;
739 it_local_goal == lpath.end())
741 result.
status = trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL;
744 if (arrive_local_goal)
753 int main(
int argc,
char** argv)
755 ros::init(argc, argv,
"trajectory_tracker");
bool use_time_optimal_control_
void cbSpeed(const std_msgs::Float32::ConstPtr &)
ros::Publisher pub_status_
TrackingResult(const int s)
ConstIterator findNearest(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target, const float max_search_range=0, const float epsilon=1e-6) const
void cbOdomTimeout(const ros::TimerEvent &)
TransportHints & reliable()
void cbParameter(const TrajectoryTrackerConfig &config, const uint32_t)
double goal_tolerance_lin_vel_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
double goal_tolerance_dist_
void cbTimer(const ros::TimerEvent &)
ros::Publisher pub_tracking_
trajectory_tracker::Path2D path_
std::vector< Pose2D >::const_iterator ConstIterator
float set(float v, const float vel, const float acc, const float dt)
std_msgs::Header path_header_
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const
dynamic_reconfigure::Server< TrajectoryTrackerConfig > parameter_server_
void setPeriod(const Duration &period, bool reset=true)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
trajectory_tracker::VelAccLimitter w_lim_
boost::recursive_mutex parameter_server_mutex_
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())
void control(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double, const double)
ros::Subscriber sub_odom_
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_backward_motion) const
ros::Timer odom_timeout_timer_
tf2_ros::TransformListener tfl_
double time_optimal_control_future_gain_
std::string topic_cmd_vel_
TransportHints & tcpNoDelay(bool nodelay=true)
double stop_tolerance_dist_
double signed_local_distance
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) 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
void publish(const boost::shared_ptr< M > &message) const
double distance_remains_raw
#define ROS_INFO_THROTTLE(period,...)
#define ROS_WARN_THROTTLE(period,...)
float lineDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
#define ROS_ERROR_THROTTLE(period,...)
void fromMsg(const A &, B &b)
trajectory_tracker::VelAccLimitter v_lim_
void cbPath(const typename MSG_TYPE::ConstPtr &)
ros::Time prev_odom_stamp_
#define ROS_WARN_STREAM(args)
double distance_from_target
double getYaw(const A &a)
Eigen::Vector2d projection2d(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
void cbOdometry(const nav_msgs::Odometry::ConstPtr &)
ros::Subscriber sub_path_velocity_
double stop_tolerance_ang_
TrackingResult getTrackingResult(const tf2::Stamped< tf2::Transform > &, const Eigen::Vector3d &, const double, const double) const
double tracking_point_curv
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)
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const
float angleNormalized(float ang)
double goal_tolerance_ang_vel_
float timeOptimalControl(const float angle, const float acc)
void deprecatedParam(const ros::NodeHandle &nh, const std::string &key, T ¶m, const T &default_value)
double goal_tolerance_ang_
int main(int argc, char **argv)
float clip(const float v, const float max)
ros::Subscriber sub_path_