perception_interfaces 1.0.0
Loading...
Searching...
No Matches
state_getters.h
Go to the documentation of this file.
1
30#pragma once
31
34
35
36namespace perception_msgs {
37
38namespace object_access {
45 inline double getX(const ObjectState& state) {
47 return state.continuous_state[indexX(state.model_id)];
48 }
49
50
58 template <typename T>
59 inline double getX(const T& obj) {
60 return getX(obj.state);
61 }
62
69 inline double getY(const ObjectState& state) {
71 return state.continuous_state[indexY(state.model_id)];
72 }
73
81 template <typename T>
82 inline double getY(const T& obj) {
83 return getY(obj.state);
84 }
85
92 inline double getZ(const ObjectState& state) {
94 return state.continuous_state[indexZ(state.model_id)];
95 }
96
104 template <typename T>
105 inline double getZ(const T& obj) {
106 return getZ(obj.state);
107 }
108
115 inline double getVelLon(const ObjectState& state) {
117 return state.continuous_state[indexVelLon(state.model_id)];
118 }
119
127 template <typename T>
128 inline double getVelLon(const T& obj) {
129 return getVelLon(obj.state);
130 }
131
138 inline double getVelLat(const ObjectState& state) {
140 return state.continuous_state[indexVelLat(state.model_id)];
141 }
142
150 template <typename T>
151 inline double getVelLat(const T& obj) {
152 return getVelLat(obj.state);
153 }
154
161 inline double getAccLon(const ObjectState& state) {
163 return state.continuous_state[indexAccLon(state.model_id)];
164 }
165
173 template <typename T>
174 inline double getAccLon(const T& obj) {
175 return getAccLon(obj.state);
176 }
177
184 inline double getAccLat(const ObjectState& state) {
186 return state.continuous_state[indexAccLat(state.model_id)];
187 }
188
196 template <typename T>
197 inline double getAccLat(const T& obj) {
198 return getAccLat(obj.state);
199 }
200
207 inline double getRoll(const ObjectState& state) {
209 return state.continuous_state[indexRoll(state.model_id)];
210 }
211
219 template <typename T>
220 inline double getRoll(const T& obj) {
221 return getRoll(obj.state);
222 }
223
230 inline double getRollRate(const ObjectState& state) {
232 return state.continuous_state[indexRollRate(state.model_id)];
233 }
234
242 template <typename T>
243 inline double getRollRate(const T& obj) {
244 return getRollRate(obj.state);
245 }
246
253 inline double getPitch(const ObjectState& state) {
255 return state.continuous_state[indexPitch(state.model_id)];
256 }
257
265 template <typename T>
266 inline double getPitch(const T& obj) {
267 return getPitch(obj.state);
268 }
269
276 inline double getPitchRate(const ObjectState& state) {
278 return state.continuous_state[indexPitchRate(state.model_id)];
279 }
280
288 template <typename T>
289 inline double getPitchRate(const T& obj) {
290 return getPitchRate(obj.state);
291 }
292
299 inline double getYaw(const ObjectState& state) {
301 return state.continuous_state[indexYaw(state.model_id)];
302 }
303
311 template <typename T>
312 inline double getYaw(const T& obj) {
313 return getYaw(obj.state);
314 }
315
322 inline double getYawRate(const ObjectState& state) {
324 return state.continuous_state[indexYawRate(state.model_id)];
325 }
326
334 template <typename T>
335 inline double getYawRate(const T& obj) {
336 return getYawRate(obj.state);
337 }
338
345 inline double getSteeringAngleAck(const ObjectState& state) {
347 return state.continuous_state[indexSteeringAngleAck(state.model_id)];
348 }
349
357 template <typename T>
358 inline double getSteeringAngleAck(const T& obj) {
359 return getSteeringAngleAck(obj.state);
360 }
361
368 inline double getSteeringAngleRateAck(const ObjectState& state) {
370 return state.continuous_state[indexSteeringAngleRateAck(state.model_id)];
371 }
372
380 template <typename T>
381 inline double getSteeringAngleRateAck(const T& obj) {
382 return getSteeringAngleRateAck(obj.state);
383 }
384
391 inline double getSteeringAngleFront(const ObjectState& state) {
393 return state.continuous_state[indexSteeringAngleFront(state.model_id)];
394 }
395
403 template <typename T>
404 inline double getSteeringAngleFront(const T& obj) {
405 return getSteeringAngleFront(obj.state);
406 }
407
414 inline double getSteeringAngleRear(const ObjectState& state) {
416 return state.continuous_state[indexSteeringAngleRear(state.model_id)];
417 }
418
426 template <typename T>
427 inline double getSteeringAngleRear(const T& obj) {
428 return getSteeringAngleRear(obj.state);
429 }
430
437 inline double getWidth(const ObjectState& state) {
439 return state.continuous_state[indexWidth(state.model_id)];
440 }
441
449 template <typename T>
450 inline double getWidth(const T& obj) {
451 return getWidth(obj.state);
452 }
453
460 inline double getLength(const ObjectState& state) {
462 return state.continuous_state[indexLength(state.model_id)];
463 }
464
472 template <typename T>
473 inline double getLength(const T& obj) {
474 return getLength(obj.state);
475 }
476
483 inline double getHeight(const ObjectState& state) {
485 return state.continuous_state[indexHeight(state.model_id)];
486 }
487
495 template <typename T>
496 inline double getHeight(const T& obj) {
497 return getHeight(obj.state);
498 }
499
507 inline bool getStandstill(const ObjectState& state) {
509 return state.discrete_state[indexStandstill(state.model_id)];
510 }
511
520 template <typename T>
521 inline bool getStandstill(const T& obj) {
522 return getStandstill(obj.state);
523 }
524
532 inline uint8_t getTrafficLightState(const ObjectState& state) {
534 return state.discrete_state[indexTrafficLightState(state.model_id)];
535 }
536
546 template <typename T>
547 inline uint8_t getTrafficLightState(const T& obj) {
548 return getTrafficLightState(obj.state);
549 }
550
558 inline uint8_t getTrafficLightType(const ObjectState& state) {
560 return state.discrete_state[indexTrafficLightType(state.model_id)];
561 }
562
572 template <typename T>
573 inline uint8_t getTrafficLightType(const T& obj) {
574 return getTrafficLightType(obj.state);
575 }
576
577} // namespace object_access
578
579} // namespace perception_msgs
Object state sanity checks.
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
Definition checks.h:84
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
Definition checks.h:104
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.
Definition state_index.h:68
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.
Definition state_index.h:91
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.
Definition state_index.h:45
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.