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

Convenience setter functions for objects state members. More...

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

Go to the source code of this file.

Functions

void perception_msgs::object_access::setContinuousState (ObjectState &state, const std::vector< double > &val)
 Set the continuous state of a given object state.
 
template<typename T >
void perception_msgs::object_access::setContinuousState (T &obj, const std::vector< double > &val)
 Set the continuous state of a given template object that contains an object state.
 
void perception_msgs::object_access::setDiscreteState (ObjectState &state, const std::vector< long int > &val)
 Set the discrete state of a given object state.
 
template<typename T >
void perception_msgs::object_access::setDiscreteState (T &obj, const std::vector< long int > &val)
 Set the discrete state of a given template object that contains an object state.
 
void perception_msgs::object_access::setContinuousStateCovariance (ObjectState &state, const std::vector< double > &val)
 Set the continuous state covariance of a given object state.
 
template<typename T >
void perception_msgs::object_access::setContinuousStateCovariance (T &obj, const std::vector< double > &val)
 Set the continuous state covariance of a given template object that contains an object state.
 
void perception_msgs::object_access::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.
 
template<typename T >
void perception_msgs::object_access::setContinuousStateCovarianceAt (T &obj, const unsigned int i, const unsigned int j, const double val)
 Set the continuous state covariance at (i,j) of a given template object that contains an object state.
 
void perception_msgs::object_access::setContinuousStateCovarianceDiagonal (ObjectState &state, const std::vector< double > val)
 Set the continuous state covariance diagonal of a given object state.
 
template<typename T >
void perception_msgs::object_access::setContinuousStateCovarianceDiagonal (T &obj, const std::vector< double > val)
 Set the continuous state covariance diagonal of a given template object that contains an object state.
 
void perception_msgs::object_access::setPosition (ObjectState &state, const gm::Point val, const bool reset_covariance=true)
 Set the position of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPosition (T &obj, const gm::Point val, const bool reset_covariance=true)
 Set the position of a given template object that contains an object state.
 
void perception_msgs::object_access::setPosition (ObjectState &state, const std::array< double, 3 > &val, const bool reset_covariance=true)
 Set the position of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPosition (T &obj, const std::array< double, 3 > &val, const bool reset_covariance=true)
 Set the position of a given template object that contains an object state.
 
void perception_msgs::object_access::setOrientation (ObjectState &state, const gm::Quaternion &val, const bool reset_covariance=true)
 Set the orientation of a given object state.
 
template<typename T >
void perception_msgs::object_access::setOrientation (T &obj, const gm::Quaternion &val, const bool reset_covariance=true)
 Set the orientation of a given template object that contains an object state.
 
void perception_msgs::object_access::setOrientation (ObjectState &state, const std::array< double, 3 > &val, const bool reset_covariance=true)
 Set the orientation of a given object state.
 
template<typename T >
void perception_msgs::object_access::setOrientation (T &obj, const std::array< double, 3 > &val, const bool reset_covariance=true)
 Set the orientation of a given template object that contains an object state.
 
void perception_msgs::object_access::setPose (ObjectState &state, const gm::Pose &val, const bool reset_covariance=true)
 Set the pose of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPose (T &obj, const gm::Pose &val, const bool reset_covariance=true)
 Set the pose of a given template object that contains an object state.
 
void perception_msgs::object_access::setPose (ObjectState &state, const std::array< double, 3 > &xyz, const std::array< double, 3 > &rpy, const bool reset_covariance=true)
 Set the pose of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPose (T &obj, const std::array< double, 3 > &xyz, const std::array< double, 3 > &rpy, const bool reset_covariance=true)
 Set the pose of a given template object that contains an object state.
 
void perception_msgs::object_access::setPoseCovariance (ObjectState &state, const gm::PoseWithCovariance::_covariance_type &val)
 Set the pose covariance of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPoseCovariance (T &obj, const gm::PoseWithCovariance::_covariance_type &val)
 Set the pose covariance of a given template object that contains an object state.
 
void perception_msgs::object_access::setPoseWithCovariance (ObjectState &state, const gm::PoseWithCovariance &val)
 Set the pose with covariance of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPoseWithCovariance (T &obj, const gm::PoseWithCovariance &val)
 Set the pose with covariance of a given template object that contains an object state.
 
