etsi_its_messages v3.4.0
Loading...
Searching...
No Matches
cpm_ts_getters.h File Reference

Getter functions for the ETSI ITS CPM (TS). More...

Go to the source code of this file.

Functions

uint32_t etsi_its_cpm_ts_msgs::access::getStationID (const ItsPduHeader &header)
 Get the StationID of ItsPduHeader.
double etsi_its_cpm_ts_msgs::access::getLatitude (const Latitude &latitude)
 Get the Latitude value.
double etsi_its_cpm_ts_msgs::access::getLongitude (const Longitude &longitude)
 Get the Longitude value.
double etsi_its_cpm_ts_msgs::access::getAltitude (const Altitude &altitude)
 Get the Altitude value.
double etsi_its_cpm_ts_msgs::access::getSpeed (const Speed &speed)
 Get the vehicle speed.
double etsi_its_cpm_ts_msgs::access::getSpeedConfidence (const Speed &speed)
 Get the Speed Confidence.
template<typename AccelerationMagnitude>
double etsi_its_cpm_ts_msgs::access::getAccelerationMagnitude (const AccelerationMagnitude &acceleration_magnitude)
 Get the AccelerationMagnitude value.
template<typename AccelerationMagnitude>
double etsi_its_cpm_ts_msgs::access::getAccelerationMagnitudeConfidence (const AccelerationMagnitude &acceleration_magnitude)
 Get the AccelerationMagnitude Confidence.
template<typename T>
gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition (const T &reference_position, int &zone, bool &northp)
 Get the UTM Position defined by the given ReferencePosition.
template<typename Heading>
double etsi_its_cpm_ts_msgs::access::getHeadingCDD (const Heading &heading)
 Get the Heading value.
template<typename Heading>
double etsi_its_cpm_ts_msgs::access::getHeadingConfidenceCDD (const Heading &heading)
 Get the Heading value.
template<typename YawRate>
double etsi_its_cpm_ts_msgs::access::getYawRateCDD (const YawRate &yaw_rate)
 Get the Yaw Rate value.
template<typename YawRate, typename YawRateConfidence = decltype(YawRate::yaw_rate_confidence)>
double etsi_its_cpm_ts_msgs::access::getYawRateConfidenceCDD (const YawRate &yaw_rate)
 Get the Yaw Rate Confidence.
template<typename SemiAxisLength>
double etsi_its_cpm_ts_msgs::access::getSemiAxis (const SemiAxisLength &semi_axis_length)
 Get the Semi Axis object.
template<typename PosConfidenceEllipse>
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse)
 Extract major axis length, minor axis length and orientation from the given position confidence ellipse.
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::CovMatrixFromConfidenceEllipse (double semi_major, double semi_minor, double major_orientation, const double object_heading)
 Convert the confidence ellipse to a covariance matrix.
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::WGSCovMatrixFromConfidenceEllipse (double semi_major, double semi_minor, double major_orientation)
 Convert the confidence ellipse to a covariance matrix.
template<typename PosConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse, const double object_heading)
 Get the covariance matrix of the position confidence ellipse.
template<typename PosConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse)
 Get the covariance matrix of the position confidence ellipse.
double etsi_its_cpm_ts_msgs::access::getLongitudinalAcceleration (const AccelerationComponent &longitudinal_acceleration)
 Get the longitudinal acceleration.
double etsi_its_cpm_ts_msgs::access::getLongitudinalAccelerationConfidence (const AccelerationComponent &longitudinal_acceleration)
 Get the Longitudinal Acceleration Confidence.
double etsi_its_cpm_ts_msgs::access::getLateralAcceleration (const AccelerationComponent &lateral_acceleration)
 Get the lateral acceleration.
double etsi_its_cpm_ts_msgs::access::getLateralAccelerationConfidence (const AccelerationComponent &lateral_acceleration)
 Get the Lateral Acceleration Confidence.
template<typename PositionConfidenceEllipse>
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPositionConfidenceEllipse (PositionConfidenceEllipse &position_confidence_ellipse)
 Extract major axis length, minor axis length and orientation from the given position confidence ellipse.
template<typename PositionConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getPositionConfidenceEllipse (const PositionConfidenceEllipse &position_confidence_ellipse, const double object_heading)
 Get the covariance matrix of the position confidence ellipse.
template<typename PositionConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSPositionConfidenceEllipse (const PositionConfidenceEllipse &position_confidence_ellipse)
 Get the covariance matrix of the position confidence ellipse.
uint32_t etsi_its_cpm_ts_msgs::access::getStationID (const CollectivePerceptionMessage &cpm)
 Retrieves the station ID from the given CPM.
TimestampIts etsi_its_cpm_ts_msgs::access::getReferenceTime (const CollectivePerceptionMessage &cpm)
 Get the Reference Time object.
uint64_t etsi_its_cpm_ts_msgs::access::getReferenceTimeValue (const CollectivePerceptionMessage &cpm)
 Get the ReferenceTime-Value.
double etsi_its_cpm_ts_msgs::access::getLatitude (const CollectivePerceptionMessage &cpm)
 Get the Latitude value of CPM.
double etsi_its_cpm_ts_msgs::access::getLongitude (const CollectivePerceptionMessage &cpm)
 Get the Longitude value of CPM.
double etsi_its_cpm_ts_msgs::access::getAltitude (const CollectivePerceptionMessage &cpm)
 Get the Altitude value of CPM.
gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition (const CollectivePerceptionMessage &cpm, int &zone, bool &northp)
 Get the UTM Position defined within the ManagementContainer of the CPM.
gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition (const CollectivePerceptionMessage &cpm)
 Get the UTM Position defined within the ManagementContainer of the CPM.
std::vector< uint8_t > etsi_its_cpm_ts_msgs::access::getCpmContainerIds (const CollectivePerceptionMessage &cpm)
 Retrieves the container IDs from a CPM.
WrappedCpmContainer etsi_its_cpm_ts_msgs::access::getCpmContainer (const CollectivePerceptionMessage &cpm, const uint8_t container_id)
WrappedCpmContainer etsi_its_cpm_ts_msgs::access::getPerceivedObjectContainer (const CollectivePerceptionMessage &cpm)
 Retrieves the perceived object container from a CPM.
uint8_t etsi_its_cpm_ts_msgs::access::getNumberOfPerceivedObjects (const WrappedCpmContainer &container)
uint8_t etsi_its_cpm_ts_msgs::access::getNumberOfPerceivedObjects (const CollectivePerceptionMessage &cpm)
PerceivedObject etsi_its_cpm_ts_msgs::access::getPerceivedObject (const WrappedCpmContainer &container, const uint8_t i)
 Retrieves the PerceivedObject at the specified index from the given WrappedCpmContainer.
uint16_t etsi_its_cpm_ts_msgs::access::getIdOfPerceivedObject (const PerceivedObject &object)
 Retrieves the ID of a perceived object.
int32_t etsi_its_cpm_ts_msgs::access::getCartesianCoordinate (const CartesianCoordinateWithConfidence &coordinate)
 Retrieves the Cartesian coordinate value from a CartesianCoordinateWithConfidence object.
uint16_t etsi_its_cpm_ts_msgs::access::getCartesianCoordinateConfidence (const CartesianCoordinateWithConfidence &coordinate)
 Retrieves the confidence value from a CartesianCoordinateWithConfidence object.
gm::Point etsi_its_cpm_ts_msgs::access::getPositionOfPerceivedObject (const PerceivedObject &object)
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPositionConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Position Confidences Of Perceived Object.
uint16_t etsi_its_cpm_ts_msgs::access::getCartesianAngle (const CartesianAngle &angle)
 Get the Cartesian angle of the PerceivedObject.
uint8_t etsi_its_cpm_ts_msgs::access::getCartesianAngleConfidence (const CartesianAngle &angle)
 Get the confidence of the Cartesian angle.
