etsi_its_messages v3.0.0
 
Loading...
Searching...
No Matches
mapem_ts_getters.h File Reference

Getter functions for the ETSI ITS MAPEM. More...

#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_getters.h>
#include <etsi_its_msgs_utils/impl/checks.h>

Go to the source code of this file.

Functions

std::vector< bool > etsi_its_mapem_ts_msgs::access::getBitString (const std::vector< uint8_t > &buffer, const int bits_unused)
 Get a Bit String in form of bool vector.
 
template<typename T1, typename T2>
void etsi_its_mapem_ts_msgs::access::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.
 
void etsi_its_mapem_ts_msgs::access::throwIfNotPresent (const bool is_present, const std::string val_desc)
 Throws an exception if the given value is not present.
 
MinuteOfTheYear etsi_its_mapem_ts_msgs::access::getMinuteOfTheYear (const MapData &map)
 Get the value of MinuteOfTheYear object MapData object.
 
uint32_t etsi_its_mapem_ts_msgs::access::getMinuteOfTheYearValue (const MapData &map)
 Get the value of MinuteOfTheYear value from MapData object.
 
MinuteOfTheYear etsi_its_mapem_ts_msgs::access::getMinuteOfTheYear (const MAPEM &mapem)
 Get the value of MinuteOfTheYear object from mapem.
 
uint32_t etsi_its_mapem_ts_msgs::access::getMinuteOfTheYearValue (const MAPEM &mapem)
 Get the value of MinuteOfTheYear value from mapem.
 
uint16_t etsi_its_mapem_ts_msgs::access::getIntersectionID (const IntersectionID &intsct_id)
 Get the IntersectionID value.
 
uint16_t etsi_its_mapem_ts_msgs::access::getIntersectionID (const IntersectionGeometry &intsct)
 Get the IntersectionId of an IntersectionGeometry object.
 
double etsi_its_mapem_ts_msgs::access::getLatitude (const Latitude &latitude)
 Get the Latitude value.
 
double etsi_its_mapem_ts_msgs::access::getLongitude (const Longitude &longitude)
 Get the Longitude value.
 
double etsi_its_mapem_ts_msgs::access::getElevation (const Elevation &elevation)
 Get the Elevation value.
 
double etsi_its_mapem_ts_msgs::access::getLatitude (const Position3D &ref_point)
 Get the Latitude value from a given Position3D object.
 
double etsi_its_mapem_ts_msgs::access::getLongitude (const Position3D &ref_point)
 Get the Longitude value from a given Position3D object.
 
double etsi_its_mapem_ts_msgs::access::getElevation (const Position3D &ref_point)
 Get the Elevation value from a given Position3D object.
 
std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection (const LaneDirection &lane_direction)
 Get the LaneDirection in form of bool vector.
 
std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection (const LaneAttributes &lane_attributes)
 Get the LaneDirection in form of bool vector from a LaneAttributes object.
 
std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection (const GenericLane &generic_lane)
 Get the LaneDirection in form of bool vector from a GenericLane object.
 
template<typename T>
gm::Point etsi_its_mapem_ts_msgs::access::getPointFromNodeXY (const T &node_xy)
 Get the Point From NodeXY object.
 

Detailed Description

Getter functions for the ETSI ITS MAPEM.

Definition in file mapem_ts_getters.h.

Function Documentation

◆ getBitString()

std::vector< bool > etsi_its_mapem_ts_msgs::access::getBitString ( const std::vector< uint8_t > & buffer,
const int bits_unused )
inline

Get a Bit String in form of bool vector.

Parameters
bufferas uint8_t vector
bits_unusednumber of bits to ignore at the end of the bit string
Returns
std::vector<bool>

Definition at line 43 of file mapem_ts_getters.h.

47 {
48 throwIfNotPresent(map.time_stamp_is_present, "map.time_stamp");
49 return map.time_stamp;
50 }
51
58 inline uint32_t getMinuteOfTheYearValue(const MapData& map) {
59 MinuteOfTheYear moy = getMinuteOfTheYear(map);
60 return moy.value;
61 }
62

◆ getElevation() [1/2]

double etsi_its_mapem_ts_msgs::access::getElevation ( const Elevation & elevation)
inline

Get the Elevation value.

Parameters
elevationobject to get the Elevation value from
Returns
Elevation value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 152 of file mapem_ts_getters.h.

