etsi_its_messages v3.2.1
 
Loading...
Searching...
No Matches
cam_setters_common.h
Go to the documentation of this file.
1/*
2=============================================================================
3MIT License
4
5Copyright (c) 2023-2025 Institute for Automotive Engineering (ika), RWTH Aachen University
6
7Permission is hereby granted, free of charge, to any person obtaining a copy
8of this software and associated documentation files (the "Software"), to deal
9in the Software without restriction, including without limitation the rights
10to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11copies of the Software, and to permit persons to whom the Software is
12furnished to do so, subject to the following conditions:
13
14The above copyright notice and this permission notice shall be included in all
15copies or substantial portions of the Software.
16
17THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
23SOFTWARE.
24=============================================================================
25*/
26
31
32#ifndef ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_SETTERS_COMMON_H
33#define ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_SETTERS_COMMON_H
34
37#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
38
47 GenerationDeltaTime& generation_delta_time, const uint64_t unix_nanosecs,
48 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
49 TimestampIts t_its;
50 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
51 uint16_t gdt_value = t_its.value % 65536;
52 throwIfOutOfRange(gdt_value, GenerationDeltaTime::MIN, GenerationDeltaTime::MAX, "GenerationDeltaTime");
53 generation_delta_time.value = gdt_value;
54}
55
64 CAM& cam, const uint64_t unix_nanosecs,
65 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
66 setGenerationDeltaTime(cam.cam.generation_delta_time, unix_nanosecs, n_leap_seconds);
67}
68
75inline void setStationType(CAM& cam, const uint8_t value) {
76 setStationType(cam.cam.cam_parameters.basic_container.station_type, value);
77}
78
89inline void setHeading(CAM& cam, const double heading_val, const double confidence = std::numeric_limits<double>::infinity()) {
90 setHeadingCDD(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.heading,
91 heading_val, confidence);
92}
93
100inline void setVehicleWidth(VehicleWidth& vehicle_width, const double value) {
101 int64_t width = (int64_t)std::round(value * 1e1);
102 throwIfOutOfRange(width, VehicleWidth::MIN, VehicleWidth::MAX, "VehicleWidthValue");
103 vehicle_width.value = width;
104}
105
112inline void setVehicleLengthValue(VehicleLengthValue& vehicle_length, const double value) {
113 int64_t length = (int64_t)std::round(value * 1e1);
114 throwIfOutOfRange(length, VehicleLengthValue::MIN, VehicleLengthValue::MAX, "VehicleLengthValue");
115 vehicle_length.value = length;
116}
117
126inline void setVehicleLength(VehicleLength& vehicle_length, const double value) {
127 vehicle_length.vehicle_length_confidence_indication.value = VehicleLengthConfidenceIndication::UNAVAILABLE;
128 setVehicleLengthValue(vehicle_length.vehicle_length_value, value);
129}
130
138inline void setVehicleDimensions(CAM& cam, const double vehicle_length, const double vehicle_width) {
140 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_length,
141 vehicle_length);
142 setVehicleWidth(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_width,
143 vehicle_width);
144}
145
152inline void setSpeed(CAM& cam, const double speed_val, const double confidence = SpeedConfidence::UNAVAILABLE) {
153 setSpeed(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.speed, speed_val, confidence);
154}
155
164inline void setLongitudinalAcceleration(CAM& cam, const double lon_accel, const double confidence = std::numeric_limits<double>::infinity()) {
166 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.longitudinal_acceleration,
167 lon_accel, confidence);
168}
169
178inline void setLateralAcceleration(CAM& cam, const double lat_accel, const double confidence = std::numeric_limits<double>::infinity()) {
180 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.lateral_acceleration,
181 lat_accel, confidence);
182 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency
183 .lateral_acceleration_is_present = true;
184}
185
197inline void setReferencePosition(CAM& cam, const double latitude, const double longitude,
198 const double altitude = AltitudeValue::UNAVAILABLE) {
199 setReferencePosition(cam.cam.cam_parameters.basic_container.reference_position, latitude, longitude, altitude);
200}
201
214inline void setFromUTMPosition(CAM& cam, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
215 setFromUTMPosition(cam.cam.cam_parameters.basic_container.reference_position, utm_position, zone, northp);
216}
217
224inline void setExteriorLights(ExteriorLights& exterior_lights, const std::vector<bool>& bits) {
225 setBitString(exterior_lights, bits);
226}
227
234inline void setExteriorLights(CAM& cam, const std::vector<bool>& exterior_lights) {
235 if (ExteriorLights::SIZE_BITS != exterior_lights.size()) {
236 throw std::invalid_argument("Vector has wrong size. (" + std::to_string(exterior_lights.size()) +
237 " != " + std::to_string(ExteriorLights::SIZE_BITS) + ")");
238 }
239 if (cam.cam.cam_parameters.low_frequency_container_is_present) {
240 if (cam.cam.cam_parameters.low_frequency_container.choice ==
241 LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY) {
243 cam.cam.cam_parameters.low_frequency_container.basic_vehicle_container_low_frequency.exterior_lights,
244 exterior_lights);
245 } else {
246 throw std::invalid_argument("LowFrequencyContainer is not BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY!");
247 }
248 } else {
249 throw std::invalid_argument("LowFrequencyContainer is not present!");
250 }
251}
252
259inline void setAccelerationControl(AccelerationControl& acceleration_control, const std::vector<bool>& bits) {
260 setBitString(acceleration_control, bits);
261}
262
269inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
270 setBitString(driving_lane_status, bits);
271}
272
279inline void setSpecialTransportType(SpecialTransportType& special_transport_type, const std::vector<bool>& bits) {
280 setBitString(special_transport_type, bits);
281}
282
289inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
290 setBitString(light_bar_siren_in_use, bits);
291}
292
299inline void setEmergencyPriority(EmergencyPriority& emergency_priority, const std::vector<bool>& bits) {
300 setBitString(emergency_priority, bits);
301}
302
303#endif // ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_SETTERS_COMMON_H
void setLongitudinalAcceleration(CAM &cam, const double lon_accel, const double confidence=std::numeric_limits< double >::infinity())
Set the longitudinal acceleration.
void setVehicleLength(VehicleLength &vehicle_length, const double value)
Set the VehicleLength object.
void setSpecialTransportType(SpecialTransportType &special_transport_type, const std::vector< bool > &bits)
Set the Special Transport Type by a vector of bools.
void setLightBarSirenInUse(LightBarSirenInUse &light_bar_siren_in_use, const std::vector< bool > &bits)
Set the Lightbar Siren In Use by a vector of bools.
void setVehicleDimensions(CAM &cam, const double vehicle_length, const double vehicle_width)
Set the vehicle dimensions.
void setVehicleLengthValue(VehicleLengthValue &vehicle_length, const double value)
Set the VehicleLengthValue object.
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.
void setLateralAcceleration(CAM &cam, const double lat_accel, const double confidence=std::numeric_limits< double >::infinity())
Set the lateral acceleration.
void setExteriorLights(ExteriorLights &exterior_lights, const std::vector< bool > &bits)
Set the Exterior Lights by a vector of bools.
void setStationType(CAM &cam, const uint8_t value)
Set the StationType for a CAM.
void setAccelerationControl(AccelerationControl &acceleration_control, const std::vector< bool > &bits)
Set the Acceleration Control by a vector of bools.
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.
void setVehicleWidth(VehicleWidth &vehicle_width, const double value)
Set the VehicleWidth object.
void setEmergencyPriority(EmergencyPriority &emergency_priority, const std::vector< bool > &bits)
Set the Emergency Priority by a vector of bools.
void setSpeed(CAM &cam, const double speed_val, const double confidence=SpeedConfidence::UNAVAILABLE)
Set the vehicle speed.
void setReferencePosition(CAM &cam, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
Set the ReferencePosition for a CAM.
void setDrivingLaneStatus(DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
Set the Driving Lane Status by a vector of bools.
void setHeading(CAM &cam, const double heading_val, const double confidence=std::numeric_limits< double >::infinity())
Set the Heading for a CAM.
void setTimestampITS(TimestampIts &timestamp_its, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
Set the TimestampITS object.
void setHeadingCDD(Heading &heading, const double value, double confidence=std::numeric_limits< double >::infinity())
Set the Heading object.
Sanity-check functions etc.
void throwIfOutOfRange(const T1 &val, const T2 &min, const T2 &max, const std::string val_desc)
Throws an exception if a given value is out of a defined range.
Definition checks.h:46
File containing constants that are used in the context of ETIS ITS Messages.
const std::map< uint64_t, uint16_t > LEAP_SECOND_INSERTIONS_SINCE_2004
std::map that stores all leap second insertions since 2004 with the corresponding unix-date of the in...
Definition constants.h:45