void perception_msgs::object_access::setVelocity (ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
 Set the velocity of a given object state.
 
template<typename T >
void perception_msgs::object_access::setVelocity (T &obj, const gm::Vector3 &val, const bool reset_covariance=true)
 Set the velocity of a given template object that contains an object state.
 
void perception_msgs::object_access::setVelocity (ObjectState &state, const std::array< double, 2 > &val, const bool reset_covariance=true)
 Set the velocity of a given object state.
 
template<typename T >
void perception_msgs::object_access::setVelocity (T &obj, const std::array< double, 2 > &val, const bool reset_covariance=true)
 Set the velocity of a given template object that contains an object state.
 
void perception_msgs::object_access::setAcceleration (ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
 Set the acceleration of a given object state.
 
template<typename T >
void perception_msgs::object_access::setAcceleration (T &obj, const gm::Vector3 &val, const bool reset_covariance=true)
 Set the acceleration of a given template object that contains an object state.
 
void perception_msgs::object_access::setAcceleration (ObjectState &state, const std::array< double, 2 > &val, const bool reset_covariance=true)
 Set the acceleration of a given object state.
 
template<typename T >
void perception_msgs::object_access::setAcceleration (T &obj, const std::array< double, 2 > &val, const bool reset_covariance=true)
 Set the acceleration of a given template object that contains an object state.
 
void perception_msgs::object_access::setRollInDeg (ObjectState &state, const double val, const bool reset_covariance=true)
 Set the roll in degree of a given object state.
 
template<typename T >
void perception_msgs::object_access::setRollInDeg (T &obj, const double val, const bool reset_covariance=true)
 Set the roll in deg of a given template object that contains an object state.
 
void perception_msgs::object_access::setPitchInDeg (ObjectState &state, const double val, const bool reset_covariance=true)
 Set the pitch in degree of a given object state.
 
template<typename T >
void perception_msgs::object_access::setPitchInDeg (T &obj, const double val, const bool reset_covariance=true)
 Set the pitch in degree of a given template object that contains an object state.
 
void perception_msgs::object_access::setYawInDeg (ObjectState &state, const double val, const bool reset_covariance=true)
 Set the yaw in degree of a given object state.
 
template<typename T >
void perception_msgs::object_access::setYawInDeg (T &obj, const double val, const bool reset_covariance=true)
 Set the yaw in degree of a given template object that contains an object state.
 
void perception_msgs::object_access::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.
 
template<typename T >
void perception_msgs::object_access::setVelocityXYZYawWithCovariance (T &obj, 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 template object that contains an object state.
 
void perception_msgs::object_access::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.
 
template<typename T >
void perception_msgs::object_access::setVelocityXYZYaw (T &obj, const gm::Vector3 &vel_xyz, const double yaw, const bool reset_covariance=true)
 Set the velocity XYZ and yaw of a given template object that contains an object state.
 
void perception_msgs::object_access::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.
 
template<typename T >
void perception_msgs::object_access::setAccelerationXYZYawWithCovariance (T &obj, 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 template object that contains an object state.
 
void perception_msgs::object_access::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.
 
template<typename T >
void perception_msgs::object_access::setAccelerationXYZYaw (T &obj, 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.
 

Detailed Description

Convenience setter 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 convenience_state_setters.h.

Function Documentation

◆ setAcceleration() [1/4]

void perception_msgs::object_access::setAcceleration ( ObjectState &  state,
const gm::Vector3 &  val,
const bool  reset_covariance = true 
)
inline

Set the acceleration of a given object state.

Parameters
state
val
reset_covariance

Definition at line 493 of file convenience_state_setters.h.

494{
495 setAccLon(state, val.x, reset_covariance);
496 setAccLat(state, val.y, reset_covariance);
497}
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.

◆ setAcceleration() [2/4]

void perception_msgs::object_access::setAcceleration ( ObjectState &  state,
const std::array< double, 2 > &  val,
const bool  reset_covariance = true 
)
inline

Set the acceleration of a given object state.

Parameters
state
val
reset_covariance

Definition at line 520 of file convenience_state_setters.h.

521{
522 setAccLon(state, val[0], reset_covariance);
523 setAccLat(state, val[1], reset_covariance);
524}

◆ setAcceleration() [3/4]

template<typename T >
void perception_msgs::object_access::setAcceleration ( T &  obj,
const gm::Vector3 &  val,
const bool  reset_covariance = true 
)
inline

Set the acceleration of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 508 of file convenience_state_setters.h.

509{
510 setAcceleration(obj.state, val, reset_covariance);
511}
void setAcceleration(ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
Set the acceleration of a given object state.

◆ setAcceleration() [4/4]

template<typename T >
void perception_msgs::object_access::setAcceleration ( T &  obj,
const std::array< double, 2 > &  val,
const bool  reset_covariance = true 
)
inline

Set the acceleration of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 535 of file convenience_state_setters.h.

536{
537 setAcceleration(obj.state, val, reset_covariance);
538}

◆ setAccelerationXYZYaw() [1/2]

void perception_msgs::object_access::setAccelerationXYZYaw ( ObjectState &  state,
const gm::Vector3 &  acc_xyz,
const double  yaw,
const bool  reset_covariance = true 
)
inline

Set the acceleration XYZ and yaw of a given template object that contains an object state.

Parameters
state
acc_xyz
yaw
reset_covariance

Definition at line 830 of file convenience_state_setters.h.

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}
void setYaw(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw for a given object state.

◆ setAccelerationXYZYaw() [2/2]

template<typename T >
void perception_msgs::object_access::setAccelerationXYZYaw ( T &  obj,
const gm::Vector3 &  acc_xyz,
const double  yaw,
const bool  reset_covariance = true 
)
inline

Set the acceleration XYZ and yaw of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
acc_xyz
yaw
reset_covariance

Definition at line 854 of file convenience_state_setters.h.

855{
856 setAccelerationXYZYaw(obj.state, acc_xyz, yaw, reset_covariance);
857}
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.

◆ setAccelerationXYZYawWithCovariance() [1/2]

void perception_msgs::object_access::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 
)
inline

Set the acceleration XYZ and yaw with covariance of a given object state.

Parameters
state
acc_xyz_in
yaw
var_acc_x
var_acc_y
cov_acc_xy

Definition at line 749 of file convenience_state_setters.h.

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}
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.
bool hasAccLat(const unsigned char &model_id)
Indicates if given model contains a lateral acceleration.
int indexAccLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal acceleration 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.
bool hasAccLon(const unsigned char &model_id)
Indicates if given model contains a longitudinal acceleration.

◆ setAccelerationXYZYawWithCovariance() [2/2]

template<typename T >
void perception_msgs::object_access::setAccelerationXYZYawWithCovariance ( T &  obj,
const gm::Vector3 &  acc_xyz_in,
const double  yaw,
const double  var_acc_x,
const double  var_acc_y,
const double  cov_acc_xy 
)
inline

Set the acceleration XYZ and yaw with covariance of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
acc_xyz_in
yaw
var_acc_x
var_acc_y
cov_acc_xy

Definition at line 815 of file convenience_state_setters.h.

818{
819 return setAccelerationXYZYawWithCovariance(obj.state, acc_xyz_in, yaw, var_acc_x, var_acc_y, cov_acc_xy);
820}
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.

◆ setContinuousState() [1/2]

void perception_msgs::object_access::setContinuousState ( ObjectState &  state,
const std::vector< double > &  val 
)
inline

Set the continuous state of a given object state.

Parameters
state
val

Definition at line 52 of file convenience_state_setters.h.

53{
54 state.continuous_state = val;
56}
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
Definition checks.h:84

◆ setContinuousState() [2/2]

template<typename T >
void perception_msgs::object_access::setContinuousState ( T &  obj,
const std::vector< double > &  val 
)
inline

Set the continuous state of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 66 of file convenience_state_setters.h.

67{
68 setContinuousState(obj.state, val);
69}
void setContinuousState(ObjectState &state, const std::vector< double > &val)
Set the continuous state of a given object state.

◆ setContinuousStateCovariance() [1/2]

void perception_msgs::object_access::setContinuousStateCovariance ( ObjectState &  state,
const std::vector< double > &  val 
)
inline

Set the continuous state covariance of a given object state.

Parameters
state
val

Definition at line 102 of file convenience_state_setters.h.

103{
104 state.continuous_state_covariance = val;
106}
void sanityCheckContinuousStateCovariance(const ObjectState &state)
Perform sanity check on continuous state covariance of given object state.
Definition checks.h:124

◆ setContinuousStateCovariance() [2/2]

template<typename T >
void perception_msgs::object_access::setContinuousStateCovariance ( T &  obj,
const std::vector< double > &  val 
)
inline

Set the continuous state covariance of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 116 of file convenience_state_setters.h.

117{
118 setContinuousStateCovariance(obj.state, val);
119}
void setContinuousStateCovariance(ObjectState &state, const std::vector< double > &val)
Set the continuous state covariance of a given object state.

◆ setContinuousStateCovarianceAt() [1/2]

void perception_msgs::object_access::setContinuousStateCovarianceAt ( ObjectState &  state,
const unsigned int  i,
const unsigned int  j,
const double  val 
)
inline

Set the continuous state covariance entry at (i,j) of a given object state.

Parameters
state
i
j
val

Definition at line 129 of file convenience_state_setters.h.

131{
133 const int n = getContinuousStateSize(state);
134 state.continuous_state_covariance[n * i + j] = val;
135}
int getContinuousStateSize(const ObjectState &state)
Get the continuous state size for a given object state.
Definition utils.h:51

◆ setContinuousStateCovarianceAt() [2/2]

template<typename T >
void perception_msgs::object_access::setContinuousStateCovarianceAt ( T &  obj,
const unsigned int  i,
const unsigned int  j,
const double  val 
)
inline

Set the continuous state covariance at (i,j) of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
i
j
val

Definition at line 147 of file convenience_state_setters.h.

149{
150 setContinuousStateCovarianceAt(obj.state, i, j, val);
151}

◆ setContinuousStateCovarianceDiagonal() [1/2]

void perception_msgs::object_access::setContinuousStateCovarianceDiagonal ( ObjectState &  state,
const std::vector< double >  val 
)
inline

Set the continuous state covariance diagonal of a given object state.

Parameters
state
val

Definition at line 159 of file convenience_state_setters.h.

160{
161 const int n = getContinuousStateSize(state);
162 for (int i = 0; i < n; i++) setContinuousStateCovarianceAt(state, i, i, val[i]);
163}

◆ setContinuousStateCovarianceDiagonal() [2/2]

template<typename T >
void perception_msgs::object_access::setContinuousStateCovarianceDiagonal ( T &  obj,
const std::vector< double >  val 
)
inline

Set the continuous state covariance diagonal of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 173 of file convenience_state_setters.h.

174{
176}
void setContinuousStateCovarianceDiagonal(ObjectState &state, const std::vector< double > val)
Set the continuous state covariance diagonal of a given object state.

◆ setDiscreteState() [1/2]

void perception_msgs::object_access::setDiscreteState ( ObjectState &  state,
const std::vector< long int > &  val 
)
inline

Set the discrete state of a given object state.

Parameters
state
val

Definition at line 77 of file convenience_state_setters.h.

78{
79 state.discrete_state = val;
81}
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
Definition checks.h:104

◆ setDiscreteState() [2/2]

template<typename T >
void perception_msgs::object_access::setDiscreteState ( T &  obj,
const std::vector< long int > &  val 
)
inline

Set the discrete state of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 91 of file convenience_state_setters.h.

92{
93 setDiscreteState(obj.state, val);
94}
void setDiscreteState(ObjectState &state, const std::vector< long int > &val)
Set the discrete state of a given object state.

◆ setOrientation() [1/4]

void perception_msgs::object_access::setOrientation ( ObjectState &  state,
const gm::Quaternion &  val,
const bool  reset_covariance = true 
)
inline

Set the orientation of a given object state.

Parameters
state
val
reset_covariance

Definition at line 243 of file convenience_state_setters.h.

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}
bool hasYaw(const unsigned char &model_id)
Indicates if given model contains a yaw.
bool hasRoll(const unsigned char &model_id)
Indicates if given model contains a roll.
bool hasPitch(const unsigned char &model_id)
Indicates if given model contains a pitch.
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.

◆ setOrientation() [2/4]

void perception_msgs::object_access::setOrientation ( ObjectState &  state,
const std::array< double, 3 > &  val,
const bool  reset_covariance = true 
)
inline

Set the orientation of a given object state.

Parameters
state
val
reset_covariance

Definition at line 275 of file convenience_state_setters.h.

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}

◆ setOrientation() [3/4]

template<typename T >
void perception_msgs::object_access::setOrientation ( T &  obj,
const gm::Quaternion &  val,
const bool  reset_covariance = true 
)
inline

Set the orientation of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 263 of file convenience_state_setters.h.

264{
265 setOrientation(obj.state, val, reset_covariance);
266}
void setOrientation(ObjectState &state, const gm::Quaternion &val, const bool reset_covariance=true)
Set the orientation of a given object state.

◆ setOrientation() [4/4]

template<typename T >
void perception_msgs::object_access::setOrientation ( T &  obj,
const std::array< double, 3 > &  val,
const bool  reset_covariance = true 
)
inline

Set the orientation of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 291 of file convenience_state_setters.h.

292{
293 setOrientation(obj.state, val, reset_covariance);
294}

◆ setPitchInDeg() [1/2]

void perception_msgs::object_access::setPitchInDeg ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch in degree of a given object state.

Parameters
state
val
reset_covariance

Definition at line 575 of file convenience_state_setters.h.

576{
577 setPitch(state, val * M_PI / 180.0, reset_covariance);
578}

◆ setPitchInDeg() [2/2]

template<typename T >
void perception_msgs::object_access::setPitchInDeg ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the pitch in degree of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 589 of file convenience_state_setters.h.

590{
591 setPitchInDeg(obj.state, val, reset_covariance);
592}
void setPitchInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the pitch in degree of a given object state.

◆ setPose() [1/4]

void perception_msgs::object_access::setPose ( ObjectState &  state,
const gm::Pose &  val,
const bool  reset_covariance = true 
)
inline

Set the pose of a given object state.

Parameters
state
val
reset_covariance

Definition at line 303 of file convenience_state_setters.h.

304{
305 setPosition(state, val.position, reset_covariance);
306 setOrientation(state, val.orientation, reset_covariance);
307}
void setPosition(ObjectState &state, const gm::Point val, const bool reset_covariance=true)
Set the position of a given object state.

◆ setPose() [2/4]

void perception_msgs::object_access::setPose ( ObjectState &  state,
const std::array< double, 3 > &  xyz,
const std::array< double, 3 > &  rpy,
const bool  reset_covariance = true 
)
inline

Set the pose of a given object state.

Parameters
state
xyz
rpy
reset_covariance

Definition at line 331 of file convenience_state_setters.h.

333{
334 setPosition(state, xyz, reset_covariance);
335 setOrientation(state, rpy, reset_covariance);
336}

◆ setPose() [3/4]

template<typename T >
void perception_msgs::object_access::setPose ( T &  obj,
const gm::Pose &  val,
const bool  reset_covariance = true 
)
inline

Set the pose of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 318 of file convenience_state_setters.h.

319{
320 setPose(obj.state, val, reset_covariance);
321}
void setPose(ObjectState &state, const gm::Pose &val, const bool reset_covariance=true)
Set the pose of a given object state.

◆ setPose() [4/4]

template<typename T >
void perception_msgs::object_access::setPose ( T &  obj,
const std::array< double, 3 > &  xyz,
const std::array< double, 3 > &  rpy,
const bool  reset_covariance = true 
)
inline

Set the pose of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
xyz
rpy
reset_covariance

Definition at line 348 of file convenience_state_setters.h.

349{
350 setPose(obj.state, xyz, rpy, reset_covariance);
351}

◆ setPoseCovariance() [1/2]

void perception_msgs::object_access::setPoseCovariance ( ObjectState &  state,
const gm::PoseWithCovariance::_covariance_type &  val 
)
inline

Set the pose covariance of a given object state.

Parameters
state
val

Definition at line 359 of file convenience_state_setters.h.

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}
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 hasY(const unsigned char &model_id)
Indicates if given model contains a y-position.
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.
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 indexPitch(const unsigned char &model_id)
Get the vector-index that stores the pitch 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 indexYaw(const unsigned char &model_id)
Get the vector-index that stores the yaw for a given model-id.

◆ setPoseCovariance() [2/2]

template<typename T >
void perception_msgs::object_access::setPoseCovariance ( T &  obj,
const gm::PoseWithCovariance::_covariance_type &  val 
)
inline

Set the pose covariance of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 403 of file convenience_state_setters.h.

404{
405 setPoseCovariance(obj.state, val);
406}
void setPoseCovariance(ObjectState &state, const gm::PoseWithCovariance::_covariance_type &val)
Set the pose covariance of a given object state.

◆ setPoseWithCovariance() [1/2]

void perception_msgs::object_access::setPoseWithCovariance ( ObjectState &  state,
const gm::PoseWithCovariance &  val 
)
inline

Set the pose with covariance of a given object state.

Parameters
state
val

Definition at line 414 of file convenience_state_setters.h.

415{
416 setPose(state, val.pose, false);
417 setPoseCovariance(state, val.covariance);
418}

◆ setPoseWithCovariance() [2/2]

template<typename T >
void perception_msgs::object_access::setPoseWithCovariance ( T &  obj,
const gm::PoseWithCovariance &  val 
)
inline

Set the pose with covariance of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val

Definition at line 428 of file convenience_state_setters.h.

429{
430 setPoseWithCovariance(obj.state, val);
431}
void setPoseWithCovariance(ObjectState &state, const gm::PoseWithCovariance &val)
Set the pose with covariance of a given object state.

◆ setPosition() [1/4]

void perception_msgs::object_access::setPosition ( ObjectState &  state,
const gm::Point  val,
const bool  reset_covariance = true 
)
inline

Set the position of a given object state.

Parameters
state
val
reset_covariance

Definition at line 187 of file convenience_state_setters.h.

188{
189 setX(state, val.x, reset_covariance);
190 setY(state, val.y, reset_covariance);
191 setZ(state, val.z, reset_covariance);
192}
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 setZ(ObjectState &state, const double val, const bool reset_covariance=true)
Set the z-position for a given object state.

◆ setPosition() [2/4]

void perception_msgs::object_access::setPosition ( ObjectState &  state,
const std::array< double, 3 > &  val,
const bool  reset_covariance = true 
)
inline

Set the position of a given object state.

Parameters
state
val
reset_covariance

Definition at line 215 of file convenience_state_setters.h.

216{
217 setX(state, val[0], reset_covariance);
218 setY(state, val[1], reset_covariance);
219 setZ(state, val[2], reset_covariance);
220}

◆ setPosition() [3/4]

template<typename T >
void perception_msgs::object_access::setPosition ( T &  obj,
const gm::Point  val,
const bool  reset_covariance = true 
)
inline

Set the position of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 203 of file convenience_state_setters.h.

204{
205 setPosition(obj.state, val, reset_covariance);
206}

◆ setPosition() [4/4]

template<typename T >
void perception_msgs::object_access::setPosition ( T &  obj,
const std::array< double, 3 > &  val,
const bool  reset_covariance = true 
)
inline

Set the position of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 231 of file convenience_state_setters.h.

232{
233 setPosition(obj.state, val, reset_covariance);
234}

◆ setRollInDeg() [1/2]

void perception_msgs::object_access::setRollInDeg ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll in degree of a given object state.

Parameters
state
val
reset_covariance

Definition at line 549 of file convenience_state_setters.h.

550{
551 setRoll(state, val * M_PI / 180.0, reset_covariance);
552}

◆ setRollInDeg() [2/2]

template<typename T >
void perception_msgs::object_access::setRollInDeg ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the roll in deg of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 563 of file convenience_state_setters.h.

564{
565 setRollInDeg(obj.state, val, reset_covariance);
566}
void setRollInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the roll in degree of a given object state.

◆ setVelocity() [1/4]

void perception_msgs::object_access::setVelocity ( ObjectState &  state,
const gm::Vector3 &  val,
const bool  reset_covariance = true 
)
inline

Set the velocity of a given object state.

Parameters
state
val
reset_covariance

Definition at line 440 of file convenience_state_setters.h.

441{
442 setVelLon(state, val.x, reset_covariance);
443 setVelLat(state, val.y, reset_covariance);
444}
void setVelLon(ObjectState &state, const double val, const bool reset_covariance=true)
Set the longitdunial velocity 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.

◆ setVelocity() [2/4]

void perception_msgs::object_access::setVelocity ( ObjectState &  state,
const std::array< double, 2 > &  val,
const bool  reset_covariance = true 
)
inline

Set the velocity of a given object state.

Parameters
state
val
reset_covariance

Definition at line 466 of file convenience_state_setters.h.

467{
468 setVelLon(state, val[0], reset_covariance);
469 setVelLat(state, val[1], reset_covariance);
470}

◆ setVelocity() [3/4]

template<typename T >
void perception_msgs::object_access::setVelocity ( T &  obj,
const gm::Vector3 &  val,
const bool  reset_covariance = true 
)
inline

Set the velocity of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 454 of file convenience_state_setters.h.

455{
456 setVelocity(obj.state, val, reset_covariance);
457}
void setVelocity(ObjectState &state, const gm::Vector3 &val, const bool reset_covariance=true)
Set the velocity of a given object state.

◆ setVelocity() [4/4]

template<typename T >
void perception_msgs::object_access::setVelocity ( T &  obj,
const std::array< double, 2 > &  val,
const bool  reset_covariance = true 
)
inline

Set the velocity of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 481 of file convenience_state_setters.h.

482{
483 setVelocity(obj.state, val, reset_covariance);
484}

◆ setVelocityXYZYaw() [1/2]

void perception_msgs::object_access::setVelocityXYZYaw ( ObjectState &  state,
const gm::Vector3 &  vel_xyz,
const double  yaw,
const bool  reset_covariance = true 
)
inline

Set the velocity XYZ and yaw of a given object state.

Parameters
state
vel_xyz
yaw
reset_covariance

Definition at line 711 of file convenience_state_setters.h.

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}