◆ getElevation() [2/2]

double etsi_its_mapem_ts_msgs::access::getElevation ( const Position3D & ref_point)
inline

Get the Elevation value from a given Position3D object.

Parameters
ref_pointPosition3D object to get the Elevation value from
Returns
Elevation value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 182 of file mapem_ts_getters.h.

◆ getIntersectionID() [1/2]

uint16_t etsi_its_mapem_ts_msgs::access::getIntersectionID ( const IntersectionGeometry & intsct)
inline

Get the IntersectionId of an IntersectionGeometry object.

Parameters
intsctIntersectionGeometry object
Returns
uint16_t the IntersectionId value

Definition at line 122 of file mapem_ts_getters.h.

◆ getIntersectionID() [2/2]

uint16_t etsi_its_mapem_ts_msgs::access::getIntersectionID ( const IntersectionID & intsct_id)
inline

Get the IntersectionID value.

Parameters
intsct_idIntersectionID object to get the value from
Returns
uint16_t the IntersectionID value

Definition at line 112 of file mapem_ts_getters.h.

◆ getLaneDirection() [1/3]

std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection ( const GenericLane & generic_lane)
inline

Get the LaneDirection in form of bool vector from a GenericLane object.

Parameters
generic_laneGenericLane object to get the bool vector from
Returns
std::vector<bool>

Definition at line 213 of file mapem_ts_getters.h.

259 inline MinuteOfTheYear getMinuteOfTheYear(const MapData& map) {
260 throwIfNotPresent(map.time_stamp_is_present, "map.time_stamp");
261 return map.time_stamp;
262 }
263
270 inline uint32_t getMinuteOfTheYearValue(const MapData& map) {
271 MinuteOfTheYear moy = getMinuteOfTheYear(map);
272 return moy.value;
273 }
274
281 inline MinuteOfTheYear getMinuteOfTheYear(const MAPEM& mapem) {
282 return getMinuteOfTheYear(mapem.map);
283 }
284
291 inline uint32_t getMinuteOfTheYearValue(const MAPEM& mapem) {
292 return getMinuteOfTheYearValue(mapem.map);
293 }
294
301 inline uint16_t getIntersectionID(const IntersectionID& intsct_id) {
302 return intsct_id.value;
303 }
304
311 inline uint16_t getIntersectionID(const IntersectionGeometry& intsct) {
312 return getIntersectionID(intsct.id.id);
313 }
314
321 inline double getLatitude(const Latitude& latitude) {
322 return ((double)latitude.value)*1e-7;
323 }
324
331 inline double getLongitude(const Longitude& longitude) {
332 return ((double)longitude.value)*1e-7;
333 }
334
341 inline double getElevation(const Elevation& elevation) {
342 return ((double)elevation.value)*1e-1;
343 }
344
351 inline double getLatitude(const Position3D& ref_point) {
352 return getLatitude(ref_point.lat);
353 }
354
361 inline double getLongitude(const Position3D& ref_point) {
362 return getLongitude(ref_point.lon);
363 }
364
371 inline double getElevation(const Position3D& ref_point) {
372 throwIfNotPresent(ref_point.elevation_is_present, "Position3D.elevation_is_present");
373 return getElevation(ref_point.elevation);
374 }
375
382 inline std::vector<bool> getLaneDirection(const LaneDirection& lane_direction) {
383 return getBitString(lane_direction.value, lane_direction.bits_unused);
384 }
385
392 inline std::vector<bool> getLaneDirection(const LaneAttributes& lane_attributes) {
393 return getLaneDirection(lane_attributes.directional_use);
394 }
395
402 inline std::vector<bool> getLaneDirection(const GenericLane& generic_lane) {
403 return getLaneDirection(generic_lane.lane_attributes);
404 }
405
413 template <typename T>
414 inline gm::Point getPointFromNodeXY(const T& node_xy) {
415 gm::Point p;
416 p.x = ((double)node_xy.x.value) * 1e-2;
417 p.y = ((double)node_xy.y.value) * 1e-2;
418 return p;
419 }
420
421} // namespace access
422
423} // namespace etsi_its_mapem_ts_msgs
double getLongitude(const CAM &cam)
Get the Longitude value of CAM.
double getLatitude(const CAM &cam)
Get the Latitude value of CAM.
Sanity-check functions etc.
void throwIfNotPresent(const bool is_present, const std::string val_desc)
Throws an exception if the given value is not present.
Definition checks.h:57
std::vector< bool > getLaneDirection(const LaneDirection &lane_direction)
Get the LaneDirection in form of bool vector.
gm::Point getPointFromNodeXY(const T &node_xy)
Get the Point From NodeXY object.
uint16_t getIntersectionID(const IntersectionID &intsct_id)
Get the IntersectionID value.
MinuteOfTheYear getMinuteOfTheYear(const MapData &map)
Get the value of MinuteOfTheYear object MapData object.
uint32_t getMinuteOfTheYearValue(const MapData &map)
Get the value of MinuteOfTheYear value from MapData object.
double getElevation(const Elevation &elevation)
Get the Elevation value.