gm::Quaternion etsi_its_cpm_ts_msgs::access::getOrientationOfPerceivedObject (const PerceivedObject &object)
 Calculates the orientation of a perceived object.
double etsi_its_cpm_ts_msgs::access::getYawOfPerceivedObject (const PerceivedObject &object)
 Get the yaw of the PerceivedObject.
double etsi_its_cpm_ts_msgs::access::getYawConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Yaw Confidence Of Perceived Object object.
gm::Pose etsi_its_cpm_ts_msgs::access::getPoseOfPerceivedObject (const PerceivedObject &object)
 Get the pose of the PerceivedObject.
double etsi_its_cpm_ts_msgs::access::getYawRateOfPerceivedObject (const PerceivedObject &object)
 Get the yaw rate of the PerceivedObject.
double etsi_its_cpm_ts_msgs::access::getYawRateConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Yaw Rate Confidence Of Perceived Object.
double etsi_its_cpm_ts_msgs::access::getVelocityComponent (const VelocityComponent &velocity)
 Get the velocity component of the PerceivedObject.
double etsi_its_cpm_ts_msgs::access::getVelocityComponentConfidence (const VelocityComponent &velocity)
 Get the confidence of the velocity component.
gm::Vector3 etsi_its_cpm_ts_msgs::access::getCartesianVelocityOfPerceivedObject (const PerceivedObject &object)
 Get the Cartesian velocity of the PerceivedObject.
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getCartesianVelocityConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Cartesian Velocity Confidence Of Perceived Object object.
double etsi_its_cpm_ts_msgs::access::getAccelerationComponent (const AccelerationComponent &acceleration)
 Get the acceleration component of the PerceivedObject.
double etsi_its_cpm_ts_msgs::access::getAccelerationComponentConfidence (const AccelerationComponent &acceleration)
 Get the confidence of the acceleration component.
gm::Vector3 etsi_its_cpm_ts_msgs::access::getCartesianAccelerationOfPerceivedObject (const PerceivedObject &object)
 Get the Cartesian acceleration of the PerceivedObject.
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getCartesianAccelerationConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Cartesian Acceleration Confidence Of Perceived Object.
uint16_t etsi_its_cpm_ts_msgs::access::getXDimensionOfPerceivedObject (const PerceivedObject &object)
 Gets the x-dimension of a perceived object.
uint8_t etsi_its_cpm_ts_msgs::access::getXDimensionConfidenceOfPerceivedObject (const PerceivedObject &object)
 Gets the confidence of the x-dimension of a perceived object.
uint16_t etsi_its_cpm_ts_msgs::access::getYDimensionOfPerceivedObject (const PerceivedObject &object)
 Retrieves the y-dimension of a perceived object.
uint8_t etsi_its_cpm_ts_msgs::access::getYDimensionConfidenceOfPerceivedObject (const PerceivedObject &object)
 Gets the confidence of the y-dimension of a perceived object.
uint16_t etsi_its_cpm_ts_msgs::access::getZDimensionOfPerceivedObject (const PerceivedObject &object)
 Retrieves the z-dimension of a perceived object.
uint8_t etsi_its_cpm_ts_msgs::access::getZDimensionConfidenceOfPerceivedObject (const PerceivedObject &object)
 Gets the confidence of the z-dimension of a perceived object.
gm::Vector3 etsi_its_cpm_ts_msgs::access::getDimensionsOfPerceivedObject (const PerceivedObject &object)
 Retrieves the dimensions of a perceived object.
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getDimensionsConfidenceOfPerceivedObject (const PerceivedObject &object)
 Get the Dimensions Confidence Of Perceived Object.
gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPositionOfPerceivedObject (const CollectivePerceptionMessage &cpm, const PerceivedObject &object)
 Calculates the UTM position of a perceived object based on the CPMs referencep position.
const std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSRefPosConfidence (const CollectivePerceptionMessage &cpm)
 Get the confidence ellipse of the reference position as Covariance matrix.
uint8_t etsi_its_cpm_ts_msgs::access::getSensorID (const SensorInformation &sensor_information)
 Get the sensorId of a SensorInformation object.
uint8_t etsi_its_cpm_ts_msgs::access::getSensorType (const SensorInformation &sensor_information)
 Get the sensorType of a SensorInformation object.

Detailed Description

Getter functions for the ETSI ITS CPM (TS).

Definition in file cpm_ts_getters.h.

Function Documentation

◆ CovMatrixFromConfidenceEllipse()

std::array< double, 4 > etsi_its_cpm_ts_msgs::access::CovMatrixFromConfidenceEllipse ( double semi_major,
double semi_minor,
double major_orientation,
const double object_heading )
inline

Convert the confidence ellipse to a covariance matrix.

Note that the major_orientation is given in degrees, while the object_heading is given in radians!

Parameters
semi_majorSemi major axis length in meters
semi_minorSemi minor axis length in meters
major_orientationOrientation of the major axis in degrees, relative to WGS84
object_headingobject heading in radians, relative to WGS84
Returns
std::array<double, 4> The covariance matrix in vehicle coordinates (x = longitudinal, y = lateral)

Definition at line 244 of file cpm_ts_getters.h.

