perception_interfaces 1.0.0
Loading...
Searching...
No Matches
Functions
state_getters.h File Reference

Getter functions for objects state members. More...

#include <perception_msgs_utils/impl/state_index.h>
#include <perception_msgs_utils/impl/checks.h>

Go to the source code of this file.

Functions

double perception_msgs::object_access::getX (const ObjectState &state)
 Get the x-position for a given object state.
 
template<typename T >
double perception_msgs::object_access::getX (const T &obj)
 Get the x-position for a given template object that contains an object state.
 
double perception_msgs::object_access::getY (const ObjectState &state)
 Get the y-position for a given object state.
 
template<typename T >
double perception_msgs::object_access::getY (const T &obj)
 Get the y-position for a given template object that contains an object state.
 
double perception_msgs::object_access::getZ (const ObjectState &state)
 Get the z-position for a given object state.
 
template<typename T >
double perception_msgs::object_access::getZ (const T &obj)
 Get the z-position for a given template object that contains an object state.
 
double perception_msgs::object_access::getVelLon (const ObjectState &state)
 Get the longitudinal velocity for a given object state.
 
template<typename T >
double perception_msgs::object_access::getVelLon (const T &obj)
 Get the longitudinal velocity for a given template object that contains an object state.
 
double perception_msgs::object_access::getVelLat (const ObjectState &state)
 Get the longitudinal velocity for a given object state.
 
template<typename T >
double perception_msgs::object_access::getVelLat (const T &obj)
 Get the longitudinal velocity for a given template object that contains an object state.
 
double perception_msgs::object_access::getAccLon (const ObjectState &state)
 Get the longitudinal acceleration for a given object state.
 
template<typename T >
double perception_msgs::object_access::getAccLon (const T &obj)
 Get the longitudinal acceleration for a given template object that contains an object state.
 
double perception_msgs::object_access::getAccLat (const ObjectState &state)
 Get the lateral acceleration for a given object state.
 
template<typename T >
double perception_msgs::object_access::getAccLat (const T &obj)
 Get the lateral acceleration for a given template object that contains an object state.
 
double perception_msgs::object_access::getRoll (const ObjectState &state)
 Get the roll for a given object state.
 
template<typename T >
double perception_msgs::object_access::getRoll (const T &obj)
 Get the roll for a given template object that contains an object state.
 
double perception_msgs::object_access::getRollRate (const ObjectState &state)
 Get the roll-rate for a given object state.
 
template<typename T >
double perception_msgs::object_access::getRollRate (const T &obj)
 Get the roll-rate for a given template object that contains an object state.
 
double perception_msgs::object_access::getPitch (const ObjectState &state)
 Get the pitch for a given object state.
 
template<typename T >
double perception_msgs::object_access::getPitch (const T &obj)
 Get the pitch for a given template object that contains an object state.
 
double perception_msgs::object_access::getPitchRate (const ObjectState &state)
 Get the pitch-rate for a given object state.
 
template<typename T >
double perception_msgs::object_access::getPitchRate (const T &obj)
 Get the pitch-rate for a given template object that contains an object state.
 
double perception_msgs::object_access::getYaw (const ObjectState &state)
 Get the yaw for a given object state.
 
template<typename T >
double perception_msgs::object_access::getYaw (const T &obj)
 Get the yaw for a given template object that contains an object state.
 
double perception_msgs::object_access::getYawRate (const ObjectState &state)
 Get the yaw-rate for a given object state.
 
template<typename T >
double perception_msgs::object_access::getYawRate (const T &obj)
 Get the yaw-rate for a given template object that contains an object state.
 
double perception_msgs::object_access::getSteeringAngleAck (const ObjectState &state)
 Get the ackermann steering angle for a given object state.
 
template<typename T >
double perception_msgs::object_access::getSteeringAngleAck (const T &obj)
 Get the ackermann steering angle for a given template object that contains an object state.
 
double perception_msgs::object_access::getSteeringAngleRateAck (const ObjectState &state)
 Get the steering angle rate for a given object state.
 
