39namespace perception_msgs {
41namespace object_access {
53 return state.continuous_state;
76 return state.discrete_state;
99 return state.continuous_state_covariance;
125 return covariance[n * i + j];
150 std::vector<double> diagonal(n);
177 position.x =
getX(state);
178 position.y =
getY(state);
179 position.z =
getZ(state);
203 double roll{0}, pitch{0}, yaw{0};
207 q.setRPY(roll, pitch, yaw);
208 return tf2::toMsg(q);
229inline gm::Pose
getPose(
const ObjectState& state) {
245 const gm::Vector3 offset_to_center = state.reference_point.translation_to_geometric_center;
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();
288 const int model_id = state.model_id;
289 std::vector<double> pose_covariance(n * n, 0.0);
291 for (
int i = 0; i < n; i++) {
292 for (
int j = 0; j < n; j++) {
293 if (i == 0 &&
hasX(model_id))
295 else if (i == 1 &&
hasY(model_id))
297 else if (i == 2 &&
hasZ(model_id))
299 else if (i == 3 &&
hasRoll(model_id))
301 else if (i == 4 &&
hasPitch(model_id))
303 else if (i == 5 &&
hasYaw(model_id))
308 if (j == 0 &&
hasX(model_id))
310 else if (j == 1 &&
hasY(model_id))
312 else if (j == 2 &&
hasZ(model_id))
314 else if (j == 3 &&
hasRoll(model_id))
316 else if (j == 4 &&
hasPitch(model_id))
318 else if (j == 5 &&
hasYaw(model_id))
326 return pose_covariance;
349 gm::PoseWithCovariance pose_with_covariance;
350 pose_with_covariance.pose =
getPose(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;
377 gm::Vector3 velocity;
405 return sqrt(pow(vel.x, 2) + pow(vel.y, 2) + pow(vel.z, 2));
426 gm::Vector3 acceleration;
429 acceleration.z = 0.0;
454 return sqrt(pow(acc.x, 2) + pow(acc.y, 2) + pow(acc.z, 2));
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;
544 auto model_id = state.model_id;
545 for (
int i = 0; i < n; i++) {
546 for (
int j = 0; j < n; j++) {
566 q.setRPY(0.0, 0.0,
getYaw(state));
567 gm::TransformStamped tf;
568 tf.transform.rotation = tf2::toMsg(q);
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;
576 tf2::doTransform(vel_lon_lat, vel_xyz, tf);
601 gm::Vector3 vel_lon_lat, vel_xyz;
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);
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;
676 auto model_id = state.model_id;
677 for (
int i = 0; i < n; i++) {
678 for (
int j = 0; j < n; j++) {
698 q.setRPY(0.0, 0.0,
getYaw(state));
699 gm::TransformStamped tf;
700 tf.transform.rotation = tf2::toMsg(q);
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;
707 tf2::doTransform(acc_lon_lat, acc_xyz, tf);
731 gm::Vector3 acc_lon_lat, acc_xyz;
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);
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;
810 highest_prob_class = *highest_prob_class_it;
812 return highest_prob_class;
Object state sanity checks.
void sanityCheckContinuousState(const ObjectState &state)
Perform sanity check on continuous state of given object state.
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.
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.
int getContinuousStateSize(const ObjectState &state)
Get the continuous state size for a given object state.