◆ setVelocityXYZYaw() [2/2]

template<typename T >
void perception_msgs::object_access::setVelocityXYZYaw ( T &  obj,
const gm::Vector3 &  vel_xyz,
const double  yaw,
const bool  reset_covariance = true 
)
inline

Set the velocity XYZ and yaw of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
vel_xyz
yaw
reset_covariance

Definition at line 734 of file convenience_state_setters.h.

735{
736 setVelocityXYZYaw(obj.state, vel_xyz, yaw, reset_covariance);
737}
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.

◆ setVelocityXYZYawWithCovariance() [1/2]

void perception_msgs::object_access::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 
)
inline

Set the velocity XYZ and yaw with covariance of a given object state.

Parameters
state
vel_xyz_in
yaw
var_vel_x
var_vel_y
cov_vel_xy

Definition at line 630 of file convenience_state_setters.h.

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}
int indexVelLon(const unsigned char &model_id)
Get the vector-index that stores the longitudinal velocity for a given model-id.
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 hasVelLon(const unsigned char &model_id)
Indicates if given model contains a longitudinal velocity.

◆ setVelocityXYZYawWithCovariance() [2/2]

template<typename T >
void perception_msgs::object_access::setVelocityXYZYawWithCovariance ( T &  obj,
const gm::Vector3 &  vel_xyz_in,
const double  yaw,
const double  var_vel_x,
const double  var_vel_y,
const double  cov_vel_xy 
)
inline

Set the velocity XYZ and yaw with covariance of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
vel_xyz_in
yaw
var_vel_x
var_vel_y
cov_vel_xy

Definition at line 696 of file convenience_state_setters.h.

699{
700 return setVelocityXYZYawWithCovariance(obj.state, vel_xyz_in, yaw, var_vel_x, var_vel_y, cov_vel_xy);
701}
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.

◆ setYawInDeg() [1/2]

void perception_msgs::object_access::setYawInDeg ( ObjectState &  state,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw in degree of a given object state.

Parameters
state
val
reset_covariance

Definition at line 601 of file convenience_state_setters.h.

602{
603 setYaw(state, val * M_PI / 180.0, reset_covariance);
604}

◆ setYawInDeg() [2/2]

template<typename T >
void perception_msgs::object_access::setYawInDeg ( T &  obj,
const double  val,
const bool  reset_covariance = true 
)
inline

Set the yaw in degree of a given template object that contains an object state.

Template Parameters
T
Parameters
obj
val
reset_covariance

Definition at line 615 of file convenience_state_setters.h.

616{
617 setYawInDeg(obj.state, val, reset_covariance);
618}
void setYawInDeg(ObjectState &state, const double val, const bool reset_covariance=true)
Set the yaw in degree of a given object state.