◆ getLaneDirection() [2/3]

std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection ( const LaneAttributes & lane_attributes)
inline

Get the LaneDirection in form of bool vector from a LaneAttributes object.

Parameters
lane_attributesLaneAttributes object to get the bool vector from
Returns
std::vector<bool>

Definition at line 203 of file mapem_ts_getters.h.

◆ getLaneDirection() [3/3]

std::vector< bool > etsi_its_mapem_ts_msgs::access::getLaneDirection ( const LaneDirection & lane_direction)
inline

Get the LaneDirection in form of bool vector.

Parameters
lane_directionLaneDirection object to get the bool vector from
Returns
std::vector<bool>

Definition at line 193 of file mapem_ts_getters.h.

◆ getLatitude() [1/2]

double etsi_its_mapem_ts_msgs::access::getLatitude ( const Latitude & latitude)
inline

Get the Latitude value.

Parameters
latitudeobject to get the Latitude value from
Returns
Latitude value in degree as decimal number

Definition at line 132 of file mapem_ts_getters.h.

◆ getLatitude() [2/2]

double etsi_its_mapem_ts_msgs::access::getLatitude ( const Position3D & ref_point)
inline

Get the Latitude value from a given Position3D object.

Parameters
ref_pointPosition3D object to get the Latitude value from
Returns
Latitude value in degree as decimal number

Definition at line 162 of file mapem_ts_getters.h.

◆ getLongitude() [1/2]

double etsi_its_mapem_ts_msgs::access::getLongitude ( const Longitude & longitude)
inline

Get the Longitude value.

Parameters
longitudeobject to get the Longitude value from
Returns
Longitude value in degree as decimal number

Definition at line 142 of file mapem_ts_getters.h.

◆ getLongitude() [2/2]

double etsi_its_mapem_ts_msgs::access::getLongitude ( const Position3D & ref_point)
inline

Get the Longitude value from a given Position3D object.

Parameters
ref_pointPosition3D object to get the Longitude value from
Returns
Longitude value in degree as decimal number

Definition at line 172 of file mapem_ts_getters.h.

◆ getMinuteOfTheYear() [1/2]

MinuteOfTheYear etsi_its_mapem_ts_msgs::access::getMinuteOfTheYear ( const MapData & map)
inline

Get the value of MinuteOfTheYear object MapData object.

Parameters
mapobject to get the MinuteOfTheYear from
Returns
MinuteOfTheYear the minute of the year object

Definition at line 70 of file mapem_ts_getters.h.

◆ getMinuteOfTheYear() [2/2]

MinuteOfTheYear etsi_its_mapem_ts_msgs::access::getMinuteOfTheYear ( const MAPEM & mapem)
inline

Get the value of MinuteOfTheYear object from mapem.

Parameters
mapemobject to get the MinuteOfTheYear
Returns
MinuteOfTheYear the minute of the year object

Definition at line 92 of file mapem_ts_getters.h.

◆ getMinuteOfTheYearValue() [1/2]

uint32_t etsi_its_mapem_ts_msgs::access::getMinuteOfTheYearValue ( const MapData & map)
inline

Get the value of MinuteOfTheYear value from MapData object.

Parameters
mapobject to get the MinuteOfTheYear value from
Returns
uint32_t the minute of the year value

Definition at line 81 of file mapem_ts_getters.h.

◆ getMinuteOfTheYearValue() [2/2]

uint32_t etsi_its_mapem_ts_msgs::access::getMinuteOfTheYearValue ( const MAPEM & mapem)
inline

Get the value of MinuteOfTheYear value from mapem.

Parameters
mapemobject to get the MinuteOfTheYear value from
Returns
uint32_t the minute of the year value

