Functions
cam_setters_common.h File Reference

Common setter functions for the ETSI ITS CAM (EN and TS) More...

#include <etsi_its_msgs_utils/impl/checks.h>
#include <etsi_its_msgs_utils/impl/constants.h>
#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
Include dependency graph for cam_setters_common.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

void setAccelerationControl (AccelerationControl &acceleration_control, const std::vector< bool > &bits)
 Set the Acceleration Control by a vector of bools. More...
 
void setDrivingLaneStatus (DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
 Set the Driving Lane Status by a vector of bools. More...
 
void setEmergencyPriority (EmergencyPriority &emergency_priority, const std::vector< bool > &bits)
 Set the Emergency Priority by a vector of bools. More...
 
void setExteriorLights (CAM &cam, const std::vector< bool > &exterior_lights)
 Set the Exterior Lights by using a vector of bools. More...
 
void setExteriorLights (ExteriorLights &exterior_lights, const std::vector< bool > &bits)
 Set the Exterior Lights by a vector of bools. More...
 
void setFromUTMPosition (CAM &cam, const gm::PointStamped &utm_position, const int &zone, const bool &northp)
 Set the ReferencePosition of a CAM from a given UTM-Position. More...
 
void setGenerationDeltaTime (CAM &cam, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
 Set the Generation Delta Time object. More...
 
void setGenerationDeltaTime (GenerationDeltaTime &generation_delta_time, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
 Set the GenerationDeltaTime-Value. More...
 
void setHeading (CAM &cam, const double heading_val, const double confidence=std::numeric_limits< double >::infinity())
 Set the Heading for a CAM. More...
 
void setLateralAcceleration (CAM &cam, const double lat_accel, const double confidence=std::numeric_limits< double >::infinity())
 Set the lateral acceleration. More...
 
void setLightBarSirenInUse (LightBarSirenInUse &light_bar_siren_in_use, const std::vector< bool > &bits)
 Set the Lightbar Siren In Use by a vector of bools. More...
 
void setLongitudinalAcceleration (CAM &cam, const double lon_accel, const double confidence=std::numeric_limits< double >::infinity())
 Set the longitudinal acceleration. More...
 
void setReferencePosition (CAM &cam, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Set the ReferencePosition for a CAM. More...
 
void setSpecialTransportType (SpecialTransportType &special_transport_type, const std::vector< bool > &bits)
 Set the Special Transport Type by a vector of bools. More...
 
void setSpeed (CAM &cam, const double speed_val, const double confidence=SpeedConfidence::UNAVAILABLE)
 Set the vehicle speed. More...
 
void setStationType (CAM &cam, const uint8_t value)
 Set the StationType for a CAM. More...
 
void setVehicleDimensions (CAM &cam, const double vehicle_length, const double vehicle_width)
 Set the vehicle dimensions. More...
 
void setVehicleLength (VehicleLength &vehicle_length, const double value)
 Set the VehicleLength object. More...
 
void setVehicleLengthValue (VehicleLengthValue &vehicle_length, const double value)
 Set the VehicleLengthValue object. More...
 
void setVehicleWidth (VehicleWidth &vehicle_width, const double value)
 Set the VehicleWidth object. More...
 

Detailed Description

Common setter functions for the ETSI ITS CAM (EN and TS)

Definition in file cam_setters_common.h.

Function Documentation

◆ setAccelerationControl()

void setAccelerationControl ( AccelerationControl &  acceleration_control,
const std::vector< bool > &  bits 
)
inline

Set the Acceleration Control by a vector of bools.

Parameters
acceleration_control
bits

Definition at line 259 of file cam_setters_common.h.

◆ setDrivingLaneStatus()

void setDrivingLaneStatus ( DrivingLaneStatus &  driving_lane_status,
const std::vector< bool > &  bits 
)
inline

Set the Driving Lane Status by a vector of bools.

Parameters
driving_lane_status
bits

Definition at line 269 of file cam_setters_common.h.

◆ setEmergencyPriority()

void setEmergencyPriority ( EmergencyPriority &  emergency_priority,
const std::vector< bool > &  bits 
)
inline

Set the Emergency Priority by a vector of bools.

Parameters
emergency_priority
bits

Definition at line 299 of file cam_setters_common.h.

◆ setExteriorLights() [1/2]

void setExteriorLights ( CAM &  cam,
const std::vector< bool > &  exterior_lights 
)
inline

Set the Exterior Lights by using a vector of bools.

Parameters
camCAM to set the exterior lights
exterior_lightsvector of bools to set the exterior lights

Definition at line 234 of file cam_setters_common.h.

◆ setExteriorLights() [2/2]

void setExteriorLights ( ExteriorLights &  exterior_lights,
const std::vector< bool > &  bits 
)
inline

Set the Exterior Lights by a vector of bools.

Parameters
exterior_lights
bits

Definition at line 224 of file cam_setters_common.h.

◆ setFromUTMPosition()

void setFromUTMPosition ( CAM &  cam,
const gm::PointStamped &  utm_position,
const int &  zone,
const bool &  northp 
)
inline

Set the ReferencePosition of a CAM from a given UTM-Position.

The position is transformed to latitude and longitude by using GeographicLib::UTMUPS The z-Coordinate is directly used as altitude value The frame_id of the given utm_position must be set to 'utm_<zone><N/S>'

Parameters
[out]camCAM for which to set the ReferencePosition
[in]utm_positiongeometry_msgs::PointStamped describing the given utm position
[in]zonethe UTM zone (zero means UPS) of the given position
[in]northphemisphere (true means north, false means south)

Definition at line 214 of file cam_setters_common.h.

◆ setGenerationDeltaTime() [1/2]

void setGenerationDeltaTime ( CAM &  cam,
const uint64_t  unix_nanosecs,
const uint16_t  n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second 
)
inline

Set the Generation Delta Time object.

Parameters
camCAM to set the GenerationDeltaTime-Value for
unix_nanosecsTimestamp in unix-nanoseconds to set the GenerationDeltaTime-Value from
n_leap_secondsNumber of leap seconds since 2004 for the given timestamp (Defaults to the todays number of leap seconds since 2004.)

Definition at line 63 of file cam_setters_common.h.

◆ setGenerationDeltaTime() [2/2]

void setGenerationDeltaTime ( GenerationDeltaTime &  generation_delta_time,
const uint64_t  unix_nanosecs,
const uint16_t  n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second 
)
inline

Set the GenerationDeltaTime-Value.

Parameters
generation_delta_timeGenerationDeltaTime to set the GenerationDeltaTime-Value for
unix_nanosecsTimestamp in unix-nanoseconds to set the GenerationDeltaTime-Value from
n_leap_secondsNumber of leap seconds since 2004 for the given timestamp (Defaults to the todays number of leap seconds since 2004.)

Definition at line 46 of file cam_setters_common.h.

◆ setHeading()

void setHeading ( CAM &  cam,
const double  heading_val,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the Heading for a CAM.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West HeadingConfidence is set to UNAVAILABLE

Parameters
camCAM to set the ReferencePosition
valueHeading value in degree as decimal number
confidencestandard deviation of heading in degree as decimal number (default: infinity, mapping to HeadingConfidence::UNAVAILABLE)

Definition at line 89 of file cam_setters_common.h.

◆ setLateralAcceleration()

void setLateralAcceleration ( CAM &  cam,
const double  lat_accel,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the lateral acceleration.

Parameters
camCAM to set the acceleration value s
lat_accellateral acceleration to set in m/s^2 as decimal number (left is positiv), if not available use 16.1 m/s^2
confidencestandard deviation of the lateral acceleration in m/s^2 as decimal number Default is infinity, mapping to AccelerationConfidence::UNAVAILABLE

Definition at line 178 of file cam_setters_common.h.

◆ setLightBarSirenInUse()

void setLightBarSirenInUse ( LightBarSirenInUse &  light_bar_siren_in_use,
const std::vector< bool > &  bits 
)
inline

Set the Lightbar Siren In Use by a vector of bools.

Parameters
light_bar_siren_in_use
bits

Definition at line 289 of file cam_setters_common.h.

◆ setLongitudinalAcceleration()

void setLongitudinalAcceleration ( CAM &  cam,
const double  lon_accel,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the longitudinal acceleration.

Parameters
camCAM to set the acceleration value s
lon_accellongitudinal acceleration to set in m/s^2 as decimal number (braking is negative), if not available use 16.1 m/s^2
confidencestandard deviation of the longitudinal acceleration in m/s^2 as decimal number Default is infinity, mapping to AccelerationConfidence::UNAVAILABLE

Definition at line 164 of file cam_setters_common.h.

◆ setReferencePosition()

void setReferencePosition ( CAM &  cam,
const double  latitude,
const double  longitude,
const double  altitude = AltitudeValue::UNAVAILABLE 
)
inline

Set the ReferencePosition for a CAM.

This function sets the latitude, longitude, and altitude of the CAMs reference position. If the altitude is not provided, it is set to AltitudeValue::UNAVAILABLE.

Parameters
camCAM to set the ReferencePosition
latitudeThe latitude value position in degree as decimal number.
longitudeThe longitude value in degree as decimal number.
altitudeThe altitude value (above the reference ellipsoid surface) in meter as decimal number (optional).

Definition at line 197 of file cam_setters_common.h.

◆ setSpecialTransportType()

void setSpecialTransportType ( SpecialTransportType &  special_transport_type,
const std::vector< bool > &  bits 
)
inline

Set the Special Transport Type by a vector of bools.

Parameters
special_transport_type
bits

Definition at line 279 of file cam_setters_common.h.

◆ setSpeed()

void setSpeed ( CAM &  cam,
const double  speed_val,
const double  confidence = SpeedConfidence::UNAVAILABLE 
)
inline

Set the vehicle speed.

Parameters
camCAM to set the speed value
speed_valspeed value to set in m/s as decimal number

Definition at line 152 of file cam_setters_common.h.

◆ setStationType()

void setStationType ( CAM &  cam,
const uint8_t  value 
)
inline

Set the StationType for a CAM.

Parameters
camCAM-Message to set the station_type value
valuestation_type value to set

Definition at line 75 of file cam_setters_common.h.

◆ setVehicleDimensions()

void setVehicleDimensions ( CAM &  cam,
const double  vehicle_length,
const double  vehicle_width 
)
inline

Set the vehicle dimensions.

Parameters
camCAM to set the vehicle dimensions
vehicle_lengthvehicle length in meter as decimal number
vehicle_widthvehicle width in meter as decimal number

Definition at line 138 of file cam_setters_common.h.

◆ setVehicleLength()

void setVehicleLength ( VehicleLength &  vehicle_length,
const double  value 
)
inline

Set the VehicleLength object.

VehicleLengthConfidenceIndication is set to UNAVAILABLE

Parameters
vehicle_lengthobject to set
valueVehicleLengthValue in meter as decimal number

Definition at line 126 of file cam_setters_common.h.

◆ setVehicleLengthValue()

void setVehicleLengthValue ( VehicleLengthValue &  vehicle_length,
const double  value 
)
inline

Set the VehicleLengthValue object.

Parameters
vehicle_lengthobject to set
valueVehicleLengthValue in meter as decimal number

Definition at line 112 of file cam_setters_common.h.

◆ setVehicleWidth()

void setVehicleWidth ( VehicleWidth &  vehicle_width,
const double  value 
)
inline

Set the VehicleWidth object.

Parameters
vehicle_widthobject to set
valueVehicleWidth in meter as decimal number

Definition at line 100 of file cam_setters_common.h.



etsi_its_msgs_utils
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:32:12