|
double | getLateralAcceleration (const LateralAcceleration &lateral_acceleration) |
| Get the lateral acceleration. More...
|
|
double | getLateralAccelerationConfidence (const LateralAcceleration &lateral_acceleration) |
| Get the Lateral Acceleration Confidence. More...
|
|
double | getLongitudinalAcceleration (const LongitudinalAcceleration &longitudinal_acceleration) |
| Get the longitudinal acceleration. More...
|
|
double | getLongitudinalAccelerationConfidence (const LongitudinalAcceleration &longitudinal_acceleration) |
| Get the Longitudinal Acceleration Confidence. More...
|
|
const std::array< double, 4 > | getRefPosConfidence (const CAM &cam) |
| Get the confidence ellipse of the reference position as Covariance matrix. More...
|
|
const std::array< double, 4 > | getWGSRefPosConfidence (const CAM &cam) |
| Get the confidence ellipse of the reference position as Covariance matrix. More...
|
|
void | setItsPduHeader (CAM &cam, const uint32_t station_id, const uint8_t protocol_version=0) |
| Set the ItsPduHeader-object for a CAM. More...
|
|
void | setLateralAcceleration (LateralAcceleration &accel, const double value, const double confidence=std::numeric_limits< double >::infinity()) |
| Set the LateralAcceleration object. More...
|
|
void | setLateralAccelerationValue (LateralAccelerationValue &accel, const double value) |
| Set the LateralAccelerationValue object. More...
|
|
void | setLongitudinalAcceleration (LongitudinalAcceleration &accel, const double value, const double confidence=std::numeric_limits< double >::infinity()) |
| Set the LongitudinalAcceleration object. More...
|
|
void | setLongitudinalAccelerationValue (LongitudinalAccelerationValue &accel, const double value) |
| Set the LongitudinalAccelerationValue object. More...
|
|
void | setRefPosConfidence (CAM &cam, const std::array< double, 4 > &covariance_matrix, const double object_heading) |
| Set the confidence of the reference position. More...
|
|
void | setWGSRefPosConfidence (CAM &cam, const std::array< double, 4 > &covariance_matrix) |
| Set the confidence of the reference position. More...
|
|
const std::array<double, 4> etsi_its_cam_msgs::access::getRefPosConfidence |
( |
const CAM & |
cam | ) |
|
|
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 the longitudinal axis and y is the lateral axis of the vehicle.
- Parameters
-
cam | The CAM message to get the reference position from |
- Returns
- const std::array<double, 4> the covariance matrix, as specified above
Definition at line 88 of file cam_getters.h.
const std::array<double, 4> etsi_its_cam_msgs::access::getWGSRefPosConfidence |
( |
const CAM & |
cam | ) |
|
|
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
-
cam | The CAM message to get the reference position from |
- Returns
- const std::array<double, 4> the covariance matrix, as specified above
Definition at line 102 of file cam_getters.h.