38namespace perception_msgs
41namespace object_access
54 state.continuous_state = val;
79 state.discrete_state = val;
104 state.continuous_state_covariance = val;
130 ObjectState & state,
const unsigned int i,
const unsigned int j,
const double val)
134 state.continuous_state_covariance[n * i + j] = val;
148 T & obj,
const unsigned int i,
const unsigned int j,
const double val)
187inline void setPosition(ObjectState & state,
const gm::Point val,
const bool reset_covariance =
true)
189 setX(state, val.x, reset_covariance);
190 setY(state, val.y, reset_covariance);
191 setZ(state, val.z, reset_covariance);
203inline void setPosition(T & obj,
const gm::Point val,
const bool reset_covariance =
true)
215inline void setPosition(ObjectState & state,
const std::array<double, 3> & val,
const bool reset_covariance =
true)
217 setX(state, val[0], reset_covariance);
218 setY(state, val[1], reset_covariance);
219 setZ(state, val[2], reset_covariance);
231inline void setPosition(T & obj,
const std::array<double, 3> & val,
const bool reset_covariance =
true)
243inline void setOrientation(ObjectState & state,
const gm::Quaternion & val,
const bool reset_covariance =
true)
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);
251 if (
hasYaw(state.model_id))
setYaw(state, yaw, reset_covariance);
263inline void setOrientation(T & obj,
const gm::Quaternion & val,
const bool reset_covariance =
true)
275inline void setOrientation(ObjectState & state,
const std::array<double, 3> & val,
const bool reset_covariance =
true)
277 if (
hasRoll(state.model_id))
setRoll(state, val[0], reset_covariance);
279 if (
hasYaw(state.model_id))
setYaw(state, val[2], reset_covariance);
291inline void setOrientation(T & obj,
const std::array<double, 3> & val,
const bool reset_covariance =
true)
303inline void setPose(ObjectState & state,
const gm::Pose & val,
const bool reset_covariance =
true)
305 setPosition(state, val.position, reset_covariance);
318inline void setPose(T & obj,
const gm::Pose & val,
const bool reset_covariance =
true)
320 setPose(obj.state, val, reset_covariance);
332 ObjectState & state,
const std::array<double, 3> & xyz,
const std::array<double, 3> & rpy,
const bool reset_covariance =
true)
348inline void setPose(T & obj,
const std::array<double, 3> & xyz,
const std::array<double, 3> & rpy,
const bool reset_covariance =
true)
350 setPose(obj.state, xyz, rpy, reset_covariance);
360 ObjectState & state,
const gm::PoseWithCovariance::_covariance_type & val)
363 const int model_id = state.model_id;
365 for (
int i = 0; i < n; i++) {
366 for (
int j = 0; j < n; j++) {
367 if (i == 0 &&
hasX(model_id))
369 else if (i == 1 &&
hasY(model_id))
371 else if (i == 2 &&
hasZ(model_id))
373 else if (i == 3 &&
hasRoll(model_id))
375 else if (i == 4 &&
hasPitch(model_id))
377 else if (i == 5 &&
hasYaw(model_id))
379 if (j == 0 &&
hasX(model_id))
381 else if (j == 1 &&
hasY(model_id))
383 else if (j == 2 &&
hasZ(model_id))
385 else if (j == 3 &&
hasRoll(model_id))
387 else if (j == 4 &&
hasPitch(model_id))
389 else if (j == 5 &&
hasYaw(model_id))
416 setPose(state, val.pose,
false);
440inline void setVelocity(ObjectState & state,
const gm::Vector3 & val,
const bool reset_covariance =
true)
442 setVelLon(state, val.x, reset_covariance);
443 setVelLat(state, val.y, reset_covariance);
454inline void setVelocity(T & obj,
const gm::Vector3 & val,
const bool reset_covariance =
true)
466inline void setVelocity(ObjectState & state,
const std::array<double, 2> & val,
const bool reset_covariance =
true)
468 setVelLon(state, val[0], reset_covariance);
469 setVelLat(state, val[1], reset_covariance);
481inline void setVelocity(T & obj,
const std::array<double, 2> & val,
const bool reset_covariance =
true)
493inline void setAcceleration(ObjectState & state,
const gm::Vector3 & val,
const bool reset_covariance =
true)
495 setAccLon(state, val.x, reset_covariance);
496 setAccLat(state, val.y, reset_covariance);
508inline void setAcceleration(T & obj,
const gm::Vector3 & val,
const bool reset_covariance =
true)
520inline void setAcceleration(ObjectState & state,
const std::array<double, 2> & val,
const bool reset_covariance =
true)
522 setAccLon(state, val[0], reset_covariance);
523 setAccLat(state, val[1], reset_covariance);
535inline void setAcceleration(T & obj,
const std::array<double, 2> & val,
const bool reset_covariance =
true)
549inline void setRollInDeg(ObjectState & state,
const double val,
const bool reset_covariance =
true)
551 setRoll(state, val * M_PI / 180.0, reset_covariance);
563inline void setRollInDeg(T & obj,
const double val,
const bool reset_covariance =
true)
575inline void setPitchInDeg(ObjectState & state,
const double val,
const bool reset_covariance =
true)
577 setPitch(state, val * M_PI / 180.0, reset_covariance);
589inline void setPitchInDeg(T & obj,
const double val,
const bool reset_covariance =
true)
601inline void setYawInDeg(ObjectState & state,
const double val,
const bool reset_covariance =
true)
603 setYaw(state, val * M_PI / 180.0, reset_covariance);
615inline void setYawInDeg(T & obj,
const double val,
const bool reset_covariance =
true)
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)
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;
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;
645 q.setRPY(0.0, 0.0, -yaw);
646 gm::TransformStamped tf;
647 tf.transform.rotation = tf2::toMsg(q);
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;
655 tf2::doTransform(vel_xyz, vel_lon_lat, tf);
658 setVelocity(state, {vel_lon_lat.pose.position.x, vel_lon_lat.pose.position.y},
false);
659 setYaw(state, yaw,
false);
662 auto model_id = state.model_id;
663 for (
int i = 0; i < n; i++) {
664 for (
int j = 0; j < n; j++) {
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)
711inline void setVelocityXYZYaw(ObjectState & state,
const gm::Vector3 & vel_xyz,
const double yaw,
const bool reset_covariance =
true)
713 gm::Vector3 vel_lon_lat, vel_xyz_in;
714 vel_xyz_in = vel_xyz;
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);
721 setYaw(state, yaw, reset_covariance);
734inline void setVelocityXYZYaw(T & obj,
const gm::Vector3 & vel_xyz,
const double yaw,
const bool reset_covariance =
true)
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)
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;
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;
764 q.setRPY(0.0, 0.0, -yaw);
765 gm::TransformStamped tf;
766 tf.transform.rotation = tf2::toMsg(q);
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;
774 tf2::doTransform(acc_xyz, acc_lon_lat, tf);
777 setAcceleration(state, {acc_lon_lat.pose.position.x, acc_lon_lat.pose.position.y},
false);
778 setYaw(state, yaw,
false);
781 auto model_id = state.model_id;
782 for (
int i = 0; i < n; i++) {
783 for (
int j = 0; j < n; j++) {
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)
831 ObjectState & state,
const gm::Vector3 & acc_xyz,
const double yaw,
const bool reset_covariance =
true)
833 gm::Vector3 acc_lon_lat, acc_xyz_in;
834 acc_xyz_in = acc_xyz;
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);
841 setYaw(state, yaw, reset_covariance);
854inline void setAccelerationXYZYaw(T & obj,
const gm::Vector3 & acc_xyz,
const double yaw,
const bool reset_covariance =
true)
Object state sanity checks.
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
void sanityCheckContinuousStateCovariance(const ObjectState &state)
Perform sanity check on continuous state covariance of given object state.
void sanityCheckDiscreteState(const ObjectState &state)
Perform sanity check on discrete state of given object state.
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.
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.
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.
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.