template<typename T >
double perception_msgs::object_access::getSteeringAngleRateAck (const T &obj)
 Get the steering angle rate for a given template object that contains an object state.
 
double perception_msgs::object_access::getSteeringAngleFront (const ObjectState &state)
 Get the front wheel angle for a given object state.
 
template<typename T >
double perception_msgs::object_access::getSteeringAngleFront (const T &obj)
 Get the front wheel angle for a given template object that contains an object state.
 
double perception_msgs::object_access::getSteeringAngleRear (const ObjectState &state)
 Get the rear wheel angle for a given object state.
 
template<typename T >
double perception_msgs::object_access::getSteeringAngleRear (const T &obj)
 Get the rear wheel angle for a given template object that contains an object state.
 
double perception_msgs::object_access::getWidth (const ObjectState &state)
 Get the width for a given object state.
 
template<typename T >
double perception_msgs::object_access::getWidth (const T &obj)
 Get the width for a given template object that contains an object state.
 
double perception_msgs::object_access::getLength (const ObjectState &state)
 Get the length for a given object state.
 
template<typename T >
double perception_msgs::object_access::getLength (const T &obj)
 Get the length for a given template object that contains an object state.
 
double perception_msgs::object_access::getHeight (const ObjectState &state)
 Get the height for a given object state.
 
template<typename T >
double perception_msgs::object_access::getHeight (const T &obj)
 Get the height for a given template object that contains an object state.
 
bool perception_msgs::object_access::getStandstill (const ObjectState &state)
 Get standstill indication for a given object state.
 
template<typename T >
bool perception_msgs::object_access::getStandstill (const T &obj)
 Get the standstill indication for a given template object that contains an object state.
 
uint8_t perception_msgs::object_access::getTrafficLightState (const ObjectState &state)
 Get the traffic light state for a given object state.
 
template<typename T >
uint8_t perception_msgs::object_access::getTrafficLightState (const T &obj)
 Get the traffic light state for a given template object that contains an object state.
 
uint8_t perception_msgs::object_access::getTrafficLightType (const ObjectState &state)
 Get the traffic light type for a given object state.
 
template<typename T >
uint8_t perception_msgs::object_access::getTrafficLightType (const T &obj)
 Get the traffic light type for a given template object that contains an object state.
 

Detailed Description

Getter functions for objects state members.

============================================================================ MIT License

Copyright (c) 2025 Institute for Automotive Engineering (ika), RWTH Aachen University

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE

SOFTWARE.

Definition in file state_getters.h.

Function Documentation

◆ getAccLat() [1/2]

double perception_msgs::object_access::getAccLat ( const ObjectState &  state)
inline

Get the lateral acceleration for a given object state.

Parameters
state
Returns
double

Definition at line 184 of file state_getters.h.

184 {
186 return state.continuous_state[indexAccLat(state.model_id)];
187 }
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
Definition checks.h:84
int indexAccLat(const unsigned char &model_id)
Get the vector-index that stores the lateral acceleration for a given model-id.

◆ getAccLat() [2/2]

template<typename T >
double perception_msgs::object_access::getAccLat ( const T &  obj)
inline

Get the lateral acceleration for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 197 of file state_getters.h.

197 {
198 return getAccLat(obj.state);
199 }
double getAccLat(const ObjectState &state)
Get the lateral acceleration for a given object state.

◆ getAccLon() [1/2]

double perception_msgs::object_access::getAccLon ( const ObjectState &  state)
inline

Get the longitudinal acceleration for a given object state.

Parameters
state
Returns
double

Definition at line 161 of file state_getters.h.

161 {
163 return state.continuous_state[indexAccLon(state.model_id)];
164 }
int indexAccLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal acceleration for a given model-id.

◆ getAccLon() [2/2]

template<typename T >
double perception_msgs::object_access::getAccLon ( const T &  obj)
inline

Get the longitudinal acceleration for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 174 of file state_getters.h.

174 {
175 return getAccLon(obj.state);
176 }
double getAccLon(const ObjectState &state)
Get the longitudinal acceleration for a given object state.

◆ getHeight() [1/2]

double perception_msgs::object_access::getHeight ( const ObjectState &  state)
inline

