30 #ifndef TRAJECTORY_TRACKER_PATH2D_H    31 #define TRAJECTORY_TRACKER_PATH2D_H    37 #include <Eigen/Geometry>    39 #include <geometry_msgs/Pose.h>    60   inline Pose2D(
const Eigen::Vector2d& p, 
float y, 
float velocity)
    66   inline explicit Pose2D(
const geometry_msgs::Pose& pose, 
float velocity)
    67     : pos_(Eigen::Vector2d(pose.position.
x, pose.position.
y))
    73 class Path2D : 
public std::vector<Pose2D>
    76   using Super = std::vector<Pose2D>;
    79   using Iterator = std::vector<Pose2D>::iterator;
    85     for (
size_t i = 1; i < size(); i++)
    86       l += ((*
this)[i - 1].pos_ - (*this)[i].pos_).norm();
    92       const bool allow_backward_motion)
 const    94     float sign_vel_prev = 0;
    98       const Eigen::Vector2d inc = it->pos_ - it_prev->pos_;
   102       const float angle_pose = allow_backward_motion ? it->yaw_ : angle;
   103       const float sign_vel_req = std::cos(angle) * std::cos(angle_pose) + std::sin(angle) * std::sin(angle_pose);
   104       if (sign_vel_prev * sign_vel_req < 0)
   106       sign_vel_prev = sign_vel_req;
   114       const Eigen::Vector2d& target,
   115       const float max_search_range = 0)
 const   117     float distance_path_search = 0;
   118     float min_dist = std::numeric_limits<float>::max();
   124       const Eigen::Vector2d inc = it->pos_ - it_prev->pos_;
   125       distance_path_search += inc.norm();
   126       if (max_search_range > 0 && distance_path_search > max_search_range)
   144       const Eigen::Vector2d& target_on_line)
 const   146     double remain = (nearest->pos_ - target_on_line).norm();
   147     if (nearest + 1 >= end)
   151       if (last_pre < begin || last < begin)
   156       const Eigen::Vector2d vec_path = last->pos_ - last_pre->pos_;
   157       const Eigen::Vector2d vec_remain = last->pos_ - target_on_line;
   158       if (vec_path.dot(vec_remain) >= 0)
   169       remain += (it_prev->pos_ - it->pos_).norm();
   177       const Eigen::Vector2d& target_on_line,
   178       const float max_search_range)
 const   180     const float max_search_range_sq = max_search_range * max_search_range;
   187       if ((it->pos_ - target_on_line).squaredNorm() > max_search_range_sq)
   197 #endif  // TRAJECTORY_TRACKER_PATH2D_H 
double remainedDistance(const ConstIterator &begin, const ConstIterator &nearest, const ConstIterator &end, const Eigen::Vector2d &target_on_line) const 
std::vector< Pose2D >::const_iterator ConstIterator
ConstIterator findLocalGoal(const ConstIterator &begin, const ConstIterator &end, const bool allow_backward_motion) const 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
float getCurvature(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target_on_line, const float max_search_range) const 
std::vector< Pose2D > Super
std::vector< Pose2D >::iterator Iterator
float curv3p(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
TFSIMD_FORCE_INLINE const tfScalar & x() const 
double getYaw(const tf2::Quaternion &q)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
Pose2D(const Eigen::Vector2d &p, float y, float velocity)
float lineStripDistance(const Eigen::Vector2d &a, const Eigen::Vector2d &b, const Eigen::Vector2d &c)
Pose2D(const geometry_msgs::Pose &pose, float velocity)
ConstIterator findNearest(const ConstIterator &begin, const ConstIterator &end, const Eigen::Vector2d &target, const float max_search_range=0) const