15 #ifndef ROS_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_
16 #define ROS_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_
19 #include <geometry_msgs/Quaternion.h>
20 #include <geometry_msgs/Point.h>
21 #include <geometry_msgs/Pose.h>
22 #include <geometry_msgs/PoseArray.h>
23 #include <geometry_msgs/PoseStamped.h>
24 #include <geometry_msgs/Vector3.h>
25 #include <rosgraph_msgs/Clock.h>
26 #include <geometry_msgs/Transform.h>
27 #include <geometry_msgs/TransformStamped.h>
28 #include <geometry_msgs/Twist.h>
30 #include <nav_msgs/OccupancyGrid.h>
31 #include <nav_msgs/Odometry.h>
32 #include <sensor_msgs/BatteryState.h>
33 #include <sensor_msgs/CameraInfo.h>
34 #include <sensor_msgs/FluidPressure.h>
35 #include <sensor_msgs/Image.h>
36 #include <sensor_msgs/Imu.h>
37 #include <sensor_msgs/JointState.h>
38 #include <sensor_msgs/LaserScan.h>
39 #include <sensor_msgs/MagneticField.h>
40 #include <sensor_msgs/NavSatFix.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <std_msgs/Bool.h>
43 #include <std_msgs/ColorRGBA.h>
44 #include <std_msgs/Empty.h>
45 #include <std_msgs/Float32.h>
46 #include <std_msgs/Float64.h>
47 #include <std_msgs/Header.h>
48 #include <std_msgs/Int32.h>
49 #include <std_msgs/String.h>
50 #include <tf2_msgs/TFMessage.h>
51 #include <visualization_msgs/Marker.h>
52 #include <visualization_msgs/MarkerArray.h>
55 #include <ignition/msgs.hh>
66 const std_msgs::Bool & ros_msg,
67 ignition::msgs::Boolean & ign_msg);
72 const ignition::msgs::Boolean & ign_msg,
73 std_msgs::Bool & ros_msg);
78 const std_msgs::ColorRGBA & ros_msg,
79 ignition::msgs::Color & ign_msg);
84 const ignition::msgs::Color & ign_msg,
85 std_msgs::ColorRGBA & ros_msg);
90 const std_msgs::Empty & ros_msg,
91 ignition::msgs::Empty & ign_msg);
96 const ignition::msgs::Empty & ign_msg,
97 std_msgs::Empty & ros_msg);
102 const std_msgs::Int32 & ros_msg,
103 ignition::msgs::Int32 & ign_msg);
108 const ignition::msgs::Int32 & ign_msg,
109 std_msgs::Int32 & ros_msg);
114 const std_msgs::Float32 & ros_msg,
115 ignition::msgs::Float & ign_msg);
120 const ignition::msgs::Float & ign_msg,
121 std_msgs::Float32 & ros_msg);
126 const std_msgs::Float64 & ros_msg,
127 ignition::msgs::Double & ign_msg);
132 const ignition::msgs::Double & ign_msg,
133 std_msgs::Float64 & ros_msg);
138 const std_msgs::Header & ros_msg,
139 ignition::msgs::Header & ign_msg);
144 const ignition::msgs::Header & ign_msg,
145 std_msgs::Header & ros_msg);
150 const std_msgs::String & ros_msg,
151 ignition::msgs::StringMsg & ign_msg);
156 const ignition::msgs::StringMsg & ign_msg,
157 std_msgs::String & ros_msg);
163 const ignition::msgs::Clock & ign_msg,
164 rosgraph_msgs::Clock & ros_msg);
169 const rosgraph_msgs::Clock & ros_msg,
170 ignition::msgs::Clock & ign_msg);
176 const geometry_msgs::Quaternion & ros_msg,
177 ignition::msgs::Quaternion & ign_msg);
182 const ignition::msgs::Quaternion & ign_msg,
183 geometry_msgs::Quaternion & ros_msg);
188 const geometry_msgs::Vector3 & ros_msg,
189 ignition::msgs::Vector3d & ign_msg);
194 const ignition::msgs::Vector3d & ign_msg,
195 geometry_msgs::Vector3 & ros_msg);
200 const geometry_msgs::Point & ros_msg,
201 ignition::msgs::Vector3d & ign_msg);
206 const ignition::msgs::Vector3d & ign_msg,
207 geometry_msgs::Point & ros_msg);
212 const geometry_msgs::Pose & ros_msg,
213 ignition::msgs::Pose & ign_msg);
218 const ignition::msgs::Pose & ign_msg,
219 geometry_msgs::Pose & ros_msg);
224 const geometry_msgs::PoseArray & ros_msg,
225 ignition::msgs::Pose_V & ign_msg);
230 const ignition::msgs::Pose_V & ign_msg,
231 geometry_msgs::PoseArray & ros_msg);
236 const geometry_msgs::PoseStamped & ros_msg,
237 ignition::msgs::Pose & ign_msg);
242 const ignition::msgs::Pose & ign_msg,
243 geometry_msgs::PoseStamped & ros_msg);
248 const geometry_msgs::Transform & ros_msg,
249 ignition::msgs::Pose & ign_msg);
254 const ignition::msgs::Pose & ign_msg,
255 geometry_msgs::Transform & ros_msg);
260 const geometry_msgs::TransformStamped & ros_msg,
261 ignition::msgs::Pose & ign_msg);
266 const ignition::msgs::Pose & ign_msg,
267 geometry_msgs::TransformStamped & ros_msg);
272 const tf2_msgs::TFMessage & ros_msg,
273 ignition::msgs::Pose_V & ign_msg);
278 const ignition::msgs::Pose_V & ign_msg,
279 tf2_msgs::TFMessage & ros_msg);
284 const geometry_msgs::Twist & ros_msg,
285 ignition::msgs::Twist & ign_msg);
290 const ignition::msgs::Twist & ign_msg,
291 geometry_msgs::Twist & ros_msg);
310 const nav_msgs::OccupancyGrid & ros_msg,
311 ignition::msgs::OccupancyGrid & ign_msg);
316 const ignition::msgs::OccupancyGrid& ign_msg,
317 nav_msgs::OccupancyGrid & ros_msg);
322 const nav_msgs::Odometry & ros_msg,
323 ignition::msgs::Odometry & ign_msg);
328 const ignition::msgs::Odometry & ign_msg,
329 nav_msgs::Odometry & ros_msg);
335 const sensor_msgs::FluidPressure & ros_msg,
336 ignition::msgs::FluidPressure & ign_msg);
341 const ignition::msgs::FluidPressure & ign_msg,
342 sensor_msgs::FluidPressure & ros_msg);
347 const sensor_msgs::Image & ros_msg,
348 ignition::msgs::Image & ign_msg);
353 const ignition::msgs::Image & ign_msg,
354 sensor_msgs::Image & ros_msg);
359 const sensor_msgs::CameraInfo & ros_msg,
360 ignition::msgs::CameraInfo & ign_msg);
365 const ignition::msgs::CameraInfo & ign_msg,
366 sensor_msgs::CameraInfo & ros_msg);
371 const sensor_msgs::Imu & ros_msg,
372 ignition::msgs::IMU & ign_msg);
377 const ignition::msgs::IMU & ign_msg,
378 sensor_msgs::Imu & ros_msg);
383 const sensor_msgs::JointState & ros_msg,
384 ignition::msgs::Model & ign_msg);
389 const ignition::msgs::Model & ign_msg,
390 sensor_msgs::JointState & ros_msg);
395 const sensor_msgs::LaserScan & ros_msg,
396 ignition::msgs::LaserScan & ign_msg);
401 const ignition::msgs::LaserScan & ign_msg,
402 sensor_msgs::LaserScan & ros_msg);
407 const sensor_msgs::MagneticField & ros_msg,
408 ignition::msgs::Magnetometer & ign_msg);
413 const ignition::msgs::Magnetometer & ign_msg,
414 sensor_msgs::MagneticField & ros_msg);
419 const sensor_msgs::NavSatFix & ros_msg,
420 ignition::msgs::NavSat & ign_msg);
425 const ignition::msgs::NavSat & ign_msg,
426 sensor_msgs::NavSatFix & ros_msg);
431 const sensor_msgs::PointCloud2 & ros_msg,
432 ignition::msgs::PointCloudPacked & ign_msg);
437 const ignition::msgs::PointCloudPacked & ign_msg,
438 sensor_msgs::PointCloud2 & ros_msg);
443 const sensor_msgs::BatteryState & ros_msg,
444 ignition::msgs::BatteryState & ign_msg);
449 const ignition::msgs::BatteryState & ign_msg,
450 sensor_msgs::BatteryState & ros_msg);
455 const visualization_msgs::Marker & ros_msg,
456 ignition::msgs::Marker & ign_msg);
461 const ignition::msgs::Marker & ign_msg,
462 visualization_msgs::Marker & ros_msg);
467 const visualization_msgs::MarkerArray & ros_msg,
468 ignition::msgs::Marker_V & ign_msg);
473 const ignition::msgs::Marker_V & ign_msg,
474 visualization_msgs::MarkerArray & ros_msg);
478 #endif // ROS_IGN_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_