etsi_its_messages 2.4.0
Loading...
Searching...
No Matches
cpm_ts_getters.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#pragma once
33
34namespace etsi_its_cpm_ts_msgs::access {
35
37
46inline uint32_t getStationID(const CollectivePerceptionMessage &cpm) { return getStationID(cpm.header); }
47
54inline TimestampIts getReferenceTime(const CollectivePerceptionMessage &cpm) {
55 return cpm.payload.management_container.reference_time;
56}
57
64inline uint64_t getReferenceTimeValue(const CollectivePerceptionMessage &cpm) { return getReferenceTime(cpm).value; }
65
72inline double getLatitude(const CollectivePerceptionMessage &cpm) {
73 return getLatitude(cpm.payload.management_container.reference_position.latitude);
74}
75
82inline double getLongitude(const CollectivePerceptionMessage &cpm) {
83 return getLongitude(cpm.payload.management_container.reference_position.longitude);
84}
92inline double getAltitude(const CollectivePerceptionMessage &cpm) {
93 return getAltitude(cpm.payload.management_container.reference_position.altitude);
94}
95
107inline gm::PointStamped getUTMPosition(const CollectivePerceptionMessage &cpm, int &zone, bool &northp) {
108 return getUTMPosition(cpm.payload.management_container.reference_position, zone, northp);
109}
110
120inline gm::PointStamped getUTMPosition(const CollectivePerceptionMessage &cpm) {
121 int zone;
122 bool northp;
123 return getUTMPosition(cpm, zone, northp);
124}
125
135inline std::vector<uint8_t> getCpmContainerIds(const CollectivePerceptionMessage &cpm) {
136 std::vector<uint8_t> container_ids;
137 for (int i = 0; i < cpm.payload.cpm_containers.value.array.size(); i++) {
138 container_ids.push_back(cpm.payload.cpm_containers.value.array[i].container_id.value);
139 }
140 return container_ids;
141}
142
151inline WrappedCpmContainer getCpmContainer(const CollectivePerceptionMessage &cpm, const uint8_t container_id) {
152 for (int i = 0; i < cpm.payload.cpm_containers.value.array.size(); i++) {
153 if (cpm.payload.cpm_containers.value.array[i].container_id.value == container_id) {
154 return cpm.payload.cpm_containers.value.array[i];
155 }
156 }
157 throw std::invalid_argument("No Container with ID " + std::to_string(container_id) + " found in CPM");
158}
168inline WrappedCpmContainer getPerceivedObjectContainer(const CollectivePerceptionMessage &cpm) {
169 return getCpmContainer(cpm, WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER);
170}
171
179inline uint8_t getNumberOfPerceivedObjects(const WrappedCpmContainer &container) {
180 if (container.container_id.value != WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
181 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
182 }
183 uint8_t number = container.container_data_perceived_object_container.number_of_perceived_objects.value;
184 return number;
185}
186
193inline uint8_t getNumberOfPerceivedObjects(const CollectivePerceptionMessage &cpm) {
194 return getNumberOfPerceivedObjects(getPerceivedObjectContainer(cpm));
195}
196
200
209inline PerceivedObject getPerceivedObject(const WrappedCpmContainer &container, const uint8_t i) {
210 if (i >= getNumberOfPerceivedObjects(container)) {
211 throw std::invalid_argument("Index out of range");
212 }
213 return container.container_data_perceived_object_container.perceived_objects.array[i];
214}
215
224inline uint16_t getIdOfPerceivedObject(const PerceivedObject &object) { return object.object_id.value; }
225
232inline int32_t getCartesianCoordinate(const CartesianCoordinateWithConfidence &coordinate) {
233 return coordinate.value.value;
235
242inline uint16_t getCartesianCoordinateConfidence(const CartesianCoordinateWithConfidence &coordinate) {
243 return coordinate.confidence.value;
244}
245
252inline gm::Point getPositionOfPerceivedObject(const PerceivedObject &object) {
253 gm::Point point;
254 point.x = double(getCartesianCoordinate(object.position.x_coordinate)) / 100.0;
255 point.y = double(getCartesianCoordinate(object.position.y_coordinate)) / 100.0;
256 if (object.position.z_coordinate_is_present) {
257 point.z = double(getCartesianCoordinate(object.position.z_coordinate)) / 100.0;
258 }
259 return point;
260}
261
268inline uint16_t getCartesianAngle(const CartesianAngle &angle) { return angle.value.value; }
269
276inline uint8_t getCartesianAngleConfidence(const CartesianAngle &angle) { return angle.confidence.value; }
277
288inline gm::Quaternion getOrientationOfPerceivedObject(const PerceivedObject &object) {
289 if (!object.angles_is_present) throw std::invalid_argument("No angles present in PerceivedObject");
290 tf2::Quaternion q;
291 double roll{0}, pitch{0}, yaw{0};
292
293 if (object.angles.x_angle_is_present) {
294 roll = (((double(getCartesianAngle(object.angles.x_angle)) / 10.0) - 180.0) / 180.0) *
295 M_PI; // TODO: check if 0-360 -> -180-180 is correct
296 }
297 if (object.angles.y_angle_is_present) {
298 pitch = (((double(getCartesianAngle(object.angles.y_angle)) / 10.0) - 180.0) / 180.0) *
299 M_PI; // TODO: check if 0-360 -> -180-180 is correct
300 }
301 yaw = (((double(getCartesianAngle(object.angles.z_angle)) / 10.0) - 180.0) / 180.0) *
302 M_PI; // TODO: check if 0-360 -> -180-180 is correct
303 q.setRPY(roll, pitch, yaw);
304
305 return tf2::toMsg(q);
307
314inline double getYawOfPerceivedObject(const PerceivedObject &object) {
315 gm::Quaternion orientation = getOrientationOfPerceivedObject(object);
316 tf2::Quaternion q(orientation.x, orientation.y, orientation.z, orientation.w);
317 double roll, pitch, yaw;
318 tf2::Matrix3x3(q).getRPY(roll, pitch, yaw);
319 return yaw;
321
328inline gm::Pose getPoseOfPerceivedObject(const PerceivedObject &object) {
329 gm::Pose pose;
330 pose.position = getPositionOfPerceivedObject(object);
331 pose.orientation = getOrientationOfPerceivedObject(object);
332 return pose;
333}
334
342inline int16_t getYawRateOfPerceivedObject(const PerceivedObject &object) {
343 if (!object.z_angular_velocity_is_present) throw std::invalid_argument("No yaw rate present in PerceivedObject");
344 return object.z_angular_velocity.value.value;
345}
346
353inline double getVelocityComponent(const VelocityComponent &velocity) { return double(velocity.value.value) / 100.0; }
354
361inline double getVelocityComponentConfidence(const VelocityComponent &velocity) {
362 return double(velocity.confidence.value) / 100.0;
363}
364
372inline gm::Vector3 getCartesianVelocityOfPerceivedObject(const PerceivedObject &object) {
373 if (!object.velocity_is_present) throw std::invalid_argument("No velocity present in PerceivedObject");
374 if (object.velocity.choice != Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY) {
375 throw std::invalid_argument("Velocity is not Cartesian");
376 }
377 gm::Vector3 velocity;
378 velocity.x = getVelocityComponent(object.velocity.cartesian_velocity.x_velocity);
379 velocity.y = getVelocityComponent(object.velocity.cartesian_velocity.y_velocity);
380 if (object.velocity.cartesian_velocity.z_velocity_is_present) {
381 velocity.z = getVelocityComponent(object.velocity.cartesian_velocity.z_velocity);
382 }
383 return velocity;
384}
385
392inline double getAccelerationComponent(const AccelerationComponent &acceleration) {
393 return double(acceleration.value.value) / 10.0;
394}
402inline double getAccelerationComponentConfidence(const AccelerationComponent &acceleration) {
403 return double(acceleration.confidence.value) / 10.0;
404}
405
413inline gm::Vector3 getCartesianAccelerationOfPerceivedObject(const PerceivedObject &object) {
414 if (!object.acceleration_is_present) throw std::invalid_argument("No acceleration present in PerceivedObject");
415 if (object.acceleration.choice != Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION) {
416 throw std::invalid_argument("Acceleration is not Cartesian");
417 }
418 gm::Vector3 acceleration;
419 acceleration.x = getAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration);
420 acceleration.y = getAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration);
421 if (object.acceleration.cartesian_acceleration.z_acceleration_is_present) {
422 acceleration.z = getAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration);
423 }
424 return acceleration;
425}
426
438inline uint16_t getXDimensionOfPerceivedObject(const PerceivedObject &object) {
439 if (!object.object_dimension_x_is_present) throw std::invalid_argument("No x-dimension present in PerceivedObject");
440 return object.object_dimension_x.value.value;
442
454inline uint16_t getYDimensionOfPerceivedObject(const PerceivedObject &object) {
455 if (!object.object_dimension_y_is_present) throw std::invalid_argument("No y-dimension present in PerceivedObject");
456 return object.object_dimension_y.value.value;
457}
458
470inline uint16_t getZDimensionOfPerceivedObject(const PerceivedObject &object) {
471 if (!object.object_dimension_z_is_present) throw std::invalid_argument("No z-dimension present in PerceivedObject");
472 return object.object_dimension_z.value.value;
473}
474
484inline gm::Vector3 getDimensionsOfPerceivedObject(const PerceivedObject &object) {
485 gm::Vector3 dimensions;
486 dimensions.x = double(getXDimensionOfPerceivedObject(object)) / 10.0;
487 dimensions.y = double(getYDimensionOfPerceivedObject(object)) / 10.0;
488 dimensions.z = double(getZDimensionOfPerceivedObject(object)) / 10.0;
489 return dimensions;
490}
491
502inline gm::PointStamped getUTMPositionOfPerceivedObject(const CollectivePerceptionMessage &cpm,
503 const PerceivedObject &object) {
504 gm::PointStamped utm_position;
505 gm::PointStamped reference_position = getUTMPosition(cpm);
506 gm::Point relative_position = getPositionOfPerceivedObject(object);
507
508 utm_position.header.frame_id = reference_position.header.frame_id;
509 utm_position.point.x = reference_position.point.x + relative_position.x;
510 utm_position.point.y = reference_position.point.y + relative_position.y;
511 utm_position.point.z = reference_position.point.z + relative_position.z;
512
513 return utm_position;
514}
515
516} // namespace etsi_its_cpm_ts_msgs::access
uint32_t getStationID(const ItsPduHeader &header)
Get the StationID of ItsPduHeader.
Definition cam_getters.h:44
double getLatitude(const Latitude &latitude)
Get the Latitude value.
Definition cam_getters.h:52
double getLongitude(const Longitude &longitude)
Get the Longitude value.
Definition cam_getters.h:60
Getter functions for the ETSI ITS Common Data Dictionary (CDD) v2.1.1.
uint16_t getZDimensionOfPerceivedObject(const PerceivedObject &object)
Retrieves the z-dimension of a perceived object.
uint8_t getNumberOfPerceivedObjects(const WrappedCpmContainer &container)
uint64_t getReferenceTimeValue(const CollectivePerceptionMessage &cpm)
Get the ReferenceTime-Value.
uint8_t getCartesianAngleConfidence(const CartesianAngle &angle)
Get the confidence of the Cartesian angle.
double getVelocityComponent(const VelocityComponent &velocity)
Get the velocity component of the PerceivedObject.
WrappedCpmContainer getPerceivedObjectContainer(const CollectivePerceptionMessage &cpm)
Retrieves the perceived object container from a CPM.
uint16_t getCartesianAngle(const CartesianAngle &angle)
Get the Cartesian angle of the PerceivedObject.
double getVelocityComponentConfidence(const VelocityComponent &velocity)
Get the confidence of the velocity component.
gm::Vector3 getCartesianVelocityOfPerceivedObject(const PerceivedObject &object)
Get the Cartesian velocity of the PerceivedObject.
uint16_t getXDimensionOfPerceivedObject(const PerceivedObject &object)
Gets the x-dimension of a perceived object.
TimestampIts getReferenceTime(const CollectivePerceptionMessage &cpm)
Get the Reference Time object.
double getAccelerationComponentConfidence(const AccelerationComponent &acceleration)
Get the confidence of the acceleration component.
WrappedCpmContainer getCpmContainer(const CollectivePerceptionMessage &cpm, const uint8_t container_id)
PerceivedObject getPerceivedObject(const WrappedCpmContainer &container, const uint8_t i)
Retrieves the PerceivedObject at the specified index from the given WrappedCpmContainer.
gm::Quaternion getOrientationOfPerceivedObject(const PerceivedObject &object)
Calculates the orientation of a perceived object.