Autoware.Auto
motion::motion_common Namespace Reference

Classes

class  LimitsConfig
 Extreme values for state/control variables. More...
 
class  OptimizationConfig
 Specifies various parameters specific to the optimization problem and it's behaviors Depending on problem setup, some weights may be ignored. More...
 
class  StateWeight
 Specifies the weights used for particular state weights in the least-squares objective function of the mpc solver. More...
 
class  VehicleConfig
 Vehicle parameters specifying vehicle's handling performance. More...
 

Typedefs

using Real = decltype(autoware_auto_planning_msgs::msg::TrajectoryPoint::longitudinal_velocity_mps)
 
using Command = autoware_auto_vehicle_msgs::msg::VehicleControlCommand
 
using Diagnostic = autoware_auto_system_msgs::msg::ControlDiagnostic
 
using State = autoware_auto_vehicle_msgs::msg::VehicleKinematicState
 
using Trajectory = autoware_auto_planning_msgs::msg::Trajectory
 
using Orientation = geometry_msgs::msg::Quaternion
 
using Double = decltype(Orientation::x)
 
using Index = decltype(Trajectory::points)::size_type
 
using Point = decltype(Trajectory::points)::value_type
 

Functions

MOTION_COMMON_PUBLIC bool is_past_point (const Point &state, const Point &pt) noexcept
 Check if a state is past a given trajectory point, assuming heading is correct. More...
 
MOTION_COMMON_PUBLIC bool is_past_point (const Point &state, const Point &current_pt, const Point &next_pt) noexcept
 
MOTION_COMMON_PUBLIC bool is_past_point (const Point &state, const Point &pt, Double nx, Double ny) noexcept
 Given a normal, determine if state is past a point. More...
 
template<typename IsPastPointF >
Index update_reference_index (const Trajectory &traj, const State &state, Index start_idx, IsPastPointF is_past_point)
 Advance to the first trajectory point past state according to criterion is_past_point. More...
 
MOTION_COMMON_PUBLIC bool heading_ok (const Trajectory &traj)
 Check that all heading values in a trajectory are normalized 2D quaternions. More...
 
MOTION_COMMON_PUBLIC void doTransform (const Point &t_in, Point &t_out, const geometry_msgs::msg::TransformStamped &transform) noexcept
 Apply transform to TrajectoryPoint. More...
 
MOTION_COMMON_PUBLIC void doTransform (const State &t_in, State &t_out, const geometry_msgs::msg::TransformStamped &transform) noexcept
 Apply transform to VehicleKinematicState. More...
 
MOTION_COMMON_PUBLIC Double to_angle (Orientation orientation) noexcept
 Converts 3D quaternion to simple heading representation. More...
 
template<typename RealT >
Orientation from_angles (RealT roll, RealT pitch, RealT yaw) noexcept
 Converts angles into a corresponding Orientation. More...
 
template<typename RealT >
Orientation from_angle (RealT angle) noexcept
 Converts a heading angle into a corresponding Orientation. More...
 
template<typename T >
clamp (T val, T min, T max)
 Standard clamp implementation. More...
 
template<typename T , typename RealT = double>
interpolate (T a, T b, RealT t)
 Standard linear interpolation. More...
 
MOTION_COMMON_PUBLIC Orientation slerp (const Orientation &a, const Orientation &b, const Real t)
 Spherical linear interpolation. More...
 
template<typename SlerpF >
Point interpolate (Point a, Point b, Real t, SlerpF slerp_fn)
 Trajectory point interpolation. More...
 
MOTION_COMMON_PUBLIC Point interpolate (Point a, Point b, Real t)
 Default point interpolation. More...
 
template<typename SlerpF >
void sample (const Trajectory &in, Trajectory &out, std::chrono::nanoseconds period, SlerpF slerp_fn)
 Sample a trajectory using interpolation; does not extrapolate. More...
 
MOTION_COMMON_PUBLIC void sample (const Trajectory &in, Trajectory &out, std::chrono::nanoseconds period)
 Trajectory sampling with default interpolation. More...
 
MOTION_COMMON_PUBLIC void error (const Point &state, const Point &ref, Diagnostic &out) noexcept
 Diagnostic header stuff. More...
 

Typedef Documentation

◆ Command

using motion::motion_common::Command = typedef autoware_auto_vehicle_msgs::msg::VehicleControlCommand

◆ Diagnostic

using motion::motion_common::Diagnostic = typedef autoware_auto_system_msgs::msg::ControlDiagnostic

◆ Double

using motion::motion_common::Double = typedef decltype(Orientation::x)

◆ Index