249 {
250 return coordinate.confidence.value;
251}
252
259inline gm::Point getPositionOfPerceivedObject(const PerceivedObject &object) {
260 gm::Point point;
261 point.x = double(getCartesianCoordinate(object.position.x_coordinate)) / 100.0;

◆ getAccelerationComponent()

double etsi_its_cpm_ts_msgs::access::getAccelerationComponent ( const AccelerationComponent & acceleration)
inline

Get the acceleration component of the PerceivedObject.

Parameters
accelerationAccelerationComponent to get the value from
Returns
double value of the acceleration component in m/s^2

Definition at line 506 of file cpm_ts_getters.h.

506 {
507 return double(acceleration.value.value) / 10.0;
508}

◆ getAccelerationComponentConfidence()

double etsi_its_cpm_ts_msgs::access::getAccelerationComponentConfidence ( const AccelerationComponent & acceleration)
inline

Get the confidence of the acceleration component.

Parameters
accelerationAccelerationComponent to get the confidence from
Returns
double value of the confidence of the acceleration component in m/s^2

Definition at line 516 of file cpm_ts_getters.h.

516 {
517 return double(acceleration.confidence.value) / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
518}

◆ getAccelerationMagnitude()

template<typename AccelerationMagnitude>
double etsi_its_cpm_ts_msgs::access::getAccelerationMagnitude ( const AccelerationMagnitude & acceleration_magnitude)
inline

Get the AccelerationMagnitude value.

Parameters
acceleration_magnitudeto get the AccelerationMagnitude from
Returns
double acceleration magnitude in m/s^2 as decimal number

Definition at line 103 of file cpm_ts_getters.h.

◆ getAccelerationMagnitudeConfidence()

template<typename AccelerationMagnitude>
double etsi_its_cpm_ts_msgs::access::getAccelerationMagnitudeConfidence ( const AccelerationMagnitude & acceleration_magnitude)
inline

Get the AccelerationMagnitude Confidence.

Parameters
acceleration_magnitudeto get the AccelerationMagnitudeConfidence from
Returns
double acceleration magnitude standard deviation in m/s^2 as decimal number

Definition at line 114 of file cpm_ts_getters.h.

◆ getAltitude() [1/2]

double etsi_its_cpm_ts_msgs::access::getAltitude ( const Altitude & altitude)
inline

Get the Altitude value.

Parameters
altitudeto get the Altitude value from
Returns
Altitude value (above the reference ellipsoid surface) in meter as decimal number (0 if unavailable)

Definition at line 71 of file cpm_ts_getters.h.

74 {
75 return getLatitude(cpm.payload.management_container.reference_position.latitude);
76}
double getLatitude(const Latitude &latitude)
Get the Latitude value.

◆ getAltitude() [2/2]

double etsi_its_cpm_ts_msgs::access::getAltitude ( const CollectivePerceptionMessage & cpm)
inline

Get the Altitude value of CPM.

Parameters
cpmCPM to get the Altitude value from
Returns
Altitude value in (above the reference ellipsoid surface) in meter as decimal number

Definition at line 94 of file cpm_ts_getters.h.

94 {
95 return getAltitude(cpm.payload.management_container.reference_position.altitude);
96}
double getAltitude(const Altitude &altitude)
Get the Altitude value.

◆ getCartesianAccelerationConfidenceOfPerceivedObject()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getCartesianAccelerationConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Cartesian Acceleration Confidence Of Perceived Object.

Parameters
objectPerceivedObject to get the Cartesian acceleration from
Returns
std::tuple<double, double, double> the x,y and z standard deviations of the acceleration in m/s^2 The z standard deviation is infinity if the z acceleration is not present.
Exceptions
std::invalid_argumentIf the acceleration is no cartesian acceleration.

Definition at line 562 of file cpm_ts_getters.h.

562 {
563 if (!object.acceleration_is_present) throw std::invalid_argument("No acceleration present in PerceivedObject");
564
565 if (object.acceleration.choice == Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION) {
566 double x_confidence = getAccelerationComponentConfidence(object.acceleration.cartesian_acceleration.x_acceleration);
567 double y_confidence = getAccelerationComponentConfidence(object.acceleration.cartesian_acceleration.y_acceleration);
568 double z_confidence = object.acceleration.cartesian_acceleration.z_acceleration_is_present
569 ? getAccelerationComponentConfidence(object.acceleration.cartesian_acceleration.z_acceleration)
570 : std::numeric_limits<double>::infinity();
571 return std::make_tuple(x_confidence, y_confidence, z_confidence);
572 } else if (object.acceleration.choice == Acceleration3dWithConfidence::CHOICE_POLAR_ACCELERATION) {
573 double magnitude_confidence = getAccelerationMagnitudeConfidence(object.acceleration.polar_acceleration.acceleration_magnitude);
574 double angle_confidence = getCartesianAngleConfidence(object.acceleration.polar_acceleration.acceleration_direction) * M_PI / 180.0 / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to radians
575 double magnitude = getAccelerationMagnitude(object.acceleration.polar_acceleration.acceleration_magnitude);
576 double angle = getCartesianAngle(object.acceleration.polar_acceleration.acceleration_direction) * M_PI / 180.0 / 10.0; // convert to radians
577 double lateral_confidence = magnitude * angle_confidence; // best approximation
578 double x_confidence = magnitude_confidence * cos(angle) * cos(angle)
579 + lateral_confidence * sin(angle) * sin(angle);
580 double y_confidence = magnitude_confidence * sin(angle) * sin(angle)
581 + lateral_confidence * cos(angle) * cos(angle);
582 // neglect xy covariance, as it is not present in the output of this function
583 double z_confidence = object.acceleration.polar_acceleration.z_acceleration_is_present
584 ? getAccelerationComponentConfidence(object.acceleration.polar_acceleration.z_acceleration)
585 : std::numeric_limits<double>::infinity();
586 return std::make_tuple(x_confidence, y_confidence, z_confidence);
587 } else {
588 throw std::invalid_argument("Acceleration is neither Cartesian nor Polar");
589 }
590}
double getAccelerationMagnitude(const AccelerationMagnitude &acceleration_magnitude)
Get the AccelerationMagnitude value.
double getAccelerationMagnitudeConfidence(const AccelerationMagnitude &acceleration_magnitude)
Get the AccelerationMagnitude Confidence.
double getAccelerationComponentConfidence(const AccelerationComponent &acceleration)
Get the confidence of the acceleration component.

◆ getCartesianAccelerationOfPerceivedObject()

gm::Vector3 etsi_its_cpm_ts_msgs::access::getCartesianAccelerationOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Cartesian acceleration of the PerceivedObject.

Parameters
objectPerceivedObject to get the Cartesian acceleration from
Returns
gm::Vector3 Cartesian acceleration of the PerceivedObject in m/s^2 (local coordinate system)
Exceptions
std::invalid_argumentIf the acceleration is no cartesian acceleration.

Definition at line 527 of file cpm_ts_getters.h.

527 {
528 if (!object.acceleration_is_present) {
529 throw std::invalid_argument("No acceleration present in PerceivedObject");
530 }
531 gm::Vector3 acceleration;
532
533 if (object.acceleration.choice == Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION) {
534 acceleration.x = getAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration);
535 acceleration.y = getAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration);
536 if (object.acceleration.cartesian_acceleration.z_acceleration_is_present) {
537 acceleration.z = getAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration);
538 }
539 } else if (object.acceleration.choice == Acceleration3dWithConfidence::CHOICE_POLAR_ACCELERATION) {
540 double magnitude = getAccelerationMagnitude(object.acceleration.polar_acceleration.acceleration_magnitude);
541 double angle = getCartesianAngle(object.acceleration.polar_acceleration.acceleration_direction) * M_PI / 180.0 / 10.0; // convert to radians
542 acceleration.x = magnitude * cos(angle);
543 acceleration.y = magnitude * sin(angle);
544 if (object.acceleration.polar_acceleration.z_acceleration_is_present) {
545 acceleration.z = getAccelerationComponent(object.acceleration.polar_acceleration.z_acceleration);
546 }
547 } else {
548 throw std::invalid_argument("Acceleration is neither Cartesian nor Polar");
549 }
550
551 return acceleration;
552}
double getAccelerationMagnitude(const AccelerationMagnitude &acceleration_magnitude)
Get the AccelerationMagnitude value.
uint16_t getCartesianAngle(const CartesianAngle &angle)
Get the Cartesian angle of the PerceivedObject.
double getAccelerationComponent(const AccelerationComponent &acceleration)
Get the acceleration component of the PerceivedObject.

◆ getCartesianAngle()

uint16_t etsi_its_cpm_ts_msgs::access::getCartesianAngle ( const CartesianAngle & angle)
inline

Get the Cartesian angle of the PerceivedObject.

Parameters
objectPerceivedObject to get the Cartesian angle from
Returns
unit16_t Cartesian angle of the PerceivedObject in 0,1 degrees

Definition at line 291 of file cpm_ts_getters.h.

291{ return angle.value.value; }

◆ getCartesianAngleConfidence()

uint8_t etsi_its_cpm_ts_msgs::access::getCartesianAngleConfidence ( const CartesianAngle & angle)
inline

Get the confidence of the Cartesian angle.

Parameters
angleCartesianAngle to get the confidence from
Returns
uint8_t confidence of the Cartesian angle in 0,1 degrees

Definition at line 299 of file cpm_ts_getters.h.

299{ return angle.confidence.value; }

◆ getCartesianCoordinate()

int32_t etsi_its_cpm_ts_msgs::access::getCartesianCoordinate ( const CartesianCoordinateWithConfidence & coordinate)
inline

Retrieves the Cartesian coordinate value from a CartesianCoordinateWithConfidence object.

Parameters
coordinateThe CartesianCoordinateWithConfidence object from which to retrieve the value.
Returns
The Cartesian coordinate value in centimeters.

Definition at line 239 of file cpm_ts_getters.h.

239 {
240 return coordinate.value.value;
241}

◆ getCartesianCoordinateConfidence()

uint16_t etsi_its_cpm_ts_msgs::access::getCartesianCoordinateConfidence ( const CartesianCoordinateWithConfidence & coordinate)
inline

Retrieves the confidence value from a CartesianCoordinateWithConfidence object.

Parameters
coordinateThe CartesianCoordinateWithConfidence object from which to retrieve the confidence value.
Returns
The confidence value of the CartesianCoordinateWithConfidence object in centimeters.

Definition at line 249 of file cpm_ts_getters.h.