Definition at line 102 of file mapem_ts_getters.h.

◆ getPointFromNodeXY()

template<typename T>
gm::Point etsi_its_mapem_ts_msgs::access::getPointFromNodeXY ( const T & node_xy)
inline

Get the Point From NodeXY object.

Template Parameters
Trepresenting different NodeXY types (NodeXY20b, NodeXY22b...)
Parameters
node_xythe NodeXY object
Returns
gm::Point geometry_msgs::Point representing the node point (values given in meters)

Definition at line 225 of file mapem_ts_getters.h.

258 {
259
260namespace access {
261
262#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_getters.h>
264
271 inline MinuteOfTheYear getMinuteOfTheYear(const MapData& map) {
272 throwIfNotPresent(map.time_stamp_is_present, "map.time_stamp");
273 return map.time_stamp;
274 }
275
282 inline uint32_t getMinuteOfTheYearValue(const MapData& map) {
283 MinuteOfTheYear moy = getMinuteOfTheYear(map);
284 return moy.value;
285 }
286
293 inline MinuteOfTheYear getMinuteOfTheYear(const MAPEM& mapem) {
294 return getMinuteOfTheYear(mapem.map);
295 }
296
303 inline uint32_t getMinuteOfTheYearValue(const MAPEM& mapem) {
304 return getMinuteOfTheYearValue(mapem.map);
305 }
306
313 inline uint16_t getIntersectionID(const IntersectionID& intsct_id) {
314 return intsct_id.value;
315 }
316
323 inline uint16_t getIntersectionID(const IntersectionGeometry& intsct) {
324 return getIntersectionID(intsct.id.id);
325 }
326
333 inline double getLatitude(const Latitude& latitude) {
334 return ((double)latitude.value)*1e-7;
335 }
336
343 inline double getLongitude(const Longitude& longitude) {
344 return ((double)longitude.value)*1e-7;
345 }
346
353 inline double getElevation(const Elevation& elevation) {
354 return ((double)elevation.value)*1e-1;
355 }
356
363 inline double getLatitude(const Position3D& ref_point) {
364 return getLatitude(ref_point.lat);
365 }
366
373 inline double getLongitude(const Position3D& ref_point) {
374 return getLongitude(ref_point.lon);
375 }
376
383 inline double getElevation(const Position3D& ref_point) {
384 throwIfNotPresent(ref_point.elevation_is_present, "Position3D.elevation_is_present");
385 return getElevation(ref_point.elevation);
386 }
387
394 inline std::vector<bool> getLaneDirection(const LaneDirection& lane_direction) {
395 return getBitString(lane_direction.value, lane_direction.bits_unused);
396 }
397
404 inline std::vector<bool> getLaneDirection(const LaneAttributes& lane_attributes) {
405 return getLaneDirection(lane_attributes.directional_use);
406 }
407
414 inline std::vector<bool> getLaneDirection(const GenericLane& generic_lane) {
415 return getLaneDirection(generic_lane.lane_attributes);
416 }
417
425 template <typename T>
426 inline gm::Point getPointFromNodeXY(const T& node_xy) {
427 gm::Point p;
428 p.x = ((double)node_xy.x.value) * 1e-2;
429 p.y = ((double)node_xy.y.value) * 1e-2;
430 return p;
431 }
432
433} // namespace access
434
435} // namespace etsi_its_mapem_ts_msgs

◆ throwIfNotPresent()

void etsi_its_mapem_ts_msgs::access::throwIfNotPresent ( const bool is_present,
const std::string val_desc )
inline

Throws an exception if the given value is not present.

Parameters
is_presentWhether the value is present.
val_descDescription of the value for the exception message.

Definition at line 58 of file mapem_ts_getters.h.

58 {
59 MinuteOfTheYear moy = getMinuteOfTheYear(map);
60 return moy.value;

◆ throwIfOutOfRange()

template<typename T1, typename T2>
void etsi_its_mapem_ts_msgs::access::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.

Template Parameters
T1
T2
Parameters
valThe value to check if it is in the range.
minThe minimum value of the range.
maxThe maximum value of the range.
val_descDescription of the value for the exception message.

Definition at line 47 of file mapem_ts_getters.h.

47 {
48 throwIfNotPresent(map.time_stamp_is_present, "map.time_stamp");
49 return map.time_stamp;
50 }
51