|
etsi_its_messages v3.4.0
|
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. | |
Getter functions for the ETSI ITS CPM (TS).
Definition in file cpm_ts_getters.h.
|
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!
| semi_major | Semi major axis length in meters |
| semi_minor | Semi minor axis length in meters |
| major_orientation | Orientation of the major axis in degrees, relative to WGS84 |
| object_heading | object heading in radians, relative to WGS84 |
Definition at line 244 of file cpm_ts_getters.h.
|
inline |
Get the acceleration component of the PerceivedObject.
| acceleration | AccelerationComponent to get the value from |
Definition at line 506 of file cpm_ts_getters.h.
|
inline |
Get the confidence of the acceleration component.
| acceleration | AccelerationComponent to get the confidence from |
Definition at line 516 of file cpm_ts_getters.h.
|
inline |
Get the AccelerationMagnitude value.
| acceleration_magnitude | to get the AccelerationMagnitude from |
Definition at line 103 of file cpm_ts_getters.h.
|
inline |
Get the AccelerationMagnitude Confidence.
| acceleration_magnitude | to get the AccelerationMagnitudeConfidence from |
Definition at line 114 of file cpm_ts_getters.h.
|
inline |
Get the Altitude value.
| altitude | to get the Altitude value from |
Definition at line 71 of file cpm_ts_getters.h.
|
inline |
Get the Altitude value of CPM.
| cpm | CPM to get the Altitude value from |
Definition at line 94 of file cpm_ts_getters.h.
|
inline |
Get the Cartesian Acceleration Confidence Of Perceived Object.
| object | PerceivedObject to get the Cartesian acceleration from |
| std::invalid_argument | If the acceleration is no cartesian acceleration. |
Definition at line 562 of file cpm_ts_getters.h.
|
inline |
Get the Cartesian acceleration of the PerceivedObject.
| object | PerceivedObject to get the Cartesian acceleration from |
| std::invalid_argument | If the acceleration is no cartesian acceleration. |
Definition at line 527 of file cpm_ts_getters.h.
|
inline |
Get the Cartesian angle of the PerceivedObject.
| object | PerceivedObject to get the Cartesian angle from |
Definition at line 291 of file cpm_ts_getters.h.
|
inline |
Get the confidence of the Cartesian angle.
| angle | CartesianAngle to get the confidence from |
Definition at line 299 of file cpm_ts_getters.h.
|
inline |
Retrieves the Cartesian coordinate value from a CartesianCoordinateWithConfidence object.
| coordinate | The CartesianCoordinateWithConfidence object from which to retrieve the value. |
Definition at line 239 of file cpm_ts_getters.h.
|
inline |
Retrieves the confidence value from a CartesianCoordinateWithConfidence object.
| coordinate | The CartesianCoordinateWithConfidence object from which to retrieve the confidence value. |
Definition at line 249 of file cpm_ts_getters.h.
|
inline |
Get the Cartesian Velocity Confidence Of Perceived Object object.
| object | PerceivedObject to get the Cartesian velocity from |
| std::invalid_argument | If the velocity is no cartesian velocity. |
Definition at line 468 of file cpm_ts_getters.h.
|
inline |
Get the Cartesian velocity of the PerceivedObject.
| object | PerceivedObject to get the Cartesian velocity from |
| std::invalid_argument | If the velocity is no cartesian velocity. |
Definition at line 435 of file cpm_ts_getters.h.
|
inline |
Retrieves the CpmContainer with the specified container ID from the CPM.
| cpm | The CPM from which to retrieve the CpmContainer. |
| container_id | The ID of the CpmContainer to retrieve. |
| std::invalid_argument | if no CpmContainer with the specified ID is found in the CPM. |
Definition at line 153 of file cpm_ts_getters.h.
|
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.
| cpm | The CPM from which to retrieve the container IDs. |
Definition at line 137 of file cpm_ts_getters.h.
|
inline |
Get the Dimensions Confidence Of Perceived Object.
| object | The PerceivedObject to get the dimensions confidence from |
Definition at line 699 of file cpm_ts_getters.h.
|
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.
| object | The PerceivedObject for which to calculate the dimensions. |
Definition at line 685 of file cpm_ts_getters.h.
|
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
| heading | to get the Heading value from |
Definition at line 159 of file cpm_ts_getters.h.
|
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
| heading | to get the Heading standard deviation from |
Definition at line 170 of file cpm_ts_getters.h.
|
inline |
Retrieves the ID of a perceived object.
This function takes a PerceivedObject as input and returns the ID of the object.
| object | The PerceivedObject for which to retrieve the ID. |
Definition at line 226 of file cpm_ts_getters.h.
|
inline |
Get the lateral acceleration.
| lateralAcceleration | to get the lateral acceleration from |
Definition at line 65 of file cpm_ts_getters.h.
|
inline |
Get the Lateral Acceleration Confidence.
| lateral_acceleration | to get the LateralAccelerationConfidence from |
Definition at line 75 of file cpm_ts_getters.h.
|
inline |
Get the Latitude value of CPM.
| cpm | CPM to get the Latitude value from |
Definition at line 74 of file cpm_ts_getters.h.
|
inline |
Get the Latitude value.
| latitude | to get the Latitude value from |
Definition at line 55 of file cpm_ts_getters.h.
|
inline |
Get the Longitude value of CPM.
| cpm | CPM to get the Longitude value from |
Definition at line 84 of file cpm_ts_getters.h.
|
inline |
Get the Longitude value.
| longitude | to get the Longitude value from |
Definition at line 63 of file cpm_ts_getters.h.
|
inline |
Get the longitudinal acceleration.
| longitudinalAcceleration | to get the longitudinal acceleration from |
Definition at line 45 of file cpm_ts_getters.h.
|
inline |
Get the Longitudinal Acceleration Confidence.
| longitudinal_acceleration | to get the LongitudinalAccelerationConfidence from |
Definition at line 55 of file cpm_ts_getters.h.
|
inline |
Retrieves the number of perceived objects from the given CPM.
| cpm | The CPM from which to retrieve the number of perceived objects. |
Definition at line 195 of file cpm_ts_getters.h.
|
inline |
Retrieves the number of perceived objects from the given perceived object container.
| container | The perceived object container to retrieve the number of perceived objects from. |
| std::invalid_argument | if the container is not a PerceivedObjectContainer. |
Definition at line 181 of file cpm_ts_getters.h.
|
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.
| object | The PerceivedObject structure containing the angles of the perceived object. |
Definition at line 311 of file cpm_ts_getters.h.
|
inline |
Retrieves the PerceivedObject at the specified index from the given WrappedCpmContainer.
| container | The WrappedCpmContainer from which to retrieve the PerceivedObject (should be a PerceivedObjectContainer). |
| i | The index of the PerceivedObject to retrieve. |
| std::invalid_argument | if the index is out of range. |
Definition at line 211 of file cpm_ts_getters.h.
|
inline |
Retrieves the perceived object container from a CPM.
This function returns the perceived object container from the given CPM.
| cpm | The CPM from which to retrieve the perceived object container. |
Definition at line 170 of file cpm_ts_getters.h.
|
inline |
Extract major axis length, minor axis length and orientation from the given position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to extract the values from |
Definition at line 225 of file cpm_ts_getters.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 286 of file cpm_ts_getters.h.
|
inline |
Get the pose of the PerceivedObject.
| object | PerceivedObject to get the pose from |
Definition at line 366 of file cpm_ts_getters.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 103 of file cpm_ts_getters.h.
|
inline |
Extract major axis length, minor axis length and orientation from the given position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to extract the values from |
Definition at line 87 of file cpm_ts_getters.h.
|
inline |
Get the Position Confidences Of Perceived Object.
| object | The PerceivedObject to get the position confidences from |
Definition at line 276 of file cpm_ts_getters.h.
|
inline |
Returns the position of a perceived object.
| object | The perceived object. |
Definition at line 259 of file cpm_ts_getters.h.
|
inline |
Get the Reference Time object.
| cpm | CPM to get the ReferenceTime-Value from |
Definition at line 56 of file cpm_ts_getters.h.
|
inline |
Get the ReferenceTime-Value.
| cpm | CPM to get the ReferenceTime-Value from |
Definition at line 66 of file cpm_ts_getters.h.
|
inline |
Get the Semi Axis object.
| semi_axis_length | The SemiAxisLength object to get the semi axis from |
Definition at line 214 of file cpm_ts_getters.h.
|
inline |
Get the sensorId of a SensorInformation object.
| sensor_information | The SensorInformation to get the sensorId from |
Definition at line 749 of file cpm_ts_getters.h.
|
inline |
Get the sensorType of a SensorInformation object.
| sensor_information | The SensorInformation to get the sensorType from |
Definition at line 759 of file cpm_ts_getters.h.
|
inline |
Get the vehicle speed.
| speed | to get the speed value from |
Definition at line 84 of file cpm_ts_getters.h.
|
inline |
Get the Speed Confidence.
| speed | to get the SpeedConfidence from |
Definition at line 92 of file cpm_ts_getters.h.
|
inline |
Retrieves the station ID from the given CPM.
This function extracts the station ID from the header of the provided CPM.
| cpm | The CPM from which to retrieve the station ID. |
Definition at line 48 of file cpm_ts_getters.h.
|
inline |
Get the StationID of ItsPduHeader.
| header | ItsPduHeader to get the StationID value from |
Definition at line 47 of file cpm_ts_getters.h.
|
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
| cpm | CPM from which to extract the UTM position. |
Definition at line 122 of file cpm_ts_getters.h.
|
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
| [in] | cpm | CPM to get the UTM Position from |
| [out] | zone | the UTM zone (zero means UPS) |
| [out] | northp | hemisphere (true means north, false means south) |
Definition at line 109 of file cpm_ts_getters.h.
|
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
| [in] | reference_position | ReferencePosition or ReferencePositionWithConfidence to get the UTM Position from |
| [out] | zone | the UTM zone (zero means UPS) |
| [out] | northp | hemisphere (true means north, false means south) |
Definition at line 130 of file cpm_ts_getters.h.
|
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.
| cpm | The Collective Perception Message (CPM) containing the reference position. |
| object | The PerceivedObject for which the UTM position needs to be calculated. |
Definition at line 716 of file cpm_ts_getters.h.
|
inline |
Get the velocity component of the PerceivedObject.
| velocity | VelocityComponent to get the value from |
Definition at line 416 of file cpm_ts_getters.h.
|
inline |
Get the confidence of the velocity component.
| velocity | VelocityComponent to get the confidence from |
Definition at line 424 of file cpm_ts_getters.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 299 of file cpm_ts_getters.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 116 of file cpm_ts_getters.h.
|
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
| cpm | The CPM message to get the reference position from |
Definition at line 739 of file cpm_ts_getters.h.
|
inline |
Gets the confidence of the x-dimension of a perceived object.
| object | The PerceivedObject from which to retrieve the x-dimension confidence. |
| std::invalid_argument | if the x-dimension is not present in the PerceivedObject. |
Definition at line 615 of file cpm_ts_getters.h.
|
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.
| object | The PerceivedObject from which to retrieve the x-dimension. |
| std::invalid_argument | if the x-dimension is not present in the PerceivedObject. |
Definition at line 603 of file cpm_ts_getters.h.
|
inline |
Get the Yaw Confidence Of Perceived Object object.
| object | PerceivedObject to get the yaw confidence from |
| std::invalid_argument | If the angles are not present in the object. |
Definition at line 353 of file cpm_ts_getters.h.
|
inline |
Get the yaw of the PerceivedObject.
| object | PerceivedObject to get the yaw from |
Definition at line 338 of file cpm_ts_getters.h.
|
inline |
Get the Yaw Rate value.
| yaw_rate | The YawRate object to get the yaw rate from |
Definition at line 179 of file cpm_ts_getters.h.
|
inline |
Get the Yaw Rate Confidence.
| yaw_rate | The YawRate object to get the yaw rate confidence from |
Definition at line 190 of file cpm_ts_getters.h.
|
inline |
Get the Yaw Rate Confidence Of Perceived Object.
| object | The PerceivedObject to get the yaw rate confidence from |
| std::invalid_argument | If the yaw rate is not present in the object. |
Definition at line 394 of file cpm_ts_getters.h.
|
inline |
Get the yaw rate of the PerceivedObject.
| object | PerceivedObject to get the yaw rate from |
| std::invalid_argument | If the yaw rate is not present in the object. |
Definition at line 380 of file cpm_ts_getters.h.
|
inline |
Gets the confidence of the y-dimension of a perceived object.
| object | The PerceivedObject from which to retrieve the y-dimension confidence. |
| std::invalid_argument | if the y-dimension is not present in the PerceivedObject. |
Definition at line 643 of file cpm_ts_getters.h.
|
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.
| object | The PerceivedObject from which to retrieve the y-dimension. |
| std::invalid_argument | if the y-dimension is not present in the PerceivedObject. |
Definition at line 631 of file cpm_ts_getters.h.
|
inline |
Gets the confidence of the z-dimension of a perceived object.
| object | The PerceivedObject from which to retrieve the z-dimension confidence. |
| std::invalid_argument | if the z-dimension is not present in the PerceivedObject. |
Definition at line 671 of file cpm_ts_getters.h.
|
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.
| object | The PerceivedObject from which to retrieve the z-dimension. |
| std::invalid_argument | If the z-dimension is not present in the object. |
Definition at line 659 of file cpm_ts_getters.h.
|
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!
| semi_major | Semi major axis length in meters |
| semi_minor | Semi minor axis length in meters |
| major_orientation | Orientation of the major axis in degrees, relative to WGS84 |
Definition at line 273 of file cpm_ts_getters.h.