249 {
250 return coordinate.confidence.value;
251}

◆ getCartesianVelocityConfidenceOfPerceivedObject()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getCartesianVelocityConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Cartesian Velocity Confidence Of Perceived Object object.

Parameters
objectPerceivedObject to get the Cartesian velocity from
Returns
std::tuple<double, double, double> the x,y and z standard deviations of the velocity in m/s The z standard deviation is infinity if the z velocity is not present.
Exceptions
std::invalid_argumentIf the velocity is no cartesian velocity.

Definition at line 468 of file cpm_ts_getters.h.

468 {
469 if (!object.velocity_is_present) {
470 throw std::invalid_argument("No velocity present in PerceivedObject");
471 }
472 if (object.velocity.choice == Velocity3dWithConfidence::CHOICE_POLAR_VELOCITY) {
473 double speed_confidence = getSpeedConfidence(object.velocity.polar_velocity.velocity_magnitude);
474 double angle_confidence = getCartesianAngleConfidence(object.velocity.polar_velocity.velocity_direction) * M_PI / 180.0 / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to radians
475 double speed = getSpeed(object.velocity.polar_velocity.velocity_magnitude);
476 double angle = getCartesianAngle(object.velocity.polar_velocity.velocity_direction) * M_PI / 180.0 / 10.0; // convert to radians
477 double lateral_confidence = speed * angle_confidence; // not exactly, but best approximation
478 double x_confidence = speed_confidence * cos(angle) * cos(angle)
479 + lateral_confidence * sin(angle) * sin(angle);
480 double y_confidence = speed_confidence * sin(angle) * sin(angle)
481 + lateral_confidence * cos(angle) * cos(angle);
482 // neglect xy covariance, as it is not present in the output of this function
483 double z_confidence = object.velocity.polar_velocity.z_velocity_is_present
484 ? getVelocityComponentConfidence(object.velocity.polar_velocity.z_velocity)
485 : std::numeric_limits<double>::infinity();
486 return std::make_tuple(x_confidence, y_confidence, z_confidence);
487 } else if (object.velocity.choice == Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY) {
488 double x_confidence = getVelocityComponentConfidence(object.velocity.cartesian_velocity.x_velocity);
489 double y_confidence = getVelocityComponentConfidence(object.velocity.cartesian_velocity.y_velocity);
490 double z_confidence = object.velocity.cartesian_velocity.z_velocity_is_present
491 ? getVelocityComponentConfidence(object.velocity.cartesian_velocity.z_velocity)
492 : std::numeric_limits<double>::infinity();
493 return std::make_tuple(x_confidence, y_confidence, z_confidence);
494 } else {
495 throw std::invalid_argument("Velocity is neither Polar nor Cartesian");
496 }
497
498}
double getSpeed(const CAM &cam)
Get the vehicle speed.
double getSpeedConfidence(const CAM &cam)
Get the Speed Confidence.

◆ getCartesianVelocityOfPerceivedObject()

gm::Vector3 etsi_its_cpm_ts_msgs::access::getCartesianVelocityOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Cartesian velocity of the PerceivedObject.

Parameters
objectPerceivedObject to get the Cartesian velocity from
Returns
gm::Vector3 Cartesian velocity of the PerceivedObject in m/s (local coordinate system)
Exceptions
std::invalid_argumentIf the velocity is no cartesian velocity.

Definition at line 435 of file cpm_ts_getters.h.

435 {
436 if (!object.velocity_is_present) {
437 throw std::invalid_argument("No velocity present in PerceivedObject");
438 }
439 gm::Vector3 velocity;
440 if (object.velocity.choice == Velocity3dWithConfidence::CHOICE_POLAR_VELOCITY) {
441 double speed = getSpeed(object.velocity.polar_velocity.velocity_magnitude);
442 double angle = getCartesianAngle(object.velocity.polar_velocity.velocity_direction) * M_PI / 180.0 / 10.0; // convert to radians
443 velocity.x = speed * cos(angle);
444 velocity.y = speed * sin(angle);
445 if (object.velocity.polar_velocity.z_velocity_is_present) {
446 velocity.z = getVelocityComponent(object.velocity.polar_velocity.z_velocity);
447 }
448 } else if (object.velocity.choice == Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY) {
449 velocity.x = getVelocityComponent(object.velocity.cartesian_velocity.x_velocity);
450 velocity.y = getVelocityComponent(object.velocity.cartesian_velocity.y_velocity);
451 if (object.velocity.cartesian_velocity.z_velocity_is_present) {
452 velocity.z = getVelocityComponent(object.velocity.cartesian_velocity.z_velocity);
453 }
454 } else {
455 throw std::invalid_argument("Velocity is neither Polar nor Cartesian");
456 }
457 return velocity;
458}
double getVelocityComponent(const VelocityComponent &velocity)
Get the velocity component of the PerceivedObject.

◆ getCpmContainer()

WrappedCpmContainer etsi_its_cpm_ts_msgs::access::getCpmContainer ( const CollectivePerceptionMessage & cpm,
const uint8_t container_id )
inline

Retrieves the CpmContainer with the specified container ID from the CPM.

Parameters
cpmThe CPM from which to retrieve the CpmContainer.
container_idThe ID of the CpmContainer to retrieve.
Returns
The CpmContainer with the specified container ID.
Exceptions
std::invalid_argumentif no CpmContainer with the specified ID is found in the CPM.

Definition at line 153 of file cpm_ts_getters.h.

153 {
154 for (int i = 0; i < cpm.payload.cpm_containers.value.array.size(); i++) {
155 if (cpm.payload.cpm_containers.value.array[i].container_id.value == container_id) {
156 return cpm.payload.cpm_containers.value.array[i];
157 }
158 }
159 throw std::invalid_argument("No Container with ID " + std::to_string(container_id) + " found in CPM");
160}

◆ getCpmContainerIds()

std::vector< uint8_t > etsi_its_cpm_ts_msgs::access::getCpmContainerIds ( const CollectivePerceptionMessage & cpm)
inline

Retrieves the container IDs from a CPM.

This function iterates over the cpm_containers array in the given CPM and extracts the container IDs into a vector of uint8_t.

Parameters
cpmThe CPM from which to retrieve the container IDs.
Returns
A vector containing the container IDs.

Definition at line 137 of file cpm_ts_getters.h.

137 {
138 std::vector<uint8_t> container_ids;
139 for (int i = 0; i < cpm.payload.cpm_containers.value.array.size(); i++) {
140 container_ids.push_back(cpm.payload.cpm_containers.value.array[i].container_id.value);
141 }
142 return container_ids;
143}

◆ getDimensionsConfidenceOfPerceivedObject()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getDimensionsConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Dimensions Confidence Of Perceived Object.

Parameters
objectThe PerceivedObject to get the dimensions confidence from
Returns
std::tuple<double, double, double> the x,y and z standard deviations of the dimensions in meters

Definition at line 699 of file cpm_ts_getters.h.

699 {
700 double conf_x = double(getXDimensionConfidenceOfPerceivedObject(object)) / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
701 double conf_y = double(getYDimensionConfidenceOfPerceivedObject(object)) / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
702 double conf_z = double(getZDimensionConfidenceOfPerceivedObject(object)) / 10.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
703 return {conf_x, conf_y, conf_z};
704}
uint8_t getYDimensionConfidenceOfPerceivedObject(const PerceivedObject &object)
Gets the confidence of the y-dimension of a perceived object.
uint8_t getZDimensionConfidenceOfPerceivedObject(const PerceivedObject &object)
Gets the confidence of the z-dimension of a perceived object.
uint8_t getXDimensionConfidenceOfPerceivedObject(const PerceivedObject &object)
Gets the confidence of the x-dimension of a perceived object.

◆ getDimensionsOfPerceivedObject()

gm::Vector3 etsi_its_cpm_ts_msgs::access::getDimensionsOfPerceivedObject ( const PerceivedObject & object)
inline