using motion::motion_common::Index = typedef decltype(Trajectory::points)::size_type

◆ Orientation

using motion::motion_common::Orientation = typedef geometry_msgs::msg::Quaternion

◆ Point

using motion::motion_common::Point = typedef decltype(Trajectory::points)::value_type

◆ Real

using motion::motion_common::Real = typedef decltype(autoware_auto_planning_msgs::msg::TrajectoryPoint::longitudinal_velocity_mps)

◆ State

using motion::motion_common::State = typedef autoware_auto_vehicle_msgs::msg::VehicleKinematicState

◆ Trajectory

using motion::motion_common::Trajectory = typedef autoware_auto_planning_msgs::msg::Trajectory

Function Documentation

◆ clamp()

template<typename T >
T motion::motion_common::clamp ( val,
min,
max 
)

Standard clamp implementation.

◆ doTransform() [1/2]

void motion::motion_common::doTransform ( const Point t_in,
Point t_out,
const geometry_msgs::msg::TransformStamped &  transform 
)
noexcept

Apply transform to TrajectoryPoint.

◆ doTransform() [2/2]

void motion::motion_common::doTransform ( const State t_in,
State t_out,
const geometry_msgs::msg::TransformStamped &  transform 
)
noexcept

Apply transform to VehicleKinematicState.

◆ error()

void motion::motion_common::error ( const Point state,
const Point ref,
Diagnostic out 
)
noexcept

Diagnostic header stuff.

◆ from_angle()

template<typename RealT >
Orientation motion::motion_common::from_angle ( RealT  angle)
noexcept

Converts a heading angle into a corresponding Orientation.

Template Parameters
RealTa floating point type
Parameters
[in]angleheading angle to use as yaw of the Orientation [radians]
Returns
A converted Orientation object

◆ from_angles()

template<typename RealT >
Orientation motion::motion_common::from_angles ( RealT  roll,
RealT  pitch,
RealT  yaw 
)
noexcept

Converts angles into a corresponding Orientation.

Template Parameters
RealTa floating point type
Parameters
[in]rollangle to use as roll of the Orientation [radians]
[in]pitchangle to use as pitch of the Orientation [radians]
[in]yawangle to use as yaw of the Orientation [radians]
Returns
A converted Orientation object

◆ heading_ok()

bool motion::motion_common::heading_ok ( const Trajectory traj)

Check that all heading values in a trajectory are normalized 2D quaternions.

◆ interpolate() [1/3]

Point motion::motion_common::interpolate ( Point  a,
Point  b,
Real  t 
)

Default point interpolation.

◆ interpolate() [2/3]

template<typename SlerpF >
Point motion::motion_common::interpolate ( Point  a,
Point  b,
Real  t,
SlerpF  slerp_fn 
)

Trajectory point interpolation.

◆ interpolate() [3/3]

template<typename T , typename RealT = double>
T motion::motion_common::interpolate ( a,
b,
RealT  t 
)

Standard linear interpolation.

◆ is_past_point() [1/3]

bool motion::motion_common::is_past_point ( const Point state,
const Point current_pt,
const Point next_pt 
)
noexcept

Check if a state is past a given trajectory point given the last (aka current) trajectory point

◆ is_past_point() [2/3]

bool motion::motion_common::is_past_point ( const Point state,
const Point pt 
)
noexcept

Check if a state is past a given trajectory point, assuming heading is correct.

◆ is_past_point() [3/3]

bool motion::motion_common::is_past_point ( const Point state,
const Point pt,
Double  nx,
Double  ny 
)
noexcept

Given a normal, determine if state is past a point.

◆ sample() [1/2]

void motion::motion_common::sample ( const Trajectory in,
Trajectory out,
std::chrono::nanoseconds  period 
)

Trajectory sampling with default interpolation.

◆ sample() [2/2]

template<typename SlerpF >
void motion::motion_common::sample ( const Trajectory in,
Trajectory out,
std::chrono::nanoseconds  period,
SlerpF  slerp_fn 
)

Sample a trajectory using interpolation; does not extrapolate.

◆ slerp()

Orientation motion::motion_common::slerp ( const Orientation a,
const Orientation b,
const Real  t 
)

Spherical linear interpolation.

◆ to_angle()

Double motion::motion_common::to_angle ( Orientation  orientation)
noexcept

Converts 3D quaternion to simple heading representation.

◆ update_reference_index()

template<typename IsPastPointF >
Index motion::motion_common::update_reference_index ( const Trajectory traj,
const State state,
Index  start_idx,
IsPastPointF  is_past_point 
)

Advance to the first trajectory point past state according to criterion is_past_point.