perception_interfaces 1.0.0
Loading...
Searching...
No Matches
convenience_state_setters.h
Go to the documentation of this file.
1
30#pragma once
31
35
36#include <array>
37
38namespace perception_msgs
39{
40
41namespace object_access
42{
43
44// --- full state/covariance -------------------------------------------------
45
52inline void setContinuousState(ObjectState & state, const std::vector<double> & val)
53{
54 state.continuous_state = val;
56}
57
65template <typename T>
66inline void setContinuousState(T & obj, const std::vector<double> & val)
67{
68 setContinuousState(obj.state, val);
69}
70
77inline void setDiscreteState(ObjectState & state, const std::vector<long int> & val)
78{
79 state.discrete_state = val;
81}
82
90template <typename T>
91inline void setDiscreteState(T & obj, const std::vector<long int> & val)
92{
93 setDiscreteState(obj.state, val);
94}
95
102inline void setContinuousStateCovariance(ObjectState & state, const std::vector<double> & val)
103{
104 state.continuous_state_covariance = val;
106}
107
115template <typename T>
116inline void setContinuousStateCovariance(T & obj, const std::vector<double> & val)
117{
118 setContinuousStateCovariance(obj.state, val);
119}
120
130 ObjectState & state, const unsigned int i, const unsigned int j, const double val)
131{
133 const int n = getContinuousStateSize(state);
134 state.continuous_state_covariance[n * i + j] = val;
135}
136
146template <typename T>
148 T & obj, const unsigned int i, const unsigned int j, const double val)
149{
150 setContinuousStateCovarianceAt(obj.state, i, j, val);
151}
152
159inline void setContinuousStateCovarianceDiagonal(ObjectState & state, const std::vector<double> val)
160{
161 const int n = getContinuousStateSize(state);
162 for (int i = 0; i < n; i++) setContinuousStateCovarianceAt(state, i, i, val[i]);
163}
164
172template <typename T>
173inline void setContinuousStateCovarianceDiagonal(T & obj, const std::vector<double> val)
174{
176}
177
178// --- vector quantities -----------------------------------------------------
179
187inline void setPosition(ObjectState & state, const gm::Point val, const bool reset_covariance = true)
188{
189 setX(state, val.x, reset_covariance);
190 setY(state, val.y, reset_covariance);
191 setZ(state, val.z, reset_covariance);
192}
193
202template <typename T>
203inline void setPosition(T & obj, const gm::Point val, const bool reset_covariance = true)
204{
205 setPosition(obj.state, val, reset_covariance);
206}
207
215inline void setPosition(ObjectState & state, const std::array<double, 3> & val, const bool reset_covariance = true)
216{
217 setX(state, val[0], reset_covariance);
218 setY(state, val[1], reset_covariance);
219 setZ(state, val[2], reset_covariance);
220}
221
230template <typename T>
231inline void setPosition(T & obj, const std::array<double, 3> & val, const bool reset_covariance = true)
232{
233 setPosition(obj.state, val, reset_covariance);
234}
235
243inline void setOrientation(ObjectState & state, const gm::Quaternion & val, const bool reset_covariance = true)
244{
245 tf2::Quaternion q;
246 tf2::fromMsg(val, q);
247 double roll, pitch, yaw;
248 tf2::Matrix3x3(q).getRPY(roll, pitch, yaw);
249 if (hasRoll(state.model_id)) setRoll(state, roll, reset_covariance);
250 if (hasPitch(state.model_id)) setPitch(state, pitch, reset_covariance);
251 if (hasYaw(state.model_id)) setYaw(state, yaw, reset_covariance);
252}
253
262template <typename T>
263inline void setOrientation(T & obj, const gm::Quaternion & val, const bool reset_covariance = true)
264{
265 setOrientation(obj.state, val, reset_covariance);
266}
267
275inline void setOrientation(ObjectState & state, const std::array<double, 3> & val, const bool reset_covariance = true)
276{
277 if (hasRoll(state.model_id)) setRoll(state, val[0], reset_covariance);
278 if (hasPitch(state.model_id)) setPitch(state, val[1], reset_covariance);
279 if (hasYaw(state.model_id)) setYaw(state, val[2], reset_covariance);
280}
281
290template <typename T>
291inline void setOrientation(T & obj, const std::array<double, 3> & val, const bool reset_covariance = true)
292{
293 setOrientation(obj.state, val, reset_covariance);
294}
295
303inline void setPose(ObjectState & state, const gm::Pose & val, const bool reset_covariance = true)
304{
305 setPosition(state, val.position, reset_covariance);
306 setOrientation(state, val.orientation, reset_covariance);
307}
308
317template <typename T>
318inline void setPose(T & obj, const gm::Pose & val, const bool reset_covariance = true)
319{
320 setPose(obj.state, val, reset_covariance);
321}
322
331inline void setPose(
332 ObjectState & state, const std::array<double, 3> & xyz, const std::array<double, 3> & rpy, const bool reset_covariance = true)
333{
334 setPosition(state, xyz, reset_covariance);
335 setOrientation(state, rpy, reset_covariance);
336}
337
347template <typename T>
348inline void setPose(T & obj, const std::array<double, 3> & xyz, const std::array<double, 3> & rpy, const bool reset_covariance = true)
349{
350 setPose(obj.state, xyz, rpy, reset_covariance);
351}
352
360 ObjectState & state, const gm::PoseWithCovariance::_covariance_type & val)
361{
362 const int n = 6;
363 const int model_id = state.model_id;
364 int ix, jx;
365 for (int i = 0; i < n; i++) {
366 for (int j = 0; j < n; j++) {
367 if (i == 0 && hasX(model_id))
368 ix = indexX(model_id);
369 else if (i == 1 && hasY(model_id))
370 ix = indexY(model_id);
371 else if (i == 2 && hasZ(model_id))
372 ix = indexZ(model_id);
373 else if (i == 3 && hasRoll(model_id))
374 ix = indexRoll(model_id);
375 else if (i == 4 && hasPitch(model_id))
376 ix = indexPitch(model_id);
377 else if (i == 5 && hasYaw(model_id))
378 ix = indexYaw(model_id);
379 if (j == 0 && hasX(model_id))
380 jx = indexX(model_id);
381 else if (j == 1 && hasY(model_id))
382 jx = indexY(model_id);
383 else if (j == 2 && hasZ(model_id))
384 jx = indexZ(model_id);
385 else if (j == 3 && hasRoll(model_id))
386 jx = indexRoll(model_id);
387 else if (j == 4 && hasPitch(model_id))
388 jx = indexPitch(model_id);
389 else if (j == 5 && hasYaw(model_id))
390 jx = indexYaw(model_id);
391 setContinuousStateCovarianceAt(state, ix, jx, val[n * i + j]);
392 }
393 }
394}
402template <typename T>
403inline void setPoseCovariance(T & obj, const gm::PoseWithCovariance::_covariance_type & val)
404{
405 setPoseCovariance(obj.state, val);
406}
407
414inline void setPoseWithCovariance(ObjectState & state, const gm::PoseWithCovariance & val)
415{
416 setPose(state, val.pose, false);
417 setPoseCovariance(state, val.covariance);
418}
419
427template <typename T>
428inline void setPoseWithCovariance(T & obj, const gm::PoseWithCovariance & val)
429{
430 setPoseWithCovariance(obj.state, val);
431}
432
440inline void setVelocity(ObjectState & state, const gm::Vector3 & val, const bool reset_covariance = true)
441{
442 setVelLon(state, val.x, reset_covariance);
443 setVelLat(state, val.y, reset_covariance);
444}
453template <typename T>
454inline void setVelocity(T & obj, const gm::Vector3 & val, const bool reset_covariance = true)
455{
456 setVelocity(obj.state, val, reset_covariance);
457}
458
466inline void setVelocity(ObjectState & state, const std::array<double, 2> & val, const bool reset_covariance = true)
467{
468 setVelLon(state, val[0], reset_covariance);
469 setVelLat(state, val[1], reset_covariance);
470}
471
480template <typename T>
481inline void setVelocity(T & obj, const std::array<double, 2> & val, const bool reset_covariance = true)
482{
483 setVelocity(obj.state, val, reset_covariance);
484}
485
493inline void setAcceleration(ObjectState & state, const gm::Vector3 & val, const bool reset_covariance = true)
494{
495 setAccLon(state, val.x, reset_covariance);
496 setAccLat(state, val.y, reset_covariance);
497}
498
507template <typename T>
508inline void setAcceleration(T & obj, const gm::Vector3 & val, const bool reset_covariance = true)
509{
510 setAcceleration(obj.state, val, reset_covariance);
511}
512
520inline void setAcceleration(ObjectState & state, const std::array<double, 2> & val, const bool reset_covariance = true)
521{
522 setAccLon(state, val[0], reset_covariance);
523 setAccLat(state, val[1], reset_covariance);
524}
525
534template <typename T>
535inline void setAcceleration(T & obj, const std::array<double, 2> & val, const bool reset_covariance = true)
536{
537 setAcceleration(obj.state, val, reset_covariance);
538}
539
540// --- alternative state entries ---------------------------------------------
541
549inline void setRollInDeg(ObjectState & state, const double val, const bool reset_covariance = true)
550{
551 setRoll(state, val * M_PI / 180.0, reset_covariance);
552}
553
562template <typename T>
563inline void setRollInDeg(T & obj, const double val, const bool reset_covariance = true)
564{
565 setRollInDeg(obj.state, val, reset_covariance);
566}
567
575inline void setPitchInDeg(ObjectState & state, const double val, const bool reset_covariance = true)
576{
577 setPitch(state, val * M_PI / 180.0, reset_covariance);
578}
579
588template <typename T>
589inline void setPitchInDeg(T & obj, const double val, const bool reset_covariance = true)
590{
591 setPitchInDeg(obj.state, val, reset_covariance);
592}
593
601inline void setYawInDeg(ObjectState & state, const double val, const bool reset_covariance = true)
602{
603 setYaw(state, val * M_PI / 180.0, reset_covariance);
604}
605
614template <typename T>
615inline void setYawInDeg(T & obj, const double val, const bool reset_covariance = true)
616{
617 setYawInDeg(obj.state, val, reset_covariance);
618}
619
631 ObjectState & state, const gm::Vector3 & vel_xyz_in, const double yaw, const double var_vel_x,
632 const double var_vel_y, const double cov_vel_xy)
633{
634 gm::PoseWithCovariance vel_lon_lat, vel_xyz;
635 vel_xyz.pose.position.x = vel_xyz_in.x;
636 vel_xyz.pose.position.y = vel_xyz_in.y;
637 vel_xyz.pose.position.z = 0.0;
638
639 vel_xyz.covariance.at(0) = var_vel_x;
640 vel_xyz.covariance.at(1) = cov_vel_xy;
641 vel_xyz.covariance.at(6) = cov_vel_xy;
642 vel_xyz.covariance.at(7) = var_vel_y;
643
644 tf2::Quaternion q;
645 q.setRPY(0.0, 0.0, -yaw);
646 gm::TransformStamped tf;
647 tf.transform.rotation = tf2::toMsg(q);
648
649#ifdef ROS1
650 gm::PoseWithCovarianceStamped vel_lon_lat_stamped, vel_xyz_stamped;
651 vel_xyz_stamped.pose = vel_xyz;
652 tf2::doTransform(vel_xyz_stamped, vel_lon_lat_stamped, tf);
653 vel_lon_lat = vel_lon_lat_stamped.pose;
654#else
655 tf2::doTransform(vel_xyz, vel_lon_lat, tf);
656#endif
657
658 setVelocity(state, {vel_lon_lat.pose.position.x, vel_lon_lat.pose.position.y}, false);
659 setYaw(state, yaw, false);
660
661 int ix, jx, n = 2;
662 auto model_id = state.model_id;
663 for (int i = 0; i < n; i++) {
664 for (int j = 0; j < n; j++) {
665 if (i == 0 && hasVelLon(model_id))
666 ix = indexVelLon(model_id);
667 else if (i == 1 && hasVelLat(model_id))
668 ix = indexVelLat(model_id);
669 else
670 continue;
671
672 if (j == 0 && hasVelLon(model_id))
673 jx = indexVelLon(model_id);
674 else if (j == 1 && hasVelLat(model_id))
675 jx = indexVelLat(model_id);
676 else
677 continue;
678
679 setContinuousStateCovarianceAt(state, ix, jx, vel_lon_lat.covariance.at(6 * i + j));
680 }
681 }
682}
683
695template <typename T>
697 T & obj, const gm::Vector3 & vel_xyz_in, const double yaw, const double var_vel_x,
698 const double var_vel_y, const double cov_vel_xy)
699{
700 return setVelocityXYZYawWithCovariance(obj.state, vel_xyz_in, yaw, var_vel_x, var_vel_y, cov_vel_xy);
701}
702
711inline void setVelocityXYZYaw(ObjectState & state, const gm::Vector3 & vel_xyz, const double yaw, const bool reset_covariance = true)
712{
713 gm::Vector3 vel_lon_lat, vel_xyz_in;
714 vel_xyz_in = vel_xyz;
715 tf2::Quaternion q;
716 q.setRPY(0.0, 0.0, -yaw);
717 gm::TransformStamped tf;
718 tf.transform.rotation = tf2::toMsg(q);
719 tf2::doTransform(vel_xyz_in, vel_lon_lat, tf);
720 setVelocity(state, vel_lon_lat, reset_covariance);
721 setYaw(state, yaw, reset_covariance);
722}
723
733template <typename T>
734inline void setVelocityXYZYaw(T & obj, const gm::Vector3 & vel_xyz, const double yaw, const bool reset_covariance = true)
735{
736 setVelocityXYZYaw(obj.state, vel_xyz, yaw, reset_covariance);
737}
738
750 ObjectState & state, const gm::Vector3 & acc_xyz_in, const double yaw, const double var_acc_x,
751 const double var_acc_y, const double cov_acc_xy)
752{
753 gm::PoseWithCovariance acc_lon_lat, acc_xyz;
754 acc_xyz.pose.position.x = acc_xyz_in.x;
755 acc_xyz.pose.position.y = acc_xyz_in.y;
756 acc_xyz.pose.position.z = 0.0;
757
758 acc_xyz.covariance.at(0) = var_acc_x;
759 acc_xyz.covariance.at(1) = cov_acc_xy;
760 acc_xyz.covariance.at(6) = cov_acc_xy;
761 acc_xyz.covariance.at(7) = var_acc_y;
762
763 tf2::Quaternion q;
764 q.setRPY(0.0, 0.0, -yaw);
765 gm::TransformStamped tf;
766 tf.transform.rotation = tf2::toMsg(q);
767
768#ifdef ROS1
769 gm::PoseWithCovarianceStamped acc_lon_lat_stamped, acc_xyz_stamped;
770 acc_xyz_stamped.pose = acc_xyz;
771 tf2::doTransform(acc_xyz_stamped, acc_lon_lat_stamped, tf);
772 acc_lon_lat = acc_lon_lat_stamped.pose;
773#else
774 tf2::doTransform(acc_xyz, acc_lon_lat, tf);
775#endif
776
777 setAcceleration(state, {acc_lon_lat.pose.position.x, acc_lon_lat.pose.position.y}, false);
778 setYaw(state, yaw, false);
779
780 int ix, jx, n = 2;
781 auto model_id = state.model_id;
782 for (int i = 0; i < n; i++) {
783 for (int j = 0; j < n; j++) {
784 if (i == 0 && hasAccLon(model_id))
785 ix = indexAccLon(model_id);
786 else if (i == 1 && hasAccLat(model_id))
787 ix = indexAccLat(model_id);
788 else
789 continue;
790
791 if (j == 0 && hasAccLon(model_id))
792 jx = indexAccLon(model_id);
793 else if (j == 1 && hasAccLat(model_id))
794 jx = indexAccLat(model_id);
795 else
796 continue;
797
798 setContinuousStateCovarianceAt(state, ix, jx, acc_lon_lat.covariance.at(6 * i + j));
799 }
800 }
801}
802
814template <typename T>
816 T & obj, const gm::Vector3 & acc_xyz_in, const double yaw, const double var_acc_x,
817 const double var_acc_y, const double cov_acc_xy)
818{
819 return setAccelerationXYZYawWithCovariance(obj.state, acc_xyz_in, yaw, var_acc_x, var_acc_y, cov_acc_xy);
820}
821
831 ObjectState & state, const gm::Vector3 & acc_xyz, const double yaw, const bool reset_covariance = true)
832{
833 gm::Vector3 acc_lon_lat, acc_xyz_in;
834 acc_xyz_in = acc_xyz;
835 tf2::Quaternion q;
836 q.setRPY(0.0, 0.0, -yaw);
837 gm::TransformStamped tf;
838 tf.transform.rotation = tf2::toMsg(q);
839 tf2::doTransform(acc_xyz_in, acc_lon_lat, tf);
840 setAcceleration(state, acc_lon_lat, reset_covariance);
841 setYaw(state, yaw, reset_covariance);
842}
843
853template <typename T>
854inline void setAccelerationXYZYaw(T & obj, const gm::Vector3 & acc_xyz, const double yaw, const bool reset_covariance = true)
855{
856 setAccelerationXYZYaw(obj.state, acc_xyz, yaw, reset_covariance);
857}
858
859} // namespace object_access
860
861} // 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 sanityCheckContinuousStateCovariance(const ObjectState &state)
Perform sanity check on continuous state covariance of given object state.
Definition checks.h:124
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
Definition checks.h:104
void setPosition(ObjectState &state, const gm::Point val, const bool reset_covariance=true)
Set the position of a given object state.
void setContinuousStateCovarianceDiagonal(ObjectState &state, const std::vector< double > val)
Set the continuous state covariance diagonal of a given object state.
void setContinuousState(ObjectState &state, const std::vector< double > &val)
Set the continuous state of a given object state.
void setPitchInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the pitch in degree of a given object state.
void setPose(ObjectState &state, const gm::Pose &val, const bool reset_covariance=true)
Set the pose of a given object state.
void setAccelerationXYZYawWithCovariance(ObjectState &state, const gm::Vector3 &acc_xyz_in, const double yaw, const double var_acc_x, const double var_acc_y, const double cov_acc_xy)
Set the acceleration XYZ and yaw with covariance of a given object state.
void setAcceleration(ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
Set the acceleration of a given object state.
void setVelocityXYZYawWithCovariance(ObjectState &state, const gm::Vector3 &vel_xyz_in, const double yaw, const double var_vel_x, const double var_vel_y, const double cov_vel_xy)
Set the velocity XYZ and yaw with covariance of a given object state.
void setRollInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the roll in degree of a given object state.
void setContinuousStateCovarianceAt(ObjectState &state, const unsigned int i, const unsigned int j, const double val)
Set the continuous state covariance entry at (i,j) of a given object state.
void setDiscreteState(ObjectState &state, const std::vector< long int > &val)
Set the discrete state of a given object state.
void setVelocity(ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
Set the velocity of a given object state.
void setOrientation(ObjectState &state, const gm::Quaternion &val, const bool reset_covariance=true)
Set the orientation of a given object state.
void setPoseCovariance(ObjectState &state, const gm::PoseWithCovariance::_covariance_type &val)
Set the pose covariance of a given object state.
void setYawInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw in degree of a given object state.
void setAccelerationXYZYaw(ObjectState &state, const gm::Vector3 &acc_xyz, const double yaw, const bool reset_covariance=true)
Set the acceleration XYZ and yaw of a given template object that contains an object state.
void setVelocityXYZYaw(ObjectState &state, const gm::Vector3 &vel_xyz, const double yaw, const bool reset_covariance=true)
Set the velocity XYZ and yaw of a given object state.
void setContinuousStateCovariance(ObjectState &state, const std::vector< double > &val)
Set the continuous state covariance of a given object state.
void setPoseWithCovariance(ObjectState &state, const gm::PoseWithCovariance &val)
Set the pose with covariance of 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.
Setter functions for objects state members.
void setAccLat(ObjectState &state, const double val, const bool reset_covariance=true)
Set the lateral acceleration for a given object state.
void setAccLon(ObjectState &state, const double val, const bool reset_covariance=true)
Set the longitudinal acceleration for a given object state.
void setVelLon(ObjectState &state, const double val, const bool reset_covariance=true)
Set the longitdunial velocity for a given object state.
void setX(ObjectState &state, const double val, const bool reset_covariance=true)
Set the x-position for a given object state.
void setY(ObjectState &state, const double val, const bool reset_covariance=true)
Set the y-position for a given object state.
void setVelLat(ObjectState &state, const double val, const bool reset_covariance=true)
Set the lateral velocity for a given object state.
void setYaw(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw for a given object state.
void setRoll(ObjectState &state, const double val, const bool reset_covariance=true)
Set the roll for a given object state.
void setPitch(ObjectState &state, const double val, const bool reset_covariance=true)
Set the pitch for a given object state.
void setZ(ObjectState &state, const double val, const bool reset_covariance=true)
Set the z-position for a given object state.
int getContinuousStateSize(const ObjectState &state)
Get the continuous state size for a given object state.
Definition utils.h:51