perception_interfaces 1.0.0
Loading...
Searching...
No Matches
convenience_state_getters.h
Go to the documentation of this file.
1
30#pragma once
31
35
36#include <algorithm>
37#include <cmath>
38
39namespace perception_msgs {
40
41namespace object_access {
42
43// --- full state/covariance -------------------------------------------------
44
51inline std::vector<double> getContinuousState(const ObjectState& state) {
53 return state.continuous_state;
54}
55
63template <typename T>
64inline std::vector<double> getContinuousState(const T& obj) {
65 return getContinuousState(obj.state);
66}
67
74inline std::vector<long int> getDiscreteState(const ObjectState& state) {
76 return state.discrete_state;
77}
78
86template <typename T>
87inline std::vector<long int> getDiscreteState(const T& obj) {
88 return getDiscreteState(obj.state);
89}
90
97inline std::vector<double> getContinuousStateCovariance(const ObjectState& state) {
99 return state.continuous_state_covariance;
100}
101
109template <typename T>
110inline std::vector<double> getContinuousStateCovariance(const T& obj) {
111 return getContinuousStateCovariance(obj.state);
112}
113
122inline double getContinuousStateCovarianceAt(const ObjectState& state, const unsigned int i, const unsigned int j) {
123 const int n = getContinuousStateSize(state);
124 const std::vector<double> covariance = getContinuousStateCovariance(state);
125 return covariance[n * i + j];
126}
127
137template <typename T>
138inline double getContinuousStateCovarianceAt(const T& obj, const unsigned int i, const unsigned int j) {
139 return getContinuousStateCovarianceAt(obj.state, i, j);
140}
141
148inline std::vector<double> getContinuousStateCovarianceDiagonal(const ObjectState& state) {
149 const int n = getContinuousStateSize(state);
150 std::vector<double> diagonal(n);
151 for (int i = 0; i < n; i++) diagonal[i] = getContinuousStateCovarianceAt(state, i, i);
152 return diagonal;
153}
154
162template <typename T>
163inline std::vector<double> getContinuousStateCovarianceDiagonal(const T& obj) {
164 return getContinuousStateCovarianceDiagonal(obj.state);
165}
166
167// --- vector quantities -----------------------------------------------------
168
175inline gm::Point getPosition(const ObjectState& state) {
176 gm::Point position;
177 position.x = getX(state);
178 position.y = getY(state);
179 position.z = getZ(state);
180 return position;
181}
182
190template <typename T>
191inline gm::Point getPosition(const T& obj) {
192 return getPosition(obj.state);
193}
194
201inline gm::Quaternion getOrientation(const ObjectState& state) {
202 tf2::Quaternion q;
203 double roll{0}, pitch{0}, yaw{0};
204 if (hasRoll(state.model_id)) roll = getRoll(state);
205 if (hasPitch(state.model_id)) pitch = getPitch(state);
206 if (hasYaw(state.model_id)) yaw = getYaw(state);
207 q.setRPY(roll, pitch, yaw);
208 return tf2::toMsg(q);
209}
210
218template <typename T>
219inline gm::Quaternion getOrientation(const T& obj) {
220 return getOrientation(obj.state);
221}
222
229inline gm::Pose getPose(const ObjectState& state) {
230 gm::Pose pose;
231 pose.position = getPosition(state);
232 pose.orientation = getOrientation(state);
233 return pose;
234}
235
242inline gm::Point getCenterPosition(const ObjectState& state) {
243 gm::Point position = getPosition(state);
244 const auto orientation = getOrientation(state);
245 const gm::Vector3 offset_to_center = state.reference_point.translation_to_geometric_center;
246 tf2::Quaternion q;
247 tf2::fromMsg(orientation, q);
248 const tf2::Vector3 offset_to_center_tf2(offset_to_center.x, offset_to_center.y, offset_to_center.z);
249 const tf2::Vector3 rotated_offset_to_center = tf2::quatRotate(q, offset_to_center_tf2);
250 position.x += rotated_offset_to_center.x();
251 position.y += rotated_offset_to_center.y();
252 position.z += rotated_offset_to_center.z();
253 return position;
254}
255
263template <typename T>
264inline gm::Point getCenterPosition(const T& object) {
265 return getCenterPosition(object.state);
266}
267
275template <typename T>
276inline gm::Pose getPose(const T& obj) {
277 return getPose(obj.state);
278}
279
286inline std::vector<double> getPoseCovariance(const ObjectState& state) {
287 const int n = 6;
288 const int model_id = state.model_id;
289 std::vector<double> pose_covariance(n * n, 0.0);
290 int ix, jx;
291 for (int i = 0; i < n; i++) {
292 for (int j = 0; j < n; j++) {
293 if (i == 0 && hasX(model_id))
294 ix = indexX(model_id);
295 else if (i == 1 && hasY(model_id))
296 ix = indexY(model_id);
297 else if (i == 2 && hasZ(model_id))
298 ix = indexZ(model_id);
299 else if (i == 3 && hasRoll(model_id))
300 ix = indexRoll(model_id);
301 else if (i == 4 && hasPitch(model_id))
302 ix = indexPitch(model_id);
303 else if (i == 5 && hasYaw(model_id))
304 ix = indexYaw(model_id);
305 else
306 continue;
307
308 if (j == 0 && hasX(model_id))
309 jx = indexX(model_id);
310 else if (j == 1 && hasY(model_id))
311 jx = indexY(model_id);
312 else if (j == 2 && hasZ(model_id))
313 jx = indexZ(model_id);
314 else if (j == 3 && hasRoll(model_id))
315 jx = indexRoll(model_id);
316 else if (j == 4 && hasPitch(model_id))
317 jx = indexPitch(model_id);
318 else if (j == 5 && hasYaw(model_id))
319 jx = indexYaw(model_id);
320 else
321 continue;
322
323 pose_covariance[n * i + j] = getContinuousStateCovarianceAt(state, ix, jx);
324 }
325 }
326 return pose_covariance;
327}
328
336template <typename T>
337inline std::vector<double> getPoseCovariance(const T& obj) {
338 return getPoseCovariance(obj.state);
339}
340
348inline gm::PoseWithCovariance getPoseWithCovariance(const ObjectState& state) {
349 gm::PoseWithCovariance pose_with_covariance;
350 pose_with_covariance.pose = getPose(state);
351 std::vector<double> covariance_vector = getPoseCovariance(state);
352 gm::PoseWithCovariance::_covariance_type covariance;
353 std::copy(covariance_vector.begin(), covariance_vector.end(), covariance.begin());
354 pose_with_covariance.covariance = covariance;
355 return pose_with_covariance;
356}
357
365template <typename T>
366inline gm::PoseWithCovariance getPoseWithCovariance(const T& obj) {
367 return getPoseWithCovariance(obj.state);
368}
369
376inline gm::Vector3 getVelocity(const ObjectState& state) {
377 gm::Vector3 velocity;
378 velocity.x = getVelLon(state);
379 velocity.y = getVelLat(state);
380 velocity.z = 0.0;
381 return velocity;
382}
383
391template <typename T>
392inline gm::Vector3 getVelocity(const T& obj) {
393 return getVelocity(obj.state);
394}
395
402inline double getVelocityMagnitude(const ObjectState& state) {
403 gm::Vector3 vel = getVelocity(state);
404 using namespace std;
405 return sqrt(pow(vel.x, 2) + pow(vel.y, 2) + pow(vel.z, 2));
406}
407
415template <typename T>
416inline double getVelocityMagnitude(const T& obj) {
417 return getVelocityMagnitude(obj.state);
418}
419
425inline gm::Vector3 getAcceleration(const ObjectState& state) {
426 gm::Vector3 acceleration;
427 acceleration.x = getAccLon(state);
428 acceleration.y = getAccLat(state);
429 acceleration.z = 0.0;
430 return acceleration;
431}
432
440template <typename T>
441inline gm::Vector3 getAcceleration(const T& obj) {
442 return getAcceleration(obj.state);
443}
444
451inline double getAccelerationMagnitude(const ObjectState& state) {
452 gm::Vector3 acc = getAcceleration(state);
453 using namespace std;
454 return sqrt(pow(acc.x, 2) + pow(acc.y, 2) + pow(acc.z, 2));
455}
456
464template <typename T>
465inline double getAccelerationMagnitude(const T& obj) {
466 return getAccelerationMagnitude(obj.state);
467}
468
469// --- alternative state entries ---------------------------------------------
470
477inline double getRollInDeg(const ObjectState& state) { return getRoll(state) * 180.0 / M_PI; }
478
486template <typename T>
487inline double getRollInDeg(const T& obj) {
488 return getRollInDeg(obj.state);
489}
490
497inline double getPitchInDeg(const ObjectState& state) { return getPitch(state) * 180.0 / M_PI; }
498
506template <typename T>
507inline double getPitchInDeg(const T& obj) {
508 return getPitchInDeg(obj.state);
509}
510
517inline double getYawInDeg(const ObjectState& state) { return getYaw(state) * 180.0 / M_PI; }
518
526template <typename T>
527inline double getYawInDeg(const T& obj) {
528 return getYawInDeg(obj.state);
529}
530
537inline gm::PoseWithCovariance getVelocityXYZWithCovariance(const ObjectState& state) {
538 gm::PoseWithCovariance vel_lon_lat, vel_xyz;
539 vel_lon_lat.pose.position.x = getVelLon(state);
540 vel_lon_lat.pose.position.y = getVelLat(state);
541 vel_lon_lat.pose.position.z = 0.0;
542
543 int ix, jx, n = 2;
544 auto model_id = state.model_id;
545 for (int i = 0; i < n; i++) {
546 for (int j = 0; j < n; j++) {
547 if (i == 0 && hasVelLon(model_id))
548 ix = indexVelLon(model_id);
549 else if (i == 1 && hasVelLat(model_id))
550 ix = indexVelLat(model_id);
551 else
552 continue;
553
554 if (j == 0 && hasVelLon(model_id))
555 jx = indexVelLon(model_id);
556 else if (j == 1 && hasVelLat(model_id))
557 jx = indexVelLat(model_id);
558 else
559 continue;
560
561 vel_lon_lat.covariance.at(6 * i + j) = getContinuousStateCovarianceAt(state, ix, jx);
562 }
563 }
564
565 tf2::Quaternion q;
566 q.setRPY(0.0, 0.0, getYaw(state));
567 gm::TransformStamped tf;
568 tf.transform.rotation = tf2::toMsg(q);
569
570#ifdef ROS1
571 gm::PoseWithCovarianceStamped vel_lon_lat_stamped, vel_xyz_stamped;
572 vel_lon_lat_stamped.pose = vel_lon_lat;
573 tf2::doTransform(vel_lon_lat_stamped, vel_xyz_stamped, tf);
574 vel_xyz = vel_xyz_stamped.pose;
575#else
576 tf2::doTransform(vel_lon_lat, vel_xyz, tf);
577#endif
578
579 return vel_xyz;
580}
581
589template <typename T>
590inline gm::PoseWithCovariance getVelocityXYZWithCovariance(const T& obj) {
591 return getVelocityXYZWithCovariance(obj.state);
592}
593
600inline gm::Vector3 getVelocityXYZ(const ObjectState& state) {
601 gm::Vector3 vel_lon_lat, vel_xyz;
602 vel_lon_lat = getVelocity(state);
603 tf2::Quaternion q;
604 q.setRPY(0.0, 0.0, getYaw(state));
605 gm::TransformStamped tf;
606 tf.transform.rotation = tf2::toMsg(q);
607 tf2::doTransform(vel_lon_lat, vel_xyz, tf);
608 return vel_xyz;
609}
610
618template <typename T>
619inline gm::Vector3 getVelocityXYZ(const T& obj) {
620 return getVelocityXYZ(obj.state);
621}
622
629inline double getVelX(const ObjectState& state) { return getVelocityXYZ(state).x; }
630
638template <typename T>
639inline double getVelX(const T& obj) {
640 return getVelX(obj.state);
641}
642
649inline double getVelY(const ObjectState& state) { return getVelocityXYZ(state).y; }
650
658template <typename T>
659inline double getVelY(const T& obj) {
660 return getVelY(obj.state);
661}
662
669inline gm::PoseWithCovariance getAccelerationXYZWithCovariance(const ObjectState& state) {
670 gm::PoseWithCovariance acc_lon_lat, acc_xyz;
671 acc_lon_lat.pose.position.x = getAccLon(state);
672 acc_lon_lat.pose.position.y = getAccLat(state);
673 acc_lon_lat.pose.position.z = 0.0;
674
675 int ix, jx, n = 2;
676 auto model_id = state.model_id;
677 for (int i = 0; i < n; i++) {
678 for (int j = 0; j < n; j++) {
679 if (i == 0 && hasAccLon(model_id))
680 ix = indexAccLon(model_id);
681 else if (i == 1 && hasAccLat(model_id))
682 ix = indexAccLat(model_id);
683 else
684 continue;
685
686 if (j == 0 && hasAccLon(model_id))
687 jx = indexAccLon(model_id);
688 else if (j == 1 && hasAccLat(model_id))
689 jx = indexAccLat(model_id);
690 else
691 continue;
692
693 acc_lon_lat.covariance.at(6 * i + j) = getContinuousStateCovarianceAt(state, ix, jx);
694 }
695 }
696
697 tf2::Quaternion q;
698 q.setRPY(0.0, 0.0, getYaw(state));
699 gm::TransformStamped tf;
700 tf.transform.rotation = tf2::toMsg(q);
701#ifdef ROS1
702 gm::PoseWithCovarianceStamped acc_lon_lat_stamped, acc_xyz_stamped;
703 acc_lon_lat_stamped.pose = acc_lon_lat;
704 tf2::doTransform(acc_lon_lat_stamped, acc_xyz_stamped, tf);
705 acc_xyz = acc_xyz_stamped.pose;
706#else
707 tf2::doTransform(acc_lon_lat, acc_xyz, tf);
708#endif
709 return acc_xyz;
710}
711
719template <typename T>
720inline gm::PoseWithCovariance getAccelerationXYZWithCovariance(const T& obj) {
721 return getAccelerationXYZWithCovariance(obj.state);
722}
723
730inline gm::Vector3 getAccelerationXYZ(const ObjectState& state) {
731 gm::Vector3 acc_lon_lat, acc_xyz;
732 acc_lon_lat = getAcceleration(state);
733 tf2::Quaternion q;
734 q.setRPY(0.0, 0.0, getYaw(state));
735 gm::TransformStamped tf;
736 tf.transform.rotation = tf2::toMsg(q);
737 tf2::doTransform(acc_lon_lat, acc_xyz, tf);
738 return acc_xyz;
739}
740
748template <typename T>
749inline gm::Vector3 getAccelerationXYZ(const T& obj) {
750 return getAccelerationXYZ(obj.state);
751}
752
759inline double getAccX(const ObjectState& state) { return getAccelerationXYZ(state).x; }
760
768template <typename T>
769inline double getAccX(const T& obj) {
770 return getAccX(obj.state);
771}
772
779inline double getAccY(const ObjectState& state) { return getAccelerationXYZ(state).y; }
780
788template <typename T>
789inline double getAccY(const T& obj) {
790 return getAccY(obj.state);
791}
792
793// --- misc ------------------------------------------------------------------
794
801inline ObjectClassification getClassWithHighestProbability(const ObjectState& state) {
802 ObjectClassification highest_prob_class;
803 auto highest_prob_class_it = std::max_element(
804 state.classifications.begin(), state.classifications.end(),
805 [](const ObjectClassification& c1, const ObjectClassification& c2) { return c1.probability < c2.probability; });
806 if (highest_prob_class_it == state.classifications.end()) {
807 highest_prob_class.probability = -1.0;
808 highest_prob_class.type = ObjectClassification::UNKNOWN;
809 } else {
810 highest_prob_class = *highest_prob_class_it;
811 }
812 return highest_prob_class;
813}
814
822template <typename T>
823inline ObjectClassification getClassWithHighestProbability(const T& obj) {
824 return getClassWithHighestProbability(obj.state);
825}
826
827} // namespace object_access
828
829} // 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
gm::PoseWithCovariance getAccelerationXYZWithCovariance(const ObjectState &state)
Get the acceleration XYZ with covariance of a given object state.
double getAccX(const ObjectState &state)
Get the x-acceleration of a given object state.
ObjectClassification getClassWithHighestProbability(const ObjectState &state)
Get the classification with highest probability of a given object state.
std::vector< double > getContinuousStateCovariance(const ObjectState &state)
Get the continuous state covariance for a given object state.
gm::Point getCenterPosition(const ObjectState &state)
Get the object's geometric center position.
double getPitchInDeg(const ObjectState &state)
Get the pitch in degree of a given object state.
double getVelocityMagnitude(const ObjectState &state)
Get the velocity magnitude of a given object state.
double getAccelerationMagnitude(const ObjectState &state)
Get the acceleration magnitude of a given object state.
double getAccY(const ObjectState &state)
Get the y-acceleration of a given object state.
std::vector< double > getContinuousState(const ObjectState &state)
Get the continuous state for a given object state.
gm::Point getPosition(const ObjectState &state)
Get the position of a given object state.
gm::Quaternion getOrientation(const ObjectState &state)
Get the orientation of a given object state.
double getContinuousStateCovarianceAt(const ObjectState &state, const unsigned int i, const unsigned int j)
Get the continuous state covariance entry (i,j) for a given object state.
double getYawInDeg(const ObjectState &state)
Get the yaw in degree of a given object state.
gm::Vector3 getVelocityXYZ(const ObjectState &state)
Get the velocity XYZ of a given object state.
gm::PoseWithCovariance getPoseWithCovariance(const ObjectState &state)
Get the pose with covariance of a given object state.
gm::Vector3 getAcceleration(const ObjectState &state)
Get the acceleration of a given object state.
gm::Pose getPose(const ObjectState &state)
Get the pose of a given object state.
std::vector< double > getPoseCovariance(const ObjectState &state)
Get the pose covariance of a given object state.
gm::PoseWithCovariance getVelocityXYZWithCovariance(const ObjectState &state)
Get the velocity XYZ with covariance of a object state.
gm::Vector3 getVelocity(const ObjectState &state)
Get the velocity of a given object state.
gm::Vector3 getAccelerationXYZ(const ObjectState &state)
Get the acceleration XYZ of a given object state.
double getRollInDeg(const ObjectState &state)
Get the roll in degree of a given object state.
std::vector< double > getContinuousStateCovarianceDiagonal(const ObjectState &state)
Get the continuous state covariance diagonal for a given object state.
double getVelY(const ObjectState &state)
Get the y-velocity of a given object state.
std::vector< long int > getDiscreteState(const ObjectState &state)
Get the discrete state for a given object state.
double getVelX(const ObjectState &state)
Get the x-velocity of a given object state.
Getter functions for objects state members.
double getZ(const ObjectState &state)
Get the z-position for a given object state.
double getRoll(const ObjectState &state)
Get the roll for a given object state.
double getVelLon(const ObjectState &state)
Get the longitudinal velocity for a given object state.
double getAccLon(const ObjectState &state)
Get the longitudinal acceleration 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.
double getX(const ObjectState &state)
Get the x-position 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.
bool hasYaw(const unsigned char &model_id)
Indicates if given model contains a yaw.
int indexVelLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal velocity 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.
bool hasZ(const unsigned char &model_id)
Indicates if given model contains a z-position.
bool hasAccLat(const unsigned char &model_id)
Indicates if given model contains a lateral acceleration.
bool hasVelLat(const unsigned char &model_id)
Indicates if given model contains a lateral velocity.
int indexVelLat(const unsigned char &model_id)
Get the vector-index that stores the lateral velocity for a given model-id.
bool hasY(const unsigned char &model_id)
Indicates if given model contains a y-position.
bool hasRoll(const unsigned char &model_id)
Indicates if given model contains a roll.
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
bool hasX(const unsigned char &model_id)
Indicates if given model contains an x-position.
bool hasVelLon(const unsigned char &model_id)
Indicates if given model contains a longitudinal velocity.
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.
bool hasPitch(const unsigned char &model_id)
Indicates if given model contains a pitch.
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 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
bool hasAccLon(const unsigned char &model_id)
Indicates if given model contains a longitudinal acceleration.
int indexYaw(const unsigned char &model_id)
Get the vector-index that stores the yaw for a given model-id.
int getContinuousStateSize(const ObjectState &state)
Get the continuous state size for a given object state.
Definition utils.h:51