Retrieves the dimensions of a perceived object.

This function extracts the dimensions of a perceived object from the given PerceivedObject. The dimensions are returned as a gm::Vector3 object with the x, y, and z dimensions in meters.

Parameters
objectThe PerceivedObject for which to calculate the dimensions.
Returns
The dimensions of the perceived object as a gm::Vector3 object in meters.

Definition at line 685 of file cpm_ts_getters.h.

685 {
686 gm::Vector3 dimensions;
687 dimensions.x = double(getXDimensionOfPerceivedObject(object)) / 10.0;
688 dimensions.y = double(getYDimensionOfPerceivedObject(object)) / 10.0;
689 dimensions.z = double(getZDimensionOfPerceivedObject(object)) / 10.0;
690 return dimensions;
691}
uint16_t getZDimensionOfPerceivedObject(const PerceivedObject &object)
Retrieves the z-dimension of a perceived object.
uint16_t getYDimensionOfPerceivedObject(const PerceivedObject &object)
Retrieves the y-dimension of a perceived object.
uint16_t getXDimensionOfPerceivedObject(const PerceivedObject &object)
Gets the x-dimension of a perceived object.

◆ getHeadingCDD()

template<typename Heading>
double etsi_its_cpm_ts_msgs::access::getHeadingCDD ( const Heading & heading)
inline

Get the Heading value.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West

Parameters
headingto get the Heading value from
Returns
Heading value in degree as decimal number

Definition at line 159 of file cpm_ts_getters.h.

◆ getHeadingConfidenceCDD()

template<typename Heading>
double etsi_its_cpm_ts_msgs::access::getHeadingConfidenceCDD ( const Heading & heading)
inline

Get the Heading value.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West

Parameters
headingto get the Heading standard deviation from
Returns
Heading standard deviation in degree as decimal number

Definition at line 170 of file cpm_ts_getters.h.

