|
Autoware.Auto
|
|
| using autoware::prediction::state::ConstAccelerationXY = typedef FloatState< variable::X, variable::X_VELOCITY, variable::X_ACCELERATION, variable::Y, variable::Y_VELOCITY, variable::Y_ACCELERATION> |
A 2D state with no rotation.
All variables have their value, velocity and acceleration. All of the variables are
assumed to be independent here.
A 2D state with a CCW rotation.
All variables in this state have their value, velocity and acceleration. All of
these variables are assumed to be independent here.
A state consisting of a 2D position, CCW orientation, speed along the orientation vector, angle change rate and acceleration along the rotation vector.
This state is usually used for the CATR motion model: i.e., a model in which Constant Acceleration and Turn Rate are assumed for a differential drive base.
| using autoware::prediction::state::ConstantVelocityAndTurnRate = typedef FloatState< variable::X, variable::Y, variable::YAW, variable::XY_VELOCITY, variable::YAW_CHANGE_RATE> |
A state consisting of a 2D position, CCW orientation, speed along the orientation vector, and an orientation change rate.
This state is usually used for the CVTR motion model: i.e., a model in which Constant Velocity and Turn Rate are assumed for a differential drive base.