test_denm_access.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <cmath>
3 
5 
6 TEST(etsi_its_denm_msgs, test_set_get_denm) {
7  denm_msgs::DENM denm;
8 
9  int station_id = randomInt(denm_msgs::StationID::MIN, denm_msgs::StationID::MAX);
10  int protocol_version =
11  randomInt(denm_msgs::ItsPduHeader::PROTOCOL_VERSION_MIN, denm_msgs::ItsPduHeader::PROTOCOL_VERSION_MAX);
12  denm_access::setItsPduHeader(denm, station_id, protocol_version);
13  EXPECT_EQ(denm_msgs::ItsPduHeader::MESSAGE_ID_DENM, denm.header.message_id);
14  EXPECT_EQ(protocol_version, denm.header.protocol_version);
15  EXPECT_EQ(station_id, denm_access::getStationID(denm));
16 
17  // https://www.etsi.org/deliver/etsi_ts/102800_102899/10289402/01.02.01_60/ts_10289402v010201p.pdf
18  // DE_TimestampITS
19  // The value for TimestampIts for 2007-01-01T00:00:00.000Z is
20  // 94694401000 milliseconds, which includes one leap second insertion
21  // since 2004-01-01T00:00:00.000Z.
22  uint64_t t_2007 = ((uint64_t)1167609600) * 1e9;
23  denm_msgs::TimestampIts t_its;
24  denm_access::setTimestampITS(t_its, t_2007, 1);
25  EXPECT_EQ(94694401000, t_its.value);
26 
27  denm_access::setReferenceTime(denm, t_2007, 1);
28  EXPECT_EQ(94694401000, denm_access::getReferenceTimeValue(denm));
29  uint64_t t_2007_off = t_2007 + 5 * 1e9;
31 
32  int stationType_val = randomInt(denm_msgs::StationType::MIN, denm_msgs::StationType::MAX);
33  denm_access::setStationType(denm, stationType_val);
34  EXPECT_EQ(stationType_val, denm_access::getStationType(denm));
35 
36  double latitude = randomDouble(-90.0, 90.0);
37  double longitude = randomDouble(-180.0, 180.0);
38  denm_access::setReferencePosition(denm, latitude, longitude);
39  EXPECT_NEAR(latitude, denm_access::getLatitude(denm), 1e-7);
40  EXPECT_NEAR(longitude, denm_access::getLongitude(denm), 1e-7);
41  latitude = randomDouble(-90.0, 90.0);
42  longitude = randomDouble(-180.0, 180.0);
43  double altitude = randomDouble(-1000.0, 8000.0);
44  denm_access::setReferencePosition(denm, latitude, longitude, altitude);
45  EXPECT_NEAR(latitude, denm_access::getLatitude(denm), 1e-7);
46  EXPECT_NEAR(longitude, denm_access::getLongitude(denm), 1e-7);
47  EXPECT_NEAR(altitude, denm_access::getAltitude(denm), 1e-2);
48 
49  // Set specific position to test utm projection
50  latitude = 50.787467;
51  longitude = 6.046498;
52  altitude = 209.0;
53  denm_access::setReferencePosition(denm, latitude, longitude, altitude);
54  int zone;
55  bool northp;
56  gm::PointStamped utm = denm_access::getUTMPosition(denm, zone, northp);
57  EXPECT_NEAR(291827.02, utm.point.x, 1e-1);
58  EXPECT_NEAR(5630349.72, utm.point.y, 1e-1);
59  EXPECT_EQ(altitude, utm.point.z);
60  EXPECT_EQ(32, zone);
61  EXPECT_EQ(true, northp);
62  denm_access::setFromUTMPosition(denm, utm, zone, northp);
63  EXPECT_NEAR(latitude, denm_access::getLatitude(denm), 1e-7);
64  EXPECT_NEAR(longitude, denm_access::getLongitude(denm), 1e-7);
65  EXPECT_NEAR(altitude, denm_access::getAltitude(denm), 1e-2);
66 
67  double heading_val = randomDouble(0.0, 360.0);
68  double heading_conf = randomDouble(0.0, 6.25);
69  denm.denm.location_is_present = true;
70  denm_access::setHeading(denm, heading_val, heading_conf);
71  EXPECT_NEAR(heading_val, denm_access::getHeading(denm), 1e-1);
72  EXPECT_NEAR(heading_conf, denm_access::getHeadingConfidence(denm), 1e-1);
73 
74  double speed_val = randomDouble(0.0, 163.82);
75  denm.denm.location_is_present = true;
76  denm_access::setSpeed(denm, speed_val);
77  EXPECT_NEAR(speed_val, denm_access::getSpeed(denm), 1e-2);
78 }
getLatitude
double getLatitude(const CAM &cam)
Get the Latitude value of CAM.
Definition: cam_getters_common.h:75
getStationType
uint8_t getStationType(const CAM &cam)
Get the stationType object.
Definition: cam_getters_common.h:67
getLongitude
double getLongitude(const CAM &cam)
Get the Longitude value of CAM.
Definition: cam_getters_common.h:85
getStationID
uint32_t getStationID(const CAM &cam)
Get the Station ID object.
Definition: cam_getters_common.h:43
setReferencePosition
void setReferencePosition(CAM &cam, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
Set the ReferencePosition for a CAM.
Definition: cam_setters_common.h:197
randomInt
int randomInt(int min, int max)
Definition: test_access.cpp:28
TEST
TEST(etsi_its_denm_msgs, test_set_get_denm)
Definition: test_denm_access.cpp:6
getAltitude
double getAltitude(const CAM &cam)
Get the Altitude value of CAM.
Definition: cam_getters_common.h:95
getUnixNanosecondsFromReferenceTime
uint64_t getUnixNanosecondsFromReferenceTime(const TimestampIts &reference_time)
Get the Unix-Nanoseconds from a given ReferenceTime object.
Definition: cpm_ts_utils.h:41
setHeading
void setHeading(CAM &cam, const double heading_val, const double confidence=std::numeric_limits< double >::infinity())
Set the Heading for a CAM.
Definition: cam_setters_common.h:89
getUTMPosition
gm::PointStamped getUTMPosition(const CAM &cam, int &zone, bool &northp)
Get the UTM Position defined within the BasicContainer of the CAM.
Definition: cam_getters_common.h:248
etsi_its_cpm_ts_msgs::access::getReferenceTimeValue
uint64_t getReferenceTimeValue(const CollectivePerceptionMessage &cpm)
Get the ReferenceTime-Value.
Definition: cpm_ts_getters.h:66
getHeading
double getHeading(const CAM &cam)
Get the Heading value of CAM.
Definition: cam_getters_common.h:107
etsi_its_cpm_ts_msgs::access::setReferenceTime
void setReferenceTime(CollectivePerceptionMessage &cpm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
Sets the reference time in a CPM.
Definition: cpm_ts_setters.h:66
setFromUTMPosition
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.
Definition: cam_setters_common.h:214
randomDouble
double randomDouble(double min, double max)
Definition: test_access.cpp:24
etsi_its_denm_msgs
Definition: denm_access.h:38
getHeadingConfidence
double getHeadingConfidence(const CAM &cam)
Get the Heading confidence of CAM.
Definition: cam_getters_common.h:118
setTimestampITS
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.
Definition: cdd_setters_common.h:52
setSpeed
void setSpeed(CAM &cam, const double speed_val, const double confidence=SpeedConfidence::UNAVAILABLE)
Set the vehicle speed.
Definition: cam_setters_common.h:152
etsi_its_denm_msgs::access
Definition: impl/denm/denm_access.h:54
etsi_its_cpm_ts_msgs::access::getReferenceTime
TimestampIts getReferenceTime(const CollectivePerceptionMessage &cpm)
Get the Reference Time object.
Definition: cpm_ts_getters.h:56
etsi_its_cam_msgs::access::setItsPduHeader
void setItsPduHeader(CAM &cam, const uint32_t station_id, const uint8_t protocol_version=0)
Set the ItsPduHeader-object for a CAM.
Definition: cam_setters.h:45
setStationType
void setStationType(CAM &cam, const uint8_t value)
Set the StationType for a CAM.
Definition: cam_setters_common.h:75
getSpeed
double getSpeed(const CAM &cam)
Get the vehicle speed.
Definition: cam_getters_common.h:168


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