15 #ifndef SIMULATION_INTERFACE__CONVERSIONS_HPP_
16 #define SIMULATION_INTERFACE__CONVERSIONS_HPP_
18 #include <simulation_interface/builtin_interfaces.pb.h>
19 #include <simulation_interface/geometry_msgs.pb.h>
20 #include <simulation_interface/rosgraph_msgs.pb.h>
21 #include <simulation_interface/simulation_api_schema.pb.h>
22 #include <simulation_interface/std_msgs.pb.h>
23 #include <simulation_interface/traffic_simulator_msgs.pb.h>
25 #include <autoware_control_msgs/msg/control.hpp>
26 #include <autoware_vehicle_msgs/msg/gear_command.hpp>
27 #include <builtin_interfaces/msg/duration.hpp>
28 #include <builtin_interfaces/msg/time.hpp>
30 #include <geometry_msgs/msg/accel.hpp>
31 #include <geometry_msgs/msg/point.hpp>
32 #include <geometry_msgs/msg/pose.hpp>
33 #include <geometry_msgs/msg/quaternion.hpp>
34 #include <geometry_msgs/msg/twist.hpp>
35 #include <geometry_msgs/msg/vector3.hpp>
37 #include <rosgraph_msgs/msg/clock.hpp>
39 #include <std_msgs/msg/header.hpp>
41 #include <traffic_simulator_msgs/msg/action_status.hpp>
42 #include <traffic_simulator_msgs/msg/axle.hpp>
43 #include <traffic_simulator_msgs/msg/axles.hpp>
44 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
45 #include <traffic_simulator_msgs/msg/entity_status.hpp>
46 #include <traffic_simulator_msgs/msg/entity_type.hpp>
47 #include <traffic_simulator_msgs/msg/lanelet_pose.hpp>
48 #include <traffic_simulator_msgs/msg/misc_object_parameters.hpp>
49 #include <traffic_simulator_msgs/msg/pedestrian_parameters.hpp>
50 #include <traffic_simulator_msgs/msg/performance.hpp>
51 #include <traffic_simulator_msgs/msg/polyline_trajectory.hpp>
52 #include <traffic_simulator_msgs/msg/vehicle_parameters.hpp>
58 template <
typename Proto>
59 zmq::message_t
toZMQ(
const Proto & proto)
62 proto.SerializeToString(&serialized_str);
64 zmq::message_t msg(serialized_str.size());
65 std::memcpy(msg.data(), serialized_str.data(), serialized_str.size());
69 template <
typename Proto>
73 proto.ParseFromArray(msg.data(),
static_cast<int>(msg.size()));
82 void toProto(
const geometry_msgs::msg::Quaternion & q, geometry_msgs::Quaternion & proto);
83 void toMsg(
const geometry_msgs::Quaternion & proto, geometry_msgs::msg::Quaternion & q);
88 void toProto(
const geometry_msgs::msg::Twist & t, geometry_msgs::Twist & proto);
89 void toMsg(
const geometry_msgs::Twist & proto, geometry_msgs::msg::Twist & t);
90 void toProto(
const geometry_msgs::msg::Accel & a, geometry_msgs::Accel & proto);
91 void toMsg(
const geometry_msgs::Accel & proto, geometry_msgs::msg::Accel & a);
99 const traffic_simulator_msgs::msg::Performance & performance,
100 traffic_simulator_msgs::Performance & proto);
102 const traffic_simulator_msgs::Performance & proto,
103 traffic_simulator_msgs::msg::Performance & performance);
104 void toProto(
const traffic_simulator_msgs::msg::Axle & axle, traffic_simulator_msgs::Axle & proto);
105 void toMsg(
const traffic_simulator_msgs::Axle & proto, traffic_simulator_msgs::msg::Axle & axle);
107 const traffic_simulator_msgs::msg::Axles & axles, traffic_simulator_msgs::Axles & proto);
108 void toMsg(
const traffic_simulator_msgs::Axles & proto, traffic_simulator_msgs::msg::Axles & axles);
110 const traffic_simulator_msgs::msg::VehicleParameters & p,
111 traffic_simulator_msgs::VehicleParameters & proto);
113 const traffic_simulator_msgs::VehicleParameters & proto,
114 traffic_simulator_msgs::msg::VehicleParameters & p);
116 const traffic_simulator_msgs::msg::PedestrianParameters & p,
117 traffic_simulator_msgs::PedestrianParameters & proto);
119 const traffic_simulator_msgs::PedestrianParameters & proto,
120 traffic_simulator_msgs::msg::PedestrianParameters & p);
122 const traffic_simulator_msgs::msg::MiscObjectParameters & p,
123 traffic_simulator_msgs::MiscObjectParameters & proto);
125 const traffic_simulator_msgs::MiscObjectParameters & proto,
126 traffic_simulator_msgs::msg::MiscObjectParameters & p);
128 const traffic_simulator_msgs::msg::ActionStatus & s,
129 traffic_simulator_msgs::ActionStatus & proto);
131 const traffic_simulator_msgs::ActionStatus & proto,
132 traffic_simulator_msgs::msg::ActionStatus & s);
162 const builtin_interfaces::msg::Duration & duration, builtin_interfaces::Duration & proto);
164 const builtin_interfaces::Duration & proto, builtin_interfaces::msg::Duration & duration);
165 void toProto(
const builtin_interfaces::msg::Time & time, builtin_interfaces::Time & proto);
166 void toMsg(
const builtin_interfaces::Time & proto, builtin_interfaces::msg::Time & time);
167 void toProto(
const rosgraph_msgs::msg::Clock & time, rosgraph_msgs::Clock & proto);
168 void toMsg(
const rosgraph_msgs::Clock & proto, rosgraph_msgs::msg::Clock & time);
169 void toProto(
const std_msgs::msg::Header & header, std_msgs::Header & proto);
170 void toMsg(
const std_msgs::Header & proto, std_msgs::msg::Header & header);
173 #define DEFINE_CONVERSION(PACKAGE, TYPENAME) \
174 auto toProto(const PACKAGE::msg::TYPENAME &, PACKAGE::TYPENAME &)->void; \
175 auto toMsg(const PACKAGE::TYPENAME &, PACKAGE::msg::TYPENAME &)->void
182 #undef DEFINE_CONVERSION
185 const std::tuple<autoware_control_msgs::msg::Control, autoware_vehicle_msgs::msg::GearCommand> &,
186 traffic_simulator_msgs::VehicleCommand &) -> void;
188 template <
typename TrafficLightBulbMessageType>
191 TrafficLightBulbMessageType & traffic_light_bulb_state) ->
void
193 using namespace simulation_api_schema;
195 auto convert_color = [](
auto color) constexpr
198 case TrafficLight_Color_RED:
199 return TrafficLightBulbMessageType::RED;
200 case TrafficLight_Color_AMBER:
201 return TrafficLightBulbMessageType::AMBER;
202 case TrafficLight_Color_GREEN:
203 return TrafficLightBulbMessageType::GREEN;
204 case TrafficLight_Color_WHITE:
205 return TrafficLightBulbMessageType::WHITE;
206 case TrafficLight_Color_UNKNOWN_COLOR:
207 return TrafficLightBulbMessageType::UNKNOWN;
209 return TrafficLightBulbMessageType::UNKNOWN;
213 auto convert_shape = [](
auto shape) constexpr
216 case TrafficLight_Shape_CIRCLE:
217 return TrafficLightBulbMessageType::CIRCLE;
218 case TrafficLight_Shape_LEFT_ARROW:
219 return TrafficLightBulbMessageType::LEFT_ARROW;
220 case TrafficLight_Shape_RIGHT_ARROW:
221 return TrafficLightBulbMessageType::RIGHT_ARROW;
222 case TrafficLight_Shape_UP_ARROW:
223 return TrafficLightBulbMessageType::UP_ARROW;
229 case TrafficLight_Shape_DOWN_ARROW:
230 return TrafficLightBulbMessageType::DOWN_ARROW;
231 case TrafficLight_Shape_DOWN_LEFT_ARROW:
232 return TrafficLightBulbMessageType::DOWN_LEFT_ARROW;
233 case TrafficLight_Shape_DOWN_RIGHT_ARROW:
234 return TrafficLightBulbMessageType::DOWN_RIGHT_ARROW;
235 case TrafficLight_Shape_CROSS:
236 return TrafficLightBulbMessageType::CROSS;
237 case TrafficLight_Shape_UNKNOWN_SHAPE:
238 return TrafficLightBulbMessageType::UNKNOWN;
240 return TrafficLightBulbMessageType::UNKNOWN;
244 auto convert_status = [](
auto status) constexpr
247 case TrafficLight_Status_SOLID_OFF:
248 return TrafficLightBulbMessageType::SOLID_OFF;
249 case TrafficLight_Status_SOLID_ON:
250 return TrafficLightBulbMessageType::SOLID_ON;
251 case TrafficLight_Status_FLASHING:
252 return TrafficLightBulbMessageType::FLASHING;
253 case TrafficLight_Status_UNKNOWN_STATUS:
254 return TrafficLightBulbMessageType::UNKNOWN;
256 return TrafficLightBulbMessageType::UNKNOWN;
260 traffic_light_bulb_state.status = convert_status(proto.status());
261 traffic_light_bulb_state.shape = convert_shape(proto.shape());
262 traffic_light_bulb_state.color = convert_color(proto.color());
263 traffic_light_bulb_state.confidence = proto.confidence();
268 -> traffic_simulator_msgs::Vertex;
270 auto toROS2Message(
const traffic_simulator_msgs::Vertex &) -> traffic_simulator_msgs::msg::Vertex;
273 -> traffic_simulator_msgs::Polyline;
276 -> traffic_simulator_msgs::msg::Polyline;
279 -> traffic_simulator_msgs::PolylineTrajectory;
281 auto toROS2Message(
const traffic_simulator_msgs::PolylineTrajectory &)
282 -> traffic_simulator_msgs::msg::PolylineTrajectory;
Definition: constants.hpp:21
auto toProtobufMessage(const traffic_simulator_msgs::msg::Vertex &) -> traffic_simulator_msgs::Vertex
Definition: conversions.cpp:601
void toProto(const geometry_msgs::msg::Point &p, geometry_msgs::Point &proto)
Definition: conversions.cpp:22
DEFINE_CONVERSION(autoware_control_msgs, Lateral)
void toMsg(const geometry_msgs::Point &proto, geometry_msgs::msg::Point &p)
Definition: conversions.cpp:29
auto toROS2Message(const traffic_simulator_msgs::Vertex &) -> traffic_simulator_msgs::msg::Vertex
Definition: conversions.cpp:610
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:62
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:70
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:23
std::string string
Definition: junit5.hpp:26
Definition: conversions.hpp:57
Proto toProto(const zmq::message_t &msg)
Definition: conversions.hpp:70
zmq::message_t toZMQ(const Proto &proto)
Definition: conversions.hpp:59
traffic_simulator_msgs::EntitySubtype EntitySubtype
Definition: helper_functions.hpp:30
traffic_simulator_msgs::EntityStatus EntityStatus
Definition: helper_functions.hpp:32
traffic_simulator_msgs::EntityType EntityType
Definition: helper_functions.hpp:31
traffic_simulator::TrafficLight TrafficLight
Definition: test_traffic_light.cpp:24