etsi_its_messages 1.0.0
Loading...
Searching...
No Matches
cam_setters_common.h
Go to the documentation of this file.
1/*
2=============================================================================
3MIT License
4
5Copyright (c) 2023-2024 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
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
36
45 GenerationDeltaTime& generation_delta_time, const uint64_t unix_nanosecs,
46 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
47 TimestampIts t_its;
48 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
49 uint16_t gdt_value = t_its.value % 65536;
50 throwIfOutOfRange(gdt_value, GenerationDeltaTime::MIN, GenerationDeltaTime::MAX, "GenerationDeltaTime");
51 generation_delta_time.value = gdt_value;
52}
53
62 CAM& cam, const uint64_t unix_nanosecs,
63 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
64 setGenerationDeltaTime(cam.cam.generation_delta_time, unix_nanosecs, n_leap_seconds);
65}
66
73inline void setStationType(CAM& cam, const uint8_t value) {
74 setStationType(cam.cam.cam_parameters.basic_container.station_type, value);
75}
76
85inline void setHeadingValue(HeadingValue& heading, const double value) {
86 int64_t deg = (int64_t)std::round(value * 1e1);
87 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
88 heading.value = deg;
89}
90
100inline void setHeading(Heading& heading, const double value) {
101 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
102 setHeadingValue(heading.heading_value, value);
103}
104
114inline void setHeading(CAM& cam, const double heading_val) {
115 setHeading(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.heading,
116 heading_val);
117}
118
125inline void setVehicleWidth(VehicleWidth& vehicle_width, const double value) {
126 int64_t width = (int64_t)std::round(value * 1e1);
127 throwIfOutOfRange(width, VehicleWidth::MIN, VehicleWidth::MAX, "VehicleWidthValue");
128 vehicle_width.value = width;
129}
130
137inline void setVehicleLengthValue(VehicleLengthValue& vehicle_length, const double value) {
138 int64_t length = (int64_t)std::round(value * 1e1);
139 throwIfOutOfRange(length, VehicleLengthValue::MIN, VehicleLengthValue::MAX, "VehicleLengthValue");
140 vehicle_length.value = length;
141}
142
151inline void setVehicleLength(VehicleLength& vehicle_length, const double value) {
152 vehicle_length.vehicle_length_confidence_indication.value = VehicleLengthConfidenceIndication::UNAVAILABLE;
153 setVehicleLengthValue(vehicle_length.vehicle_length_value, value);
154}
155
163inline void setVehicleDimensions(CAM& cam, const double vehicle_length, const double vehicle_width) {
165 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_length,
166 vehicle_length);
167 setVehicleWidth(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_width,
168 vehicle_width);
169}
170
177inline void setSpeed(CAM& cam, const double speed_val) {
178 setSpeed(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.speed, speed_val);
179}
180
187inline void setLongitudinalAcceleration(CAM& cam, const double lon_accel) {
189 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.longitudinal_acceleration,
190 lon_accel);
191}
192
199inline void setLateralAcceleration(CAM& cam, const double lat_accel) {
201 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.lateral_acceleration,
202 lat_accel);
203 cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency
204 .lateral_acceleration_is_present = true;
205}
206
218inline void setReferencePosition(CAM& cam, const double latitude, const double longitude,
219 const double altitude = AltitudeValue::UNAVAILABLE) {
220 setReferencePosition(cam.cam.cam_parameters.basic_container.reference_position, latitude, longitude, altitude);
221}
222
235inline void setFromUTMPosition(CAM& cam, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
236 setFromUTMPosition(cam.cam.cam_parameters.basic_container.reference_position, utm_position, zone, northp);
237}
238
245inline void setExteriorLights(ExteriorLights& exterior_lights, const std::vector<bool>& bits) {
246 setBitString(exterior_lights, bits);
247}
248
255inline void setExteriorLights(CAM& cam, const std::vector<bool>& exterior_lights) {
256 if (ExteriorLights::SIZE_BITS != exterior_lights.size()) {
257 throw std::invalid_argument("Vector has wrong size. (" + std::to_string(exterior_lights.size()) +
258 " != " + std::to_string(ExteriorLights::SIZE_BITS) + ")");
259 }
260 if (cam.cam.cam_parameters.low_frequency_container_is_present) {
261 if (cam.cam.cam_parameters.low_frequency_container.choice ==
262 LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY) {
264 cam.cam.cam_parameters.low_frequency_container.basic_vehicle_container_low_frequency.exterior_lights,
265 exterior_lights);
266 } else {
267 throw std::invalid_argument("LowFrequencyContainer is not BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY!");
268 }
269 } else {
270 throw std::invalid_argument("LowFrequencyContainer is not present!");
271 }
272}
273
280inline void setAccelerationControl(AccelerationControl& acceleration_control, const std::vector<bool>& bits) {
281 setBitString(acceleration_control, bits);
282}
283
290inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
291 setBitString(driving_lane_status, bits);
292}
293
300inline void setSpecialTransportType(SpecialTransportType& special_transport_type, const std::vector<bool>& bits) {
301 setBitString(special_transport_type, bits);
302}
303
310inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
311 setBitString(light_bar_siren_in_use, bits);
312}
313
320inline void setEmergencyPriority(EmergencyPriority& emergency_priority, const std::vector<bool>& bits) {
321 setBitString(emergency_priority, bits);
322}
323
324#endif // ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_SETTERS_COMMON_H
void setLongitudinalAcceleration(CAM &cam, const double lon_accel)
Set the longitudinal acceleration.
void setVehicleLength(VehicleLength &vehicle_length, const double value)
Set the VehicleLength object.
void setLateralAcceleration(CAM &cam, const double lat_accel)
Set the lateral acceleration.
void setSpecialTransportType(SpecialTransportType &special_transport_type, const std::vector< bool > &bits)
Set the Special Transport Type by a vector of bools.
void setSpeed(CAM &cam, const double speed_val)
Set the vehicle speed.
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 setHeading(Heading &heading, const double value)
Set the Heading object.
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 setHeadingValue(HeadingValue &heading, const double value)
Set the HeadingValue object.
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 setGenerationDeltaTime(GenerationDeltaTime &generation_delta_time, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Set the GenerationDeltaTime-Value.
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 setTimestampITS(TimestampIts &timestamp_its, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Set the TimestampITS object.
void setBitString(T &bitstring, const std::vector< bool > &bits)
Set a Bit String by a vector of bools.
File containing constants that are used in the context of ETIS ITS Messages.