Get the height for a given object state.

Parameters
state
Returns
double

Definition at line 483 of file state_getters.h.

483 {
485 return state.continuous_state[indexHeight(state.model_id)];
486 }
int indexHeight(const unsigned char &model_id)
Get the vector-index that stores the height for a given model-id.

◆ getHeight() [2/2]

template<typename T >
double perception_msgs::object_access::getHeight ( const T &  obj)
inline

Get the height for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 496 of file state_getters.h.

496 {
497 return getHeight(obj.state);
498 }
double getHeight(const ObjectState &state)
Get the height for a given object state.

◆ getLength() [1/2]

double perception_msgs::object_access::getLength ( const ObjectState &  state)
inline

Get the length for a given object state.

Parameters
state
Returns
double

Definition at line 460 of file state_getters.h.

460 {
462 return state.continuous_state[indexLength(state.model_id)];
463 }
int indexLength(const unsigned char &model_id)
Get the vector-index that stores the length for a given model-id.

◆ getLength() [2/2]

template<typename T >
double perception_msgs::object_access::getLength ( const T &  obj)
inline

Get the length for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 473 of file state_getters.h.

473 {
474 return getLength(obj.state);
475 }
double getLength(const ObjectState &state)
Get the length for a given object state.

◆ getPitch() [1/2]

double perception_msgs::object_access::getPitch ( const ObjectState &  state)
inline

Get the pitch for a given object state.

Parameters
state
Returns
double

Definition at line 253 of file state_getters.h.

253 {
255 return state.continuous_state[indexPitch(state.model_id)];
256 }
int indexPitch(const unsigned char &model_id)
Get the vector-index that stores the pitch for a given model-id.

◆ getPitch() [2/2]

template<typename T >
double perception_msgs::object_access::getPitch ( const T &  obj)
inline

Get the pitch for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 266 of file state_getters.h.

266 {
267 return getPitch(obj.state);
268 }
double getPitch(const ObjectState &state)
Get the pitch for a given object state.

◆ getPitchRate() [1/2]

double perception_msgs::object_access::getPitchRate ( const ObjectState &  state)
inline

Get the pitch-rate for a given object state.

Parameters
state
Returns
double

Definition at line 276 of file state_getters.h.

276 {
278 return state.continuous_state[indexPitchRate(state.model_id)];
279 }
int indexPitchRate(const unsigned char &model_id)
Get the vector-index that stores the pitch rate for a given model-id.

◆ getPitchRate() [2/2]

template<typename T >
double perception_msgs::object_access::getPitchRate ( const T &  obj)
inline

Get the pitch-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 289 of file state_getters.h.

289 {
290 return getPitchRate(obj.state);
291 }
double getPitchRate(const ObjectState &state)
Get the pitch-rate for a given object state.

◆ getRoll() [1/2]

double perception_msgs::object_access::getRoll ( const ObjectState &  state)
inline

Get the roll for a given object state.

Parameters
state
Returns
double

Definition at line 207 of file state_getters.h.

207 {
209 return state.continuous_state[indexRoll(state.model_id)];
210 }
int indexRoll(const unsigned char &model_id)
Get the vector-index that stores the roll for a given model-id.

◆ getRoll() [2/2]

template<typename T >
double perception_msgs::object_access::getRoll ( const T &  obj)
inline

Get the roll for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 220 of file state_getters.h.

220 {
221 return getRoll(obj.state);
222 }
double getRoll(const ObjectState &state)
Get the roll for a given object state.

◆ getRollRate() [1/2]

double perception_msgs::object_access::getRollRate ( const ObjectState &  state)
inline

Get the roll-rate for a given object state.

Parameters
state
Returns
double

Definition at line 230 of file state_getters.h.

230 {
232 return state.continuous_state[indexRollRate(state.model_id)];
233 }
int indexRollRate(const unsigned char &model_id)
Get the vector-index that stores the roll rate for a given model-id.

◆ getRollRate() [2/2]

template<typename T >
double perception_msgs::object_access::getRollRate ( const T &  obj)
inline

