convertIntersectionState.h
Go to the documentation of this file.
1 
54 #pragma once
55 
66 #ifdef ROS1
67 #include <etsi_its_spatem_ts_msgs/IntersectionState.h>
68 namespace spatem_ts_msgs = etsi_its_spatem_ts_msgs;
69 #else
70 #include <etsi_its_spatem_ts_msgs/msg/intersection_state.hpp>
71 namespace spatem_ts_msgs = etsi_its_spatem_ts_msgs::msg;
72 #endif
73 
74 
76 
77 void toRos_IntersectionState(const spatem_ts_IntersectionState_t& in, spatem_ts_msgs::IntersectionState& out) {
78  if (in.name) {
79  toRos_DescriptiveName(*in.name, out.name);
80  out.name_is_present = true;
81  }
83  toRos_MsgCount(in.revision, out.revision);
84  toRos_IntersectionStatusObject(in.status, out.status);
85  if (in.moy) {
86  toRos_MinuteOfTheYear(*in.moy, out.moy);
87  out.moy_is_present = true;
88  }
89  if (in.timeStamp) {
90  toRos_DSecond(*in.timeStamp, out.time_stamp);
91  out.time_stamp_is_present = true;
92  }
93  if (in.enabledLanes) {
94  toRos_EnabledLaneList(*in.enabledLanes, out.enabled_lanes);
95  out.enabled_lanes_is_present = true;
96  }
97  toRos_MovementList(in.states, out.states);
98  if (in.maneuverAssistList) {
99  toRos_ManeuverAssistList(*in.maneuverAssistList, out.maneuver_assist_list);
100  out.maneuver_assist_list_is_present = true;
101  }
102 }
103 
104 void toStruct_IntersectionState(const spatem_ts_msgs::IntersectionState& in, spatem_ts_IntersectionState_t& out) {
105  memset(&out, 0, sizeof(spatem_ts_IntersectionState_t));
106  if (in.name_is_present) {
108  toStruct_DescriptiveName(in.name, *out.name);
109  }
111  toStruct_MsgCount(in.revision, out.revision);
113  if (in.moy_is_present) {
114  out.moy = (spatem_ts_MinuteOfTheYear_t*) calloc(1, sizeof(spatem_ts_MinuteOfTheYear_t));
115  toStruct_MinuteOfTheYear(in.moy, *out.moy);
116  }
117  if (in.time_stamp_is_present) {
118  out.timeStamp = (spatem_ts_DSecond_t*) calloc(1, sizeof(spatem_ts_DSecond_t));
119  toStruct_DSecond(in.time_stamp, *out.timeStamp);
120  }
121  if (in.enabled_lanes_is_present) {
123  toStruct_EnabledLaneList(in.enabled_lanes, *out.enabledLanes);
124  }
125  toStruct_MovementList(in.states, out.states);
126  if (in.maneuver_assist_list_is_present) {
128  toStruct_ManeuverAssistList(in.maneuver_assist_list, *out.maneuverAssistList);
129  }
130 }
131 
132 }
spatem_ts_IntersectionState::moy
spatem_ts_MinuteOfTheYear_t * moy
spatem_ts_IntersectionState::enabledLanes
struct spatem_ts_EnabledLaneList * enabledLanes
etsi_its_spatem_ts_conversion::toRos_IntersectionReferenceID
void toRos_IntersectionReferenceID(const spatem_ts_IntersectionReferenceID_t &in, spatem_ts_msgs::IntersectionReferenceID &out)
Definition: convertIntersectionReferenceID.h:62
etsi_its_spatem_ts_conversion::toRos_IntersectionStatusObject
void toRos_IntersectionStatusObject(const spatem_ts_IntersectionStatusObject_t &in, spatem_ts_msgs::IntersectionStatusObject &out)
Definition: convertIntersectionStatusObject.h:74
spatem_ts_MinuteOfTheYear_t
long spatem_ts_MinuteOfTheYear_t
etsi_its_spatem_ts_conversion::toRos_MovementList
void toRos_MovementList(const spatem_ts_MovementList_t &in, spatem_ts_msgs::MovementList &out)
Definition: convertMovementList.h:64
spatem_ts_IntersectionState.h
spatem_ts_IntersectionState::timeStamp
spatem_ts_DSecond_t * timeStamp
etsi_its_spatem_ts_conversion::toStruct_MsgCount
void toStruct_MsgCount(const spatem_ts_msgs::MsgCount &in, spatem_ts_MsgCount_t &out)
Definition: convertMsgCount.h:63
etsi_its_spatem_ts_conversion::toStruct_MovementList
void toStruct_MovementList(const spatem_ts_msgs::MovementList &in, spatem_ts_MovementList_t &out)
Definition: convertMovementList.h:72
etsi_its_spatem_ts_conversion::toRos_DSecond
void toRos_DSecond(const spatem_ts_DSecond_t &in, spatem_ts_msgs::DSecond &out)
Definition: convertDSecond.h:59
spatem_ts_IntersectionState::maneuverAssistList
struct spatem_ts_ManeuverAssistList * maneuverAssistList
etsi_its_spatem_ts_conversion::toStruct_MinuteOfTheYear
void toStruct_MinuteOfTheYear(const spatem_ts_msgs::MinuteOfTheYear &in, spatem_ts_MinuteOfTheYear_t &out)
Definition: convertMinuteOfTheYear.h:63
convertMovementList.h
spatem_ts_IntersectionState::id
spatem_ts_IntersectionReferenceID_t id
etsi_its_spatem_ts_conversion::toStruct_DescriptiveName
void toStruct_DescriptiveName(const spatem_ts_msgs::DescriptiveName &in, spatem_ts_DescriptiveName_t &out)
Definition: convertDescriptiveName.h:63
convertIntersectionStatusObject.h
convertMsgCount.h
spatem_ts_IntersectionState::revision
spatem_ts_MsgCount_t revision
convertDescriptiveName.h
spatem_ts_IntersectionReferenceID::id
spatem_ts_IntersectionID_t id
etsi_its_spatem_ts_conversion::toStruct_ManeuverAssistList
void toStruct_ManeuverAssistList(const spatem_ts_msgs::ManeuverAssistList &in, spatem_ts_ManeuverAssistList_t &out)
Definition: convertManeuverAssistList.h:72
etsi_its_spatem_ts_conversion::toRos_MinuteOfTheYear
void toRos_MinuteOfTheYear(const spatem_ts_MinuteOfTheYear_t &in, spatem_ts_msgs::MinuteOfTheYear &out)
Definition: convertMinuteOfTheYear.h:59
spatem_ts_ManeuverAssistList
etsi_its_spatem_ts_conversion::toStruct_DSecond
void toStruct_DSecond(const spatem_ts_msgs::DSecond &in, spatem_ts_DSecond_t &out)
Definition: convertDSecond.h:63
spatem_ts_IntersectionState::name
spatem_ts_DescriptiveName_t * name
etsi_its_spatem_ts_conversion::toStruct_IntersectionState
void toStruct_IntersectionState(const spatem_ts_msgs::IntersectionState &in, spatem_ts_IntersectionState_t &out)
Definition: convertIntersectionState.h:104
spatem_ts_EnabledLaneList
etsi_its_spatem_ts_conversion::toStruct_IntersectionReferenceID
void toStruct_IntersectionReferenceID(const spatem_ts_msgs::IntersectionReferenceID &in, spatem_ts_IntersectionReferenceID_t &out)
Definition: convertIntersectionReferenceID.h:70
OCTET_STRING
etsi_its_spatem_ts_conversion::toStruct_EnabledLaneList
void toStruct_EnabledLaneList(const spatem_ts_msgs::EnabledLaneList &in, spatem_ts_EnabledLaneList_t &out)
Definition: convertEnabledLaneList.h:72
convertManeuverAssistList.h
spatem_ts_DSecond_t
long spatem_ts_DSecond_t
etsi_its_spatem_ts_conversion::toStruct_IntersectionStatusObject
void toStruct_IntersectionStatusObject(const spatem_ts_msgs::IntersectionStatusObject &in, spatem_ts_IntersectionStatusObject_t &out)
Definition: convertIntersectionStatusObject.h:79
convertDSecond.h
etsi_its_spatem_ts_conversion::toRos_IntersectionState
void toRos_IntersectionState(const spatem_ts_IntersectionState_t &in, spatem_ts_msgs::IntersectionState &out)
Definition: convertIntersectionState.h:77
convertMinuteOfTheYear.h
etsi_its_spatem_ts_conversion::toRos_ManeuverAssistList
void toRos_ManeuverAssistList(const spatem_ts_ManeuverAssistList_t &in, spatem_ts_msgs::ManeuverAssistList &out)
Definition: convertManeuverAssistList.h:64
convertIntersectionReferenceID.h
etsi_its_spatem_ts_conversion::toRos_EnabledLaneList
void toRos_EnabledLaneList(const spatem_ts_EnabledLaneList_t &in, spatem_ts_msgs::EnabledLaneList &out)
Definition: convertEnabledLaneList.h:64
etsi_its_spatem_ts_conversion::toRos_MsgCount
void toRos_MsgCount(const spatem_ts_MsgCount_t &in, spatem_ts_msgs::MsgCount &out)
Definition: convertMsgCount.h:59
spatem_ts_IntersectionState
convertEnabledLaneList.h
etsi_its_spatem_ts_conversion::toRos_DescriptiveName
void toRos_DescriptiveName(const spatem_ts_DescriptiveName_t &in, spatem_ts_msgs::DescriptiveName &out)
Definition: convertDescriptiveName.h:59
etsi_its_spatem_ts_conversion
Definition: convertAdvisorySpeed.h:67
spatem_ts_IntersectionState::status
spatem_ts_IntersectionStatusObject_t status
spatem_ts_IntersectionState::states
spatem_ts_MovementList_t states


etsi_its_spatem_ts_conversion
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:30:52