170{

◆ getIdOfPerceivedObject()

uint16_t etsi_its_cpm_ts_msgs::access::getIdOfPerceivedObject ( const PerceivedObject & object)
inline

Retrieves the ID of a perceived object.

This function takes a PerceivedObject as input and returns the ID of the object.

Parameters
objectThe PerceivedObject for which to retrieve the ID.
Returns
The ID of the perceived object.

Definition at line 226 of file cpm_ts_getters.h.

226 {
227 if (!object.object_id_is_present) {
228 throw std::invalid_argument("No object_id present in PerceivedObject");
229 }
230 return object.object_id.value;
231}

◆ getLateralAcceleration()

double etsi_its_cpm_ts_msgs::access::getLateralAcceleration ( const AccelerationComponent & lateral_acceleration)
inline

Get the lateral acceleration.

Parameters
lateralAccelerationto get the lateral acceleration from
Returns
lateral acceleration in m/s^2 as decimal number (left is positive)

Definition at line 65 of file cpm_ts_getters.h.

66 { return getReferenceTime(cpm).value; }
67
TimestampIts getReferenceTime(const CollectivePerceptionMessage &cpm)
Get the Reference Time object.

◆ getLateralAccelerationConfidence()

double etsi_its_cpm_ts_msgs::access::getLateralAccelerationConfidence ( const AccelerationComponent & lateral_acceleration)
inline

Get the Lateral Acceleration Confidence.

Parameters
lateral_accelerationto get the LateralAccelerationConfidence from
Returns
double standard deviation of the lateral acceleration in m/s^2 as decimal number

Definition at line 75 of file cpm_ts_getters.h.

◆ getLatitude() [1/2]

double etsi_its_cpm_ts_msgs::access::getLatitude ( const CollectivePerceptionMessage & cpm)
inline

Get the Latitude value of CPM.

Parameters
cpmCPM to get the Latitude value from
Returns
Latitude value in degree as decimal number

Definition at line 74 of file cpm_ts_getters.h.

74 {
75 return getLatitude(cpm.payload.management_container.reference_position.latitude);
76}

◆ getLatitude() [2/2]

double etsi_its_cpm_ts_msgs::access::getLatitude ( const Latitude & latitude)
inline

Get the Latitude value.

Parameters
latitudeto get the Latitude value from
Returns
Latitude value in degree as decimal number

Definition at line 55 of file cpm_ts_getters.h.

◆ getLongitude() [1/2]

double etsi_its_cpm_ts_msgs::access::getLongitude ( const CollectivePerceptionMessage & cpm)
inline

Get the Longitude value of CPM.

Parameters
cpmCPM to get the Longitude value from
Returns
Longitude value in degree as decimal number

Definition at line 84 of file cpm_ts_getters.h.

84 {
85 return getLongitude(cpm.payload.management_container.reference_position.longitude);
86}
double getLongitude(const Longitude &longitude)
Get the Longitude value.

◆ getLongitude() [2/2]

double etsi_its_cpm_ts_msgs::access::getLongitude ( const Longitude & longitude)
inline

Get the Longitude value.

Parameters
longitudeto get the Longitude value from
Returns
Longitude value in degree as decimal number

Definition at line 63 of file cpm_ts_getters.h.

◆ getLongitudinalAcceleration()

double etsi_its_cpm_ts_msgs::access::getLongitudinalAcceleration ( const AccelerationComponent & longitudinal_acceleration)
inline

Get the longitudinal acceleration.

Parameters
longitudinalAccelerationto get the longitudinal acceleration from
Returns
longitudinal acceleration in m/s^2 as decimal number (left is positive)

Definition at line 45 of file cpm_ts_getters.h.

◆ getLongitudinalAccelerationConfidence()

double etsi_its_cpm_ts_msgs::access::getLongitudinalAccelerationConfidence ( const AccelerationComponent & longitudinal_acceleration)
inline

Get the Longitudinal Acceleration Confidence.

Parameters
longitudinal_accelerationto get the LongitudinalAccelerationConfidence from
Returns
double standard deviation of the longitudinal acceleration in m/s^2 as decimal number

Definition at line 55 of file cpm_ts_getters.h.

56 {
57 return cpm.payload.management_container.reference_time;

◆ getNumberOfPerceivedObjects() [1/2]

uint8_t etsi_its_cpm_ts_msgs::access::getNumberOfPerceivedObjects ( const CollectivePerceptionMessage & cpm)
inline

Retrieves the number of perceived objects from the given CPM.

Parameters
cpmThe CPM from which to retrieve the number of perceived objects.
Returns
The number of perceived objects.

Definition at line 195 of file cpm_ts_getters.h.

195 {
197}
uint8_t getNumberOfPerceivedObjects(const WrappedCpmContainer &container)
WrappedCpmContainer getPerceivedObjectContainer(const CollectivePerceptionMessage &cpm)
Retrieves the perceived object container from a CPM.

◆ getNumberOfPerceivedObjects() [2/2]

uint8_t etsi_its_cpm_ts_msgs::access::getNumberOfPerceivedObjects ( const WrappedCpmContainer & container)
inline

Retrieves the number of perceived objects from the given perceived object container.

Parameters
containerThe perceived object container to retrieve the number of perceived objects from.
Returns
The number of perceived objects.
Exceptions
std::invalid_argumentif the container is not a PerceivedObjectContainer.

Definition at line 181 of file cpm_ts_getters.h.

181 {
182 if (container.container_id.value != WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
183 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
184 }
185 uint8_t number = container.container_data_perceived_object_container.number_of_perceived_objects.value;
186 return number;
187}

◆ getOrientationOfPerceivedObject()

gm::Quaternion etsi_its_cpm_ts_msgs::access::getOrientationOfPerceivedObject ( const PerceivedObject & object)
inline

Calculates the orientation of a perceived object.

This function calculates the orientation of a perceived object based on the angles provided in the PerceivedObject structure. The angles are converted to radians and used to set the roll, pitch, and yaw values of a tf2::Quaternion object. The resulting quaternion is then converted to a gm::Quaternion message and returned.

Parameters
objectThe PerceivedObject structure containing the angles of the perceived object.
Returns
gm::Quaternion The orientation of the perceived object in radians from -pi to pi.

Definition at line 311 of file cpm_ts_getters.h.

311 {
312 if (!object.angles_is_present) throw std::invalid_argument("No angles present in PerceivedObject");
313 tf2::Quaternion q;
314 double roll{0}, pitch{0}, yaw{0};
315
316 if (object.angles.x_angle_is_present) {
317 roll = (((double(getCartesianAngle(object.angles.x_angle)) / 10.0) ) / 180.0) *
318 M_PI;
319 }
320 if (object.angles.y_angle_is_present) {
321 pitch = (((double(getCartesianAngle(object.angles.y_angle)) / 10.0) ) / 180.0) *
322 M_PI;
323 }
324 yaw = (((double(getCartesianAngle(object.angles.z_angle)) / 10.0)) / 180.0) *
325 M_PI;
326 // This wraps from -pi ti pi because setRPY only uses cos and sin of the angles
327 q.setRPY(roll, pitch, yaw);
328
329 return tf2::toMsg(q);
330}

◆ getPerceivedObject()

PerceivedObject etsi_its_cpm_ts_msgs::access::getPerceivedObject ( const WrappedCpmContainer & container,
const uint8_t i )
inline

Retrieves the PerceivedObject at the specified index from the given WrappedCpmContainer.

Parameters
containerThe WrappedCpmContainer from which to retrieve the PerceivedObject (should be a PerceivedObjectContainer).
iThe index of the PerceivedObject to retrieve.
Returns
The PerceivedObject at the specified index.
Exceptions
std::invalid_argumentif the index is out of range.

Definition at line 211 of file cpm_ts_getters.h.

211 {
212 if (i >= getNumberOfPerceivedObjects(container)) {
213 throw std::invalid_argument("Index out of range");
214 }
215 return container.container_data_perceived_object_container.perceived_objects.array[i];
216}

◆ getPerceivedObjectContainer()

WrappedCpmContainer etsi_its_cpm_ts_msgs::access::getPerceivedObjectContainer ( const CollectivePerceptionMessage & cpm)
inline

Retrieves the perceived object container from a CPM.

This function returns the perceived object container from the given CPM.

Parameters
cpmThe CPM from which to retrieve the perceived object container.
Returns
The perceived object container.

Definition at line 170 of file cpm_ts_getters.h.

170 {
171 return getCpmContainer(cpm, WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER);
172}
WrappedCpmContainer getCpmContainer(const CollectivePerceptionMessage &cpm, const uint8_t container_id)

◆ getPosConfidenceEllipse() [1/2]

template<typename PosConfidenceEllipse>
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPosConfidenceEllipse ( const PosConfidenceEllipse & position_confidence_ellipse)
inline

Extract major axis length, minor axis length and orientation from the given position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to extract the values from
Returns
std::tuple<double, double, double> major axis length in meters, minor axis length in meters, and orientation in degrees

Definition at line 225 of file cpm_ts_getters.h.

226 {
227 if (!object.object_id_is_present) {
228 throw std::invalid_argument("No object_id present in PerceivedObject");
229 }
230 return object.object_id.value;
231}

◆ getPosConfidenceEllipse() [2/2]

template<typename PosConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getPosConfidenceEllipse ( const PosConfidenceEllipse & position_confidence_ellipse,
const double object_heading )
inline

Get the covariance matrix of the position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to get the covariance matrix from
object_headingThe object heading in radians
Returns
std::array<double, 4> The covariance matrix of the position confidence ellipse in vehicle coordinates (x = longitudinal, y = lateral)

Definition at line 286 of file cpm_ts_getters.h.

◆ getPoseOfPerceivedObject()

gm::Pose etsi_its_cpm_ts_msgs::access::getPoseOfPerceivedObject ( const PerceivedObject & object)
inline

Get the pose of the PerceivedObject.

Parameters
objectPerceivedObject to get the pose from
Returns
gm::Pose pose of the PerceivedObject (position in m, orientation in rad)

Definition at line 366 of file cpm_ts_getters.h.

366 {
367 gm::Pose pose;
368 pose.position = getPositionOfPerceivedObject(object);
369 pose.orientation = getOrientationOfPerceivedObject(object);
370 return pose;
371}
gm::Point getPositionOfPerceivedObject(const PerceivedObject &object)
gm::Quaternion getOrientationOfPerceivedObject(const PerceivedObject &object)
Calculates the orientation of a perceived object.

◆ getPositionConfidenceEllipse() [1/2]

template<typename PositionConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getPositionConfidenceEllipse ( const PositionConfidenceEllipse & position_confidence_ellipse,
const double object_heading )
inline

Get the covariance matrix of the position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to get the covariance matrix from
object_headingThe object heading in radians
Returns
std::array<double, 4> The covariance matrix of the position confidence ellipse in vehicle coordinates (x = longitudinal, y = lateral)

Definition at line 103 of file cpm_ts_getters.h.

◆ getPositionConfidenceEllipse() [2/2]

template<typename PositionConfidenceEllipse>
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPositionConfidenceEllipse ( PositionConfidenceEllipse & position_confidence_ellipse)
inline

Extract major axis length, minor axis length and orientation from the given position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to extract the values from
Returns
std::tuple<double, double, double> major axis length in meters, minor axis length in meters, and orientation in degrees

Definition at line 87 of file cpm_ts_getters.h.

◆ getPositionConfidenceOfPerceivedObject()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::getPositionConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Position Confidences Of Perceived Object.

Parameters
objectThe PerceivedObject to get the position confidences from
Returns
std::tuple<double, double, double> x,y and z standard deviations of the positions in meters. The z standard deviation is infinity if the z coordinate is not present.

Definition at line 276 of file cpm_ts_getters.h.

276 {
277 double x_confidence = double(getCartesianCoordinateConfidence(object.position.x_coordinate)) / 100.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
278 double y_confidence = double(getCartesianCoordinateConfidence(object.position.y_coordinate)) / 100.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
279 double z_confidence = object.position.z_coordinate_is_present
280 ? double(getCartesianCoordinateConfidence(object.position.z_coordinate)) / 100.0 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR
281 : std::numeric_limits<double>::infinity();
282 return std::make_tuple(x_confidence, y_confidence, z_confidence);
283}
uint16_t getCartesianCoordinateConfidence(const CartesianCoordinateWithConfidence &coordinate)
Retrieves the confidence value from a CartesianCoordinateWithConfidence object.

◆ getPositionOfPerceivedObject()

gm::Point etsi_its_cpm_ts_msgs::access::getPositionOfPerceivedObject ( const PerceivedObject & object)
inline

Returns the position of a perceived object.

Parameters
objectThe perceived object.
Returns
The position of the perceived object as a gm::Point (all values in meters).

Definition at line 259 of file cpm_ts_getters.h.

259 {
260 gm::Point point;
261 point.x = double(getCartesianCoordinate(object.position.x_coordinate)) / 100.0;
262 point.y = double(getCartesianCoordinate(object.position.y_coordinate)) / 100.0;
263 if (object.position.z_coordinate_is_present) {
264 point.z = double(getCartesianCoordinate(object.position.z_coordinate)) / 100.0;
265 }
266 return point;
267}
int32_t getCartesianCoordinate(const CartesianCoordinateWithConfidence &coordinate)
Retrieves the Cartesian coordinate value from a CartesianCoordinateWithConfidence object.

◆ getReferenceTime()

TimestampIts etsi_its_cpm_ts_msgs::access::getReferenceTime ( const CollectivePerceptionMessage & cpm)
inline

Get the Reference Time object.

Parameters
cpmCPM to get the ReferenceTime-Value from
Returns
TimestampIts

Definition at line 56 of file cpm_ts_getters.h.

56 {
57 return cpm.payload.management_container.reference_time;
58}

◆ getReferenceTimeValue()

uint64_t etsi_its_cpm_ts_msgs::access::getReferenceTimeValue ( const CollectivePerceptionMessage & cpm)
inline

Get the ReferenceTime-Value.

Parameters
cpmCPM to get the ReferenceTime-Value from
Returns
uint64_t the ReferenceTime-Value in milliseconds

Definition at line 66 of file cpm_ts_getters.h.

66{ return getReferenceTime(cpm).value; }

◆ getSemiAxis()

template<typename SemiAxisLength>
double etsi_its_cpm_ts_msgs::access::getSemiAxis ( const SemiAxisLength & semi_axis_length)
inline

Get the Semi Axis object.

Parameters
semi_axis_lengthThe SemiAxisLength object to get the semi axis from
Returns
double the semi axis length in meters

Definition at line 214 of file cpm_ts_getters.h.

◆ getSensorID()

uint8_t etsi_its_cpm_ts_msgs::access::getSensorID ( const SensorInformation & sensor_information)
inline

Get the sensorId of a SensorInformation object.

Parameters
sensor_informationThe SensorInformation to get the sensorId from
Returns
uint8_t The sensorId of a SensorInformation object

Definition at line 749 of file cpm_ts_getters.h.

749 {
750 return sensor_information.sensor_id.value;
751}

◆ getSensorType()

uint8_t etsi_its_cpm_ts_msgs::access::getSensorType ( const SensorInformation & sensor_information)
inline

Get the sensorType of a SensorInformation object.

Parameters
sensor_informationThe SensorInformation to get the sensorType from
Returns
uint8_t The sensorType of a SensorInformation object

Definition at line 759 of file cpm_ts_getters.h.

759 {
760 return sensor_information.sensor_type.value;
761}

◆ getSpeed()

double etsi_its_cpm_ts_msgs::access::getSpeed ( const Speed & speed)
inline

Get the vehicle speed.

Parameters
speedto get the speed value from
Returns
speed value in m/s as decimal number

Definition at line 84 of file cpm_ts_getters.h.

84{

◆ getSpeedConfidence()

double etsi_its_cpm_ts_msgs::access::getSpeedConfidence ( const Speed & speed)
inline

Get the Speed Confidence.

Parameters
speedto get the SpeedConfidence from
Returns
double speed standard deviation in m/s as decimal number

Definition at line 92 of file cpm_ts_getters.h.

94 {

◆ getStationID() [1/2]

uint32_t etsi_its_cpm_ts_msgs::access::getStationID ( const CollectivePerceptionMessage & cpm)
inline

Retrieves the station ID from the given CPM.

This function extracts the station ID from the header of the provided CPM.

Parameters
cpmThe CPM from which to retrieve the station ID.
Returns
The station ID extracted from the header of the CPM.

Definition at line 48 of file cpm_ts_getters.h.

48{ return getStationID(cpm.header); }
uint32_t getStationID(const ItsPduHeader &header)
Get the StationID of ItsPduHeader.

◆ getStationID() [2/2]

uint32_t etsi_its_cpm_ts_msgs::access::getStationID ( const ItsPduHeader & header)
inline

Get the StationID of ItsPduHeader.

Parameters
headerItsPduHeader to get the StationID value from
Returns
stationID value

Definition at line 47 of file cpm_ts_getters.h.

◆ getUTMPosition() [1/3]

gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition ( const CollectivePerceptionMessage & cpm)
inline

Get the UTM Position defined within the ManagementContainer of the CPM.

The position is transformed into UTM by using GeographicLib::UTMUPS The altitude value is directly used as z-Coordinate

Parameters
cpmCPM from which to extract the UTM position.
Returns
geometry_msgs::PointStamped of the given position with the UTM zone and hemisphere as frame_id

Definition at line 122 of file cpm_ts_getters.h.

122 {
123 int zone;
124 bool northp;
125 return getUTMPosition(cpm, zone, northp);
126}
gm::PointStamped getUTMPosition(const T &reference_position, int &zone, bool &northp)
Get the UTM Position defined by the given ReferencePosition.

◆ getUTMPosition() [2/3]

gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition ( const CollectivePerceptionMessage & cpm,
int & zone,
bool & northp )
inline

Get the UTM Position defined within the ManagementContainer of the CPM.

The position is transformed into UTM by using GeographicLib::UTMUPS The altitude value is directly used as z-Coordinate

Parameters
[in]cpmCPM to get the UTM Position from
[out]zonethe UTM zone (zero means UPS)
[out]northphemisphere (true means north, false means south)
Returns
geometry_msgs::PointStamped of the given position with the UTM zone and hemisphere as frame_id

Definition at line 109 of file cpm_ts_getters.h.

109 {
110 return getUTMPosition(cpm.payload.management_container.reference_position, zone, northp);
111}

◆ getUTMPosition() [3/3]

template<typename T>
gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPosition ( const T & reference_position,
int & zone,
bool & northp )
inline

Get the UTM Position defined by the given ReferencePosition.

The position is transformed into UTM by using GeographicLib::UTMUPS The altitude value is directly used as z-Coordinate

Parameters
[in]reference_positionReferencePosition or ReferencePositionWithConfidence to get the UTM Position from
[out]zonethe UTM zone (zero means UPS)
[out]northphemisphere (true means north, false means south)
Returns
gm::PointStamped geometry_msgs::PointStamped of the given position

Definition at line 130 of file cpm_ts_getters.h.

137 {
138 std::vector<uint8_t> container_ids;
139 for (int i = 0; i < cpm.payload.cpm_containers.value.array.size(); i++) {
140 container_ids.push_back(cpm.payload.cpm_containers.value.array[i].container_id.value);
141 }
142 return container_ids;
143}
144

◆ getUTMPositionOfPerceivedObject()

gm::PointStamped etsi_its_cpm_ts_msgs::access::getUTMPositionOfPerceivedObject ( const CollectivePerceptionMessage & cpm,
const PerceivedObject & object )
inline

Calculates the UTM position of a perceived object based on the CPMs referencep position.

This function takes a CPM and a PerceivedObject as input parameters and calculates the UTM position of the object. The UTM position is calculated by adding the relative position of the object to the UTM position of the reference point in the CPM.

Parameters
cpmThe Collective Perception Message (CPM) containing the reference position.
objectThe PerceivedObject for which the UTM position needs to be calculated.
Returns
The UTM position of the perceived object.

Definition at line 716 of file cpm_ts_getters.h.

◆ getVelocityComponent()

double etsi_its_cpm_ts_msgs::access::getVelocityComponent ( const VelocityComponent & velocity)
inline

Get the velocity component of the PerceivedObject.

Parameters
velocityVelocityComponent to get the value from
Returns
double value of the velocity component in m/s

Definition at line 416 of file cpm_ts_getters.h.

◆ getVelocityComponentConfidence()

double etsi_its_cpm_ts_msgs::access::getVelocityComponentConfidence ( const VelocityComponent & velocity)
inline

Get the confidence of the velocity component.

Parameters
velocityVelocityComponent to get the confidence from
Returns
double value of the confidence of the velocity component in m/s

Definition at line 424 of file cpm_ts_getters.h.

◆ getWGSPosConfidenceEllipse()

template<typename PosConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSPosConfidenceEllipse ( const PosConfidenceEllipse & position_confidence_ellipse)
inline

Get the covariance matrix of the position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to get the covariance matrix from
object_headingThe object heading in radians
Returns
std::array<double, 4> The covariance matrix of the position confidence ellipse in WGS coordinates (x = North, y = East)

Definition at line 299 of file cpm_ts_getters.h.

◆ getWGSPositionConfidenceEllipse()

template<typename PositionConfidenceEllipse>
std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSPositionConfidenceEllipse ( const PositionConfidenceEllipse & position_confidence_ellipse)
inline

Get the covariance matrix of the position confidence ellipse.

Parameters
position_confidence_ellipseThe position confidence ellipse to get the covariance matrix from
object_headingThe object heading in radians
Returns
std::array<double, 4> The covariance matrix of the position confidence ellipse in WGS coordinates (x = North, y = East)

Definition at line 116 of file cpm_ts_getters.h.

◆ getWGSRefPosConfidence()

const std::array< double, 4 > etsi_its_cpm_ts_msgs::access::getWGSRefPosConfidence ( const CollectivePerceptionMessage & cpm)
inline

Get the confidence ellipse of the reference position as Covariance matrix.

The covariance matrix will have the entries cov_xx, cov_xy, cov_yx, cov_yy where x is WGS84 North and y is East

Parameters
cpmThe CPM message to get the reference position from
Returns
const std::array<double, 4> the covariance matrix, as specified above

Definition at line 739 of file cpm_ts_getters.h.

◆ getXDimensionConfidenceOfPerceivedObject()

uint8_t etsi_its_cpm_ts_msgs::access::getXDimensionConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Gets the confidence of the x-dimension of a perceived object.

Parameters
objectThe PerceivedObject from which to retrieve the x-dimension confidence.
Returns
uint8_t The confidence of the x-dimension of the perceived object in decimeters.
Exceptions
std::invalid_argumentif the x-dimension is not present in the PerceivedObject.

Definition at line 615 of file cpm_ts_getters.h.

◆ getXDimensionOfPerceivedObject()

uint16_t etsi_its_cpm_ts_msgs::access::getXDimensionOfPerceivedObject ( const PerceivedObject & object)
inline

Gets the x-dimension of a perceived object.

This function extracts the x-dimension from a given PerceivedObject. If the x-dimension is not present in the object, it throws an std::invalid_argument exception.

Parameters
objectThe PerceivedObject from which to retrieve the x-dimension.
Returns
The x-dimension of the perceived object in decimeters.
Exceptions
std::invalid_argumentif the x-dimension is not present in the PerceivedObject.

Definition at line 603 of file cpm_ts_getters.h.

◆ getYawConfidenceOfPerceivedObject()

double etsi_its_cpm_ts_msgs::access::getYawConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Yaw Confidence Of Perceived Object object.

Parameters
objectPerceivedObject to get the yaw confidence from
Returns
double The standard deviation of the yaw angle in radians
Exceptions
std::invalid_argumentIf the angles are not present in the object.

Definition at line 353 of file cpm_ts_getters.h.

◆ getYawOfPerceivedObject()

double etsi_its_cpm_ts_msgs::access::getYawOfPerceivedObject ( const PerceivedObject & object)
inline

Get the yaw of the PerceivedObject.

Parameters
objectPerceivedObject to get the yaw from
Returns
double yaw of the PerceivedObject in radians from -pi to pi

Definition at line 338 of file cpm_ts_getters.h.

◆ getYawRateCDD()

template<typename YawRate>
double etsi_its_cpm_ts_msgs::access::getYawRateCDD ( const YawRate & yaw_rate)
inline

Get the Yaw Rate value.

Parameters
yaw_rateThe YawRate object to get the yaw rate from
Returns
double The yaw rate in degrees per second

Definition at line 179 of file cpm_ts_getters.h.

◆ getYawRateConfidenceCDD()

template<typename YawRate, typename YawRateConfidence = decltype(YawRate::yaw_rate_confidence)>
double etsi_its_cpm_ts_msgs::access::getYawRateConfidenceCDD ( const YawRate & yaw_rate)
inline

Get the Yaw Rate Confidence.

Parameters
yaw_rateThe YawRate object to get the yaw rate confidence from
Returns
double The yaw rate standard deviation in degrees per second

Definition at line 190 of file cpm_ts_getters.h.

202

◆ getYawRateConfidenceOfPerceivedObject()

double etsi_its_cpm_ts_msgs::access::getYawRateConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Get the Yaw Rate Confidence Of Perceived Object.

Parameters
objectThe PerceivedObject to get the yaw rate confidence from
Returns
double The standard deviation of the yaw rate in rad/s As defined in the TS, this is rounded up to the next possible value
Exceptions
std::invalid_argumentIf the yaw rate is not present in the object.

Definition at line 394 of file cpm_ts_getters.h.

◆ getYawRateOfPerceivedObject()

double etsi_its_cpm_ts_msgs::access::getYawRateOfPerceivedObject ( const PerceivedObject & object)
inline

Get the yaw rate of the PerceivedObject.

Parameters
objectPerceivedObject to get the yaw rate from
Returns
double yaw rate of the PerceivedObject in rad/s
Exceptions
std::invalid_argumentIf the yaw rate is not present in the object.

Definition at line 380 of file cpm_ts_getters.h.

◆ getYDimensionConfidenceOfPerceivedObject()

uint8_t etsi_its_cpm_ts_msgs::access::getYDimensionConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Gets the confidence of the y-dimension of a perceived object.

Parameters
objectThe PerceivedObject from which to retrieve the y-dimension confidence.
Returns
uint8_t The confidence of the y-dimension of the perceived object in decimeters.
Exceptions
std::invalid_argumentif the y-dimension is not present in the PerceivedObject.

Definition at line 643 of file cpm_ts_getters.h.

◆ getYDimensionOfPerceivedObject()

uint16_t etsi_its_cpm_ts_msgs::access::getYDimensionOfPerceivedObject ( const PerceivedObject & object)
inline

Retrieves the y-dimension of a perceived object.

This function extracts the y-dimension from a given PerceivedObject. If the y-dimension is not present in the object, it throws an std::invalid_argument exception.

Parameters
objectThe PerceivedObject from which to retrieve the y-dimension.
Returns
uint16_t y-dimension of the perceived object in in decimeters.
Exceptions
std::invalid_argumentif the y-dimension is not present in the PerceivedObject.

Definition at line 631 of file cpm_ts_getters.h.

◆ getZDimensionConfidenceOfPerceivedObject()

uint8_t etsi_its_cpm_ts_msgs::access::getZDimensionConfidenceOfPerceivedObject ( const PerceivedObject & object)
inline

Gets the confidence of the z-dimension of a perceived object.

Parameters
objectThe PerceivedObject from which to retrieve the z-dimension confidence.
Returns
uint8_t The confidence of the z-dimension of the perceived object in decimeters.
Exceptions
std::invalid_argumentif the z-dimension is not present in the PerceivedObject.

Definition at line 671 of file cpm_ts_getters.h.

◆ getZDimensionOfPerceivedObject()

uint16_t etsi_its_cpm_ts_msgs::access::getZDimensionOfPerceivedObject ( const PerceivedObject & object)
inline

Retrieves the z-dimension of a perceived object.

This function extracts the z-dimension from a given PerceivedObject. If the z-dimension is not present in the object, it throws an std::invalid_argument exception.

Parameters
objectThe PerceivedObject from which to retrieve the z-dimension.
Returns
uint16_t z-dimension of the perceived object in decimeters.
Exceptions
std::invalid_argumentIf the z-dimension is not present in the object.

Definition at line 659 of file cpm_ts_getters.h.

◆ WGSCovMatrixFromConfidenceEllipse()

std::array< double, 4 > etsi_its_cpm_ts_msgs::access::WGSCovMatrixFromConfidenceEllipse ( double semi_major,
double semi_minor,
double major_orientation )
inline

Convert the confidence ellipse to a covariance matrix.

Note that the major_orientation is given in degrees, while the object_heading is given in radians!

Parameters
semi_majorSemi major axis length in meters
semi_minorSemi minor axis length in meters
major_orientationOrientation of the major axis in degrees, relative to WGS84
Returns
std::array<double, 4> The covariance matrix in WGS coordinates (x = North, y = East)

Definition at line 273 of file cpm_ts_getters.h.