Get the roll-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 243 of file state_getters.h.

243 {
244 return getRollRate(obj.state);
245 }
double getRollRate(const ObjectState &state)
Get the roll-rate for a given object state.

◆ getStandstill() [1/2]

bool perception_msgs::object_access::getStandstill ( const ObjectState &  state)
inline

Get standstill indication for a given object state.

Parameters
state
Returns
true
false

Definition at line 507 of file state_getters.h.

507 {
509 return state.discrete_state[indexStandstill(state.model_id)];
510 }
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
Definition checks.h:104
int indexStandstill(const unsigned char &model_id)
Get the vector-index that stores the standstill indication for a given model-id.

◆ getStandstill() [2/2]

template<typename T >
bool perception_msgs::object_access::getStandstill ( const T &  obj)
inline

Get the standstill indication for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
true
false

Definition at line 521 of file state_getters.h.

521 {
522 return getStandstill(obj.state);
523 }
bool getStandstill(const ObjectState &state)
Get standstill indication for a given object state.

◆ getSteeringAngleAck() [1/2]

double perception_msgs::object_access::getSteeringAngleAck ( const ObjectState &  state)
inline

Get the ackermann steering angle for a given object state.

Parameters
state
Returns
double

Definition at line 345 of file state_getters.h.

345 {
347 return state.continuous_state[indexSteeringAngleAck(state.model_id)];
348 }
int indexSteeringAngleAck(const unsigned char &model_id)
Get the vector-index that stores the ackermann steering angle for a given model-id.

◆ getSteeringAngleAck() [2/2]

template<typename T >
double perception_msgs::object_access::getSteeringAngleAck ( const T &  obj)
inline

Get the ackermann steering angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 358 of file state_getters.h.

358 {
359 return getSteeringAngleAck(obj.state);
360 }
double getSteeringAngleAck(const ObjectState &state)
Get the ackermann steering angle for a given object state.

◆ getSteeringAngleFront() [1/2]

double perception_msgs::object_access::getSteeringAngleFront ( const ObjectState &  state)
inline

Get the front wheel angle for a given object state.

Parameters
state
Returns
double

Definition at line 391 of file state_getters.h.

391 {
393 return state.continuous_state[indexSteeringAngleFront(state.model_id)];
394 }
int indexSteeringAngleFront(const unsigned char &model_id)
Get the vector-index that stores the front wheel angle for a given model-id.

◆ getSteeringAngleFront() [2/2]

template<typename T >
double perception_msgs::object_access::getSteeringAngleFront ( const T &  obj)
inline

Get the front wheel angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 404 of file state_getters.h.

404 {
405 return getSteeringAngleFront(obj.state);
406 }
double getSteeringAngleFront(const ObjectState &state)
Get the front wheel angle for a given object state.

◆ getSteeringAngleRateAck() [1/2]

double perception_msgs::object_access::getSteeringAngleRateAck ( const ObjectState &  state)
inline

Get the steering angle rate for a given object state.

Parameters
state
Returns
double

Definition at line 368 of file state_getters.h.

368 {
370 return state.continuous_state[indexSteeringAngleRateAck(state.model_id)];
371 }
int indexSteeringAngleRateAck(const unsigned char &model_id)
Get the vector-index that stores the steering angle rate for a given model-id.

◆ getSteeringAngleRateAck() [2/2]

template<typename T >
double perception_msgs::object_access::getSteeringAngleRateAck ( const T &  obj)
inline

Get the steering angle rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 381 of file state_getters.h.

381 {
382 return getSteeringAngleRateAck(obj.state);
383 }
double getSteeringAngleRateAck(const ObjectState &state)
Get the steering angle rate for a given object state.

◆ getSteeringAngleRear() [1/2]

double perception_msgs::object_access::getSteeringAngleRear ( const ObjectState &  state)
inline

Get the rear wheel angle for a given object state.

Parameters
state
Returns
double

Definition at line 414 of file state_getters.h.

414 {
416 return state.continuous_state[indexSteeringAngleRear(state.model_id)];
417 }
int indexSteeringAngleRear(const unsigned char &model_id)
Get the vector-index that stores the rear wheel angle for a given model-id.

