Autoware.Auto
autoware::motion::motion_common Namespace Reference

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 Documentation

◆ Point

typedef autoware_auto_planning_msgs::msg::TrajectoryPoint autoware::motion::motion_common::Point

◆ Vector3f

typedef Eigen::Matrix<float64_t, 3, 1> autoware::motion::motion_common::Vector3f

Function Documentation

◆ calcLongitudinalDeviation()

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

Parameters
[in]base_posebase from which to calculate the deviation
[in]target_pointpoint for which to calculate the deviation
Returns
longitudinal distance between the base and the target

◆ calcLongitudinalOffsetToSegment()

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

Parameters
pointstrajectory points
seg_idxsegment index of point at beginning of length
p_targettarget point at end of length
Returns
signed length

◆ calcSignedArcLength() [1/3]

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

Parameters
[in]pointsinput points
[in]src_pointsource point
[in]dst_pointdestination point
Returns
arc length distance from source to destination along the input points

◆ calcSignedArcLength() [2/3]

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

Parameters
[in]pointsinput points
[in]src_pointsource point
[in]dst_idxdestination index
Returns
arc length distance from source to destination along the input points

◆ calcSignedArcLength() [3/3]

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

Parameters
[in]pointsinput points
[in]src_idxsource index
[in]dst_idxdestination index
Returns
arc length distance from source to destination along the input points

◆ calcYawDeviation()

float64_t autoware::motion::motion_common::calcYawDeviation ( const float64_t &  base_yaw,
const float64_t &  target_yaw 
)

calculate the yaw deviation between two angles

Parameters
[in]base_yawbase yaw angle [radians]
[in]target_yawtarget yaw angle [radians]
Returns
normalized angle from the base to the target [radians]

◆ findNearestIndex() [1/2]

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

Parameters
[in]pointslist of points to search
[in]pointtarget point
Returns
index of the point nearest to the target

◆ findNearestIndex() [2/2]

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

Parameters
[in]pointslist of points to search
[in]posetarget point
[in]max_distoptional maximum distance from the pose when searching for the nearest index
[in]max_yawoptional maximum deviation from the pose when searching for the nearest index
Returns
index of the point nearest to the target

◆ findNearestSegmentIndex()

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

Parameters
pointspoints of trajectory
pointpoint to which to find nearest segment index
Returns
nearest index

◆ searchZeroVelocityIndex() [1/2]

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

Parameters
[in]pointslist of points to check

◆ searchZeroVelocityIndex() [2/2]

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

Parameters
[in]pointslist of points to check
[in]src_idxstarting search index
[in]dst_idxending (excluded) search index
[in]epsilonoptional value to use to determine zero velocities
Returns
index of the first zero velocity point found

◆ validateNonEmpty()

void autoware::motion::motion_common::validateNonEmpty ( const Points points)

throws an exception if the given list of points is empty

Parameters
[in]pointslist of points to check

Variable Documentation

◆ Points

decltype(autoware_auto_planning_msgs::msg::Trajectory::points) typedef autoware::motion::motion_common::Points