Autoware.Auto
|
|
Typedefs | |
typedef autoware_auto_planning_msgs::msg::TrajectoryPoint | Point |
typedef Eigen::Matrix< float64_t, 3, 1 > | Vector3f |
Functions | |
MOTION_COMMON_PUBLIC void | validateNonEmpty (const Points &points) |
throws an exception if the given list of points is empty More... | |
MOTION_COMMON_PUBLIC float64_t | calcYawDeviation (const float64_t &base_yaw, const float64_t &target_yaw) |
calculate the yaw deviation between two angles More... | |
MOTION_COMMON_PUBLIC std::experimental::optional< size_t > | searchZeroVelocityIndex (const Points &points, const size_t src_idx, const size_t dst_idx, const float64_t epsilon=1e-3) |
search first index with a velocity of zero in the given range of points More... | |
MOTION_COMMON_PUBLIC std::experimental::optional< size_t > | searchZeroVelocityIndex (const Points &points) |
search first index with a velocity of zero in the given points More... | |
MOTION_COMMON_PUBLIC size_t | findNearestIndex (const Points &points, const geometry_msgs::msg::Point &point) |
search the index of the point nearest to the given target More... | |
MOTION_COMMON_PUBLIC std::experimental::optional< size_t > | findNearestIndex (const Points &points, const geometry_msgs::msg::Pose &pose, const float64_t max_dist=std::numeric_limits< float64_t >::max(), const float64_t max_yaw=std::numeric_limits< float64_t >::max()) |
search the index of the point nearest to the given target with limits on the distance and yaw deviation More... | |
MOTION_COMMON_PUBLIC float64_t | calcLongitudinalOffsetToSegment (const Points &points, const size_t seg_idx, const geometry_msgs::msg::Point &p_target) |
calculate length along trajectory from seg_idx point to nearest point to p_target on trajectory If seg_idx point is after that nearest point, length is negative More... | |
MOTION_COMMON_PUBLIC size_t | findNearestSegmentIndex (const Points &points, const geometry_msgs::msg::Point &point) |
find nearest segment index to point segment is straight path between two continuous points of trajectory When point is on a trajectory point whose index is nearest_idx, return nearest_idx - 1 More... | |
MOTION_COMMON_PUBLIC float64_t | calcSignedArcLength (const Points &points, const size_t src_idx, const size_t dst_idx) |
calculate arc length along points More... | |
MOTION_COMMON_PUBLIC float64_t | calcSignedArcLength (const Points &points, const geometry_msgs::msg::Point &src_point, const size_t &dst_idx) |
calculate arc length along points More... | |
MOTION_COMMON_PUBLIC float64_t | calcSignedArcLength (const Points &points, const geometry_msgs::msg::Point &src_point, const geometry_msgs::msg::Point &dst_point) |
calculate arc length along points More... | |
MOTION_COMMON_PUBLIC float64_t | calcLongitudinalDeviation (const geometry_msgs::msg::Pose &base_pose, const geometry_msgs::msg::Point &target_point) |
calculate longitudinal deviation of a point relative to a pose More... | |
Variables | |
decltype(autoware_auto_planning_msgs::msg::Trajectory::points) typedef | Points |
typedef autoware_auto_planning_msgs::msg::TrajectoryPoint autoware::motion::motion_common::Point |
typedef Eigen::Matrix<float64_t, 3, 1> autoware::motion::motion_common::Vector3f |
float64_t autoware::motion::motion_common::calcLongitudinalDeviation | ( | const geometry_msgs::msg::Pose & | base_pose, |
const geometry_msgs::msg::Point & | target_point | ||
) |
calculate longitudinal deviation of a point relative to a pose
[in] | base_pose | base from which to calculate the deviation |
[in] | target_point | point for which to calculate the deviation |
float64_t autoware::motion::motion_common::calcLongitudinalOffsetToSegment | ( | const Points & | points, |
const size_t | seg_idx, | ||
const geometry_msgs::msg::Point & | p_target | ||
) |
calculate length along trajectory from seg_idx point to nearest point to p_target on trajectory If seg_idx point is after that nearest point, length is negative
points | trajectory points |
seg_idx | segment index of point at beginning of length |
p_target | target point at end of length |
float64_t autoware::motion::motion_common::calcSignedArcLength | ( | const Points & | points, |
const geometry_msgs::msg::Point & | src_point, | ||
const geometry_msgs::msg::Point & | dst_point | ||
) |
calculate arc length along points
[in] | points | input points |
[in] | src_point | source point |
[in] | dst_point | destination point |
float64_t autoware::motion::motion_common::calcSignedArcLength | ( | const Points & | points, |
const geometry_msgs::msg::Point & | src_point, | ||
const size_t & | dst_idx | ||
) |
calculate arc length along points
[in] | points | input points |
[in] | src_point | source point |
[in] | dst_idx | destination index |
float64_t autoware::motion::motion_common::calcSignedArcLength | ( | const Points & | points, |
const size_t | src_idx, | ||
const size_t | dst_idx | ||
) |
calculate arc length along points
[in] | points | input points |
[in] | src_idx | source index |
[in] | dst_idx | destination index |
float64_t autoware::motion::motion_common::calcYawDeviation | ( | const float64_t & | base_yaw, |
const float64_t & | target_yaw | ||
) |
calculate the yaw deviation between two angles
[in] | base_yaw | base yaw angle [radians] |
[in] | target_yaw | target yaw angle [radians] |
size_t autoware::motion::motion_common::findNearestIndex | ( | const Points & | points, |
const geometry_msgs::msg::Point & | point | ||
) |
search the index of the point nearest to the given target
[in] | points | list of points to search |
[in] | point | target point |
std::experimental::optional< size_t > autoware::motion::motion_common::findNearestIndex | ( | const Points & | points, |
const geometry_msgs::msg::Pose & | pose, | ||
const float64_t | max_dist = std::numeric_limits<float64_t>::max() , |
||
const float64_t | max_yaw = std::numeric_limits<float64_t>::max() |
||
) |
search the index of the point nearest to the given target with limits on the distance and yaw deviation
[in] | points | list of points to search |
[in] | pose | target point |
[in] | max_dist | optional maximum distance from the pose when searching for the nearest index |
[in] | max_yaw | optional maximum deviation from the pose when searching for the nearest index |
size_t autoware::motion::motion_common::findNearestSegmentIndex | ( | const Points & | points, |
const geometry_msgs::msg::Point & | point | ||
) |
find nearest segment index to point segment is straight path between two continuous points of trajectory When point is on a trajectory point whose index is nearest_idx, return nearest_idx - 1
points | points of trajectory |
point | point to which to find nearest segment index |
std::experimental::optional< size_t > autoware::motion::motion_common::searchZeroVelocityIndex | ( | const Points & | points | ) |
search first index with a velocity of zero in the given points
[in] | points | list of points to check |
std::experimental::optional< size_t > autoware::motion::motion_common::searchZeroVelocityIndex | ( | const Points & | points, |
const size_t | src_idx, | ||
const size_t | dst_idx, | ||
const float64_t | epsilon = 1e-3 |
||
) |
search first index with a velocity of zero in the given range of points
[in] | points | list of points to check |
[in] | src_idx | starting search index |
[in] | dst_idx | ending (excluded) search index |
[in] | epsilon | optional value to use to determine zero velocities |
void autoware::motion::motion_common::validateNonEmpty | ( | const Points & | points | ) |
throws an exception if the given list of points is empty
[in] | points | list of points to check |
decltype(autoware_auto_planning_msgs::msg::Trajectory::points) typedef autoware::motion::motion_common::Points |