◆ getSteeringAngleRear() [2/2]

template<typename T >
double perception_msgs::object_access::getSteeringAngleRear ( const T &  obj)
inline

Get the rear wheel angle for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 427 of file state_getters.h.

427 {
428 return getSteeringAngleRear(obj.state);
429 }
double getSteeringAngleRear(const ObjectState &state)
Get the rear wheel angle for a given object state.

◆ getTrafficLightState() [1/2]

uint8_t perception_msgs::object_access::getTrafficLightState ( const ObjectState &  state)
inline

Get the traffic light state for a given object state.

Parameters
state
Returns
uint8_t

Definition at line 532 of file state_getters.h.

532 {
534 return state.discrete_state[indexTrafficLightState(state.model_id)];
535 }
int indexTrafficLightState(const unsigned char &model_id)
Get the vector-index that stores the traffic light state for a given model-id.

◆ getTrafficLightState() [2/2]

template<typename T >
uint8_t perception_msgs::object_access::getTrafficLightState ( const T &  obj)
inline

Get the traffic light state for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
uint8_t

Definition at line 547 of file state_getters.h.

547 {
548 return getTrafficLightState(obj.state);
549 }
uint8_t getTrafficLightState(const ObjectState &state)
Get the traffic light state for a given object state.

◆ getTrafficLightType() [1/2]

uint8_t perception_msgs::object_access::getTrafficLightType ( const ObjectState &  state)
inline

Get the traffic light type for a given object state.

Parameters
state
Returns
uint8_t

Definition at line 558 of file state_getters.h.

558 {
560 return state.discrete_state[indexTrafficLightType(state.model_id)];
561 }
int indexTrafficLightType(const unsigned char &model_id)
Get the vector-index that stores the traffic light type for a given model-id.

◆ getTrafficLightType() [2/2]

template<typename T >
uint8_t perception_msgs::object_access::getTrafficLightType ( const T &  obj)
inline

Get the traffic light type for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
uint8_t

Definition at line 573 of file state_getters.h.

573 {
574 return getTrafficLightType(obj.state);
575 }
uint8_t getTrafficLightType(const ObjectState &state)
Get the traffic light type for a given object state.

◆ getVelLat() [1/2]

double perception_msgs::object_access::getVelLat ( const ObjectState &  state)
inline

Get the longitudinal velocity for a given object state.

Parameters
state
Returns
double

Definition at line 138 of file state_getters.h.

138 {
140 return state.continuous_state[indexVelLat(state.model_id)];
141 }
int indexVelLat(const unsigned char &model_id)
Get the vector-index that stores the lateral velocity for a given model-id.

◆ getVelLat() [2/2]

template<typename T >
double perception_msgs::object_access::getVelLat ( const T &  obj)
inline

Get the longitudinal velocity for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 151 of file state_getters.h.

151 {
152 return getVelLat(obj.state);
153 }
double getVelLat(const ObjectState &state)
Get the longitudinal velocity for a given object state.

◆ getVelLon() [1/2]

double perception_msgs::object_access::getVelLon ( const ObjectState &  state)
inline

Get the longitudinal velocity for a given object state.

Parameters
state
Returns
double

Definition at line 115 of file state_getters.h.

115 {
117 return state.continuous_state[indexVelLon(state.model_id)];
118 }
int indexVelLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal velocity for a given model-id.

◆ getVelLon() [2/2]

template<typename T >
double perception_msgs::object_access::getVelLon ( const T &  obj)
inline

Get the longitudinal velocity for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 128 of file state_getters.h.

128 {
129 return getVelLon(obj.state);
130 }
double getVelLon(const ObjectState &state)
Get the longitudinal velocity for a given object state.

◆ getWidth() [1/2]

double perception_msgs::object_access::getWidth ( const ObjectState &  state)
inline

Get the width for a given object state.

Parameters
state
Returns
double

Definition at line 437 of file state_getters.h.

437 {
439 return state.continuous_state[indexWidth(state.model_id)];
440 }
int indexWidth(const unsigned char &model_id)
Get the vector-index that stores the width for a given model-id.

