36namespace perception_msgs {
38namespace object_access {
45 inline double getX(
const ObjectState& state) {
47 return state.continuous_state[
indexX(state.model_id)];
59 inline double getX(
const T& obj) {
60 return getX(obj.state);
69 inline double getY(
const ObjectState& state) {
71 return state.continuous_state[
indexY(state.model_id)];
82 inline double getY(
const T& obj) {
83 return getY(obj.state);
92 inline double getZ(
const ObjectState& state) {
94 return state.continuous_state[
indexZ(state.model_id)];
104 template <
typename T>
105 inline double getZ(
const T& obj) {
106 return getZ(obj.state);
117 return state.continuous_state[
indexVelLon(state.model_id)];
127 template <
typename T>
140 return state.continuous_state[
indexVelLat(state.model_id)];
150 template <
typename T>
163 return state.continuous_state[
indexAccLon(state.model_id)];
173 template <
typename T>
186 return state.continuous_state[
indexAccLat(state.model_id)];
196 template <
typename T>
207 inline double getRoll(
const ObjectState& state) {
209 return state.continuous_state[
indexRoll(state.model_id)];
219 template <
typename T>
232 return state.continuous_state[
indexRollRate(state.model_id)];
242 template <
typename T>
255 return state.continuous_state[
indexPitch(state.model_id)];
265 template <
typename T>
288 template <
typename T>
299 inline double getYaw(
const ObjectState& state) {
301 return state.continuous_state[
indexYaw(state.model_id)];
311 template <
typename T>
324 return state.continuous_state[
indexYawRate(state.model_id)];
334 template <
typename T>
357 template <
typename T>
380 template <
typename T>
403 template <
typename T>
426 template <
typename T>
439 return state.continuous_state[
indexWidth(state.model_id)];
449 template <
typename T>
462 return state.continuous_state[
indexLength(state.model_id)];
472 template <
typename T>
485 return state.continuous_state[
indexHeight(state.model_id)];
495 template <
typename T>
520 template <
typename T>
546 template <
typename T>
572 template <
typename T>
Object state sanity checks.
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
double getSteeringAngleAck(const ObjectState &state)
Get the ackermann steering angle for a given object state.
double getZ(const ObjectState &state)
Get the z-position for a given object state.
double getHeight(const ObjectState &state)
Get the height for a given object state.
double getRoll(const ObjectState &state)
Get the roll for a given object state.
double getYawRate(const ObjectState &state)
Get the yaw-rate for a given object state.
double getVelLon(const ObjectState &state)
Get the longitudinal velocity for a given object state.
double getSteeringAngleRear(const ObjectState &state)
Get the rear wheel angle for a given object state.
uint8_t getTrafficLightState(const ObjectState &state)
Get the traffic light state for a given object state.
double getAccLon(const ObjectState &state)
Get the longitudinal acceleration for a given object state.
double getRollRate(const ObjectState &state)
Get the roll-rate for a given object state.
double getSteeringAngleFront(const ObjectState &state)
Get the front wheel angle for a given object state.
double getPitchRate(const ObjectState &state)
Get the pitch-rate for a given object state.
double getPitch(const ObjectState &state)
Get the pitch for a given object state.
double getYaw(const ObjectState &state)
Get the yaw for a given object state.
double getAccLat(const ObjectState &state)
Get the lateral acceleration for a given object state.
double getY(const ObjectState &state)
Get the y-position for a given object state.
bool getStandstill(const ObjectState &state)
Get standstill indication for a given object state.
double getSteeringAngleRateAck(const ObjectState &state)
Get the steering angle rate for a given object state.
double getWidth(const ObjectState &state)
Get the width for a given object state.
double getX(const ObjectState &state)
Get the x-position for a given object state.
double getLength(const ObjectState &state)
Get the length for a given object state.
uint8_t getTrafficLightType(const ObjectState &state)
Get the traffic light type for a given object state.
double getVelLat(const ObjectState &state)
Get the longitudinal velocity for a given object state.
Object state vector indices based on state model.
int indexRollRate(const unsigned char &model_id)
Get the vector-index that stores the roll rate for a given model-id.
int indexVelLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal velocity for a given model-id.
int indexWidth(const unsigned char &model_id)
Get the vector-index that stores the width for a given model-id.
int indexRoll(const unsigned char &model_id)
Get the vector-index that stores the roll for a given model-id.
int indexLength(const unsigned char &model_id)
Get the vector-index that stores the length for a given model-id.
int indexPitchRate(const unsigned char &model_id)
Get the vector-index that stores the pitch rate for a given model-id.
int indexYawRate(const unsigned char &model_id)
Get the vector-index that stores the yaw-rate for a given model-id.
int indexHeight(const unsigned char &model_id)
Get the vector-index that stores the height for a given model-id.
int indexVelLat(const unsigned char &model_id)
Get the vector-index that stores the lateral velocity for a given model-id.
int indexY(const unsigned char &model_id)
Get the vector-index that stores the y-position for a given model-id.
int indexSteeringAngleFront(const unsigned char &model_id)
Get the vector-index that stores the front wheel angle for a given model-id.
int indexSteeringAngleRear(const unsigned char &model_id)
Get the vector-index that stores the rear wheel angle for a given model-id.
int indexZ(const unsigned char &model_id)
Get the vector-index that stores the z-position for a given model-id.
int indexAccLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal acceleration for a given model-id.
int indexStandstill(const unsigned char &model_id)
Get the vector-index that stores the standstill indication for a given model-id.
int indexTrafficLightType(const unsigned char &model_id)
Get the vector-index that stores the traffic light type for a given model-id.
int indexSteeringAngleRateAck(const unsigned char &model_id)
Get the vector-index that stores the steering angle rate for a given model-id.
int indexPitch(const unsigned char &model_id)
Get the vector-index that stores the pitch for a given model-id.
int indexAccLat(const unsigned char &model_id)
Get the vector-index that stores the lateral acceleration for a given model-id.
int indexSteeringAngleAck(const unsigned char &model_id)
Get the vector-index that stores the ackermann steering angle for a given model-id.
int indexX(const unsigned char &model_id)
Get the vector-index that stores the x-position for a given model-id.
int indexTrafficLightState(const unsigned char &model_id)
Get the vector-index that stores the traffic light state for a given model-id.
int indexYaw(const unsigned char &model_id)
Get the vector-index that stores the yaw for a given model-id.