◆ getWidth() [2/2]

template<typename T >
double perception_msgs::object_access::getWidth ( const T &  obj)
inline

Get the width for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 450 of file state_getters.h.

450 {
451 return getWidth(obj.state);
452 }
double getWidth(const ObjectState &state)
Get the width for a given object state.

◆ getX() [1/2]

double perception_msgs::object_access::getX ( const ObjectState &  state)
inline

Get the x-position for a given object state.

Parameters
state
Returns
double

Definition at line 45 of file state_getters.h.

45 {
47 return state.continuous_state[indexX(state.model_id)];
48 }
int indexX(const unsigned char &model_id)
Get the vector-index that stores the x-position for a given model-id.
Definition state_index.h:45

◆ getX() [2/2]

template<typename T >
double perception_msgs::object_access::getX ( const T &  obj)
inline

Get the x-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 59 of file state_getters.h.

59 {
60 return getX(obj.state);
61 }
double getX(const ObjectState &state)
Get the x-position for a given object state.

◆ getY() [1/2]

double perception_msgs::object_access::getY ( const ObjectState &  state)
inline

Get the y-position for a given object state.

Parameters
state
Returns
double

Definition at line 69 of file state_getters.h.

69 {
71 return state.continuous_state[indexY(state.model_id)];
72 }
int indexY(const unsigned char &model_id)
Get the vector-index that stores the y-position for a given model-id.
Definition state_index.h:68

◆ getY() [2/2]

template<typename T >
double perception_msgs::object_access::getY ( const T &  obj)
inline

Get the y-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 82 of file state_getters.h.

82 {
83 return getY(obj.state);
84 }
double getY(const ObjectState &state)
Get the y-position for a given object state.

◆ getYaw() [1/2]

double perception_msgs::object_access::getYaw ( const ObjectState &  state)
inline

Get the yaw for a given object state.

Parameters
state
Returns
double

Definition at line 299 of file state_getters.h.

299 {
301 return state.continuous_state[indexYaw(state.model_id)];
302 }
int indexYaw(const unsigned char &model_id)
Get the vector-index that stores the yaw for a given model-id.

◆ getYaw() [2/2]

template<typename T >
double perception_msgs::object_access::getYaw ( const T &  obj)
inline

Get the yaw for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 312 of file state_getters.h.

312 {
313 return getYaw(obj.state);
314 }
double getYaw(const ObjectState &state)
Get the yaw for a given object state.

◆ getYawRate() [1/2]

double perception_msgs::object_access::getYawRate ( const ObjectState &  state)
inline

Get the yaw-rate for a given object state.

Parameters
state
Returns
double

Definition at line 322 of file state_getters.h.

322 {
324 return state.continuous_state[indexYawRate(state.model_id)];
325 }
int indexYawRate(const unsigned char &model_id)
Get the vector-index that stores the yaw-rate for a given model-id.

◆ getYawRate() [2/2]

template<typename T >
double perception_msgs::object_access::getYawRate ( const T &  obj)
inline

Get the yaw-rate for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 335 of file state_getters.h.

335 {
336 return getYawRate(obj.state);
337 }
double getYawRate(const ObjectState &state)
Get the yaw-rate for a given object state.

◆ getZ() [1/2]

double perception_msgs::object_access::getZ ( const ObjectState &  state)
inline

Get the z-position for a given object state.

Parameters
state
Returns
double

Definition at line 92 of file state_getters.h.

92 {
94 return state.continuous_state[indexZ(state.model_id)];
95 }
int indexZ(const unsigned char &model_id)
Get the vector-index that stores the z-position for a given model-id.
Definition state_index.h:91

◆ getZ() [2/2]

template<typename T >
double perception_msgs::object_access::getZ ( const T &  obj)
inline

Get the z-position for a given template object that contains an object state.

Template Parameters
T
Parameters
obj
Returns
double

Definition at line 105 of file state_getters.h.

105 {
106 return getZ(obj.state);
107 }
double getZ(const ObjectState &state)
Get the z-position for a given object state.