24 std::shared_ptr<FactoryInterface>
26 const std::string & ros_type_name,
27 const std::string & ign_type_name)
31 (ros_type_name ==
"std_msgs/Bool" || ros_type_name ==
"") &&
32 ign_type_name ==
"ignition.msgs.Boolean")
34 return std::make_shared<
37 ignition::msgs::Boolean
39 >(
"std_msgs/Bool", ign_type_name);
42 (ros_type_name ==
"std_msgs/ColorRGBA" || ros_type_name ==
"") &&
43 ign_type_name ==
"ignition.msgs.Color")
45 return std::make_shared<
50 >(
"std_msgs/ColorRGBA", ign_type_name);
53 (ros_type_name ==
"std_msgs/Empty" || ros_type_name ==
"") &&
54 ign_type_name ==
"ignition.msgs.Empty")
56 return std::make_shared<
61 >(
"std_msgs/Empty", ign_type_name);
64 (ros_type_name ==
"std_msgs/Int32" || ros_type_name ==
"") &&
65 ign_type_name ==
"ignition.msgs.Int32")
67 return std::make_shared<
72 >(
"std_msgs/Int32", ign_type_name);
75 (ros_type_name ==
"std_msgs/Float32" || ros_type_name ==
"") &&
76 ign_type_name ==
"ignition.msgs.Float")
78 return std::make_shared<
83 >(
"std_msgs/Float32", ign_type_name);
86 (ros_type_name ==
"std_msgs/Float64" || ros_type_name ==
"") &&
87 ign_type_name ==
"ignition.msgs.Double")
89 return std::make_shared<
92 ignition::msgs::Double
94 >(
"std_msgs/Float64", ign_type_name);
97 (ros_type_name ==
"std_msgs/Header" || ros_type_name ==
"") &&
98 ign_type_name ==
"ignition.msgs.Header")
100 return std::make_shared<
103 ignition::msgs::Header
105 >(
"std_msgs/Header", ign_type_name);
108 (ros_type_name ==
"std_msgs/String" || ros_type_name ==
"") &&
109 ign_type_name ==
"ignition.msgs.StringMsg")
111 return std::make_shared<
114 ignition::msgs::StringMsg
116 >(
"std_msgs/String", ign_type_name);
119 (ros_type_name ==
"geometry_msgs/Quaternion" || ros_type_name ==
"") &&
120 ign_type_name ==
"ignition.msgs.Quaternion")
122 return std::make_shared<
124 geometry_msgs::Quaternion,
125 ignition::msgs::Quaternion
127 >(
"geometry_msgs/Quaternion", ign_type_name);
130 (ros_type_name ==
"rosgraph_msgs/Clock" || ros_type_name ==
"") &&
131 ign_type_name ==
"ignition.msgs.Clock")
133 return std::make_shared<
135 rosgraph_msgs::Clock,
136 ignition::msgs::Clock
138 >(
"rosgraph_msgs/Clock", ign_type_name);
141 (ros_type_name ==
"geometry_msgs/Vector3" || ros_type_name ==
"") &&
142 ign_type_name ==
"ignition.msgs.Vector3d")
144 return std::make_shared<
146 geometry_msgs::Vector3,
147 ignition::msgs::Vector3d
149 >(
"geometry_msgs/Vector3", ign_type_name);
152 (ros_type_name ==
"geometry_msgs/Point" || ros_type_name ==
"") &&
153 ign_type_name ==
"ignition.msgs.Vector3d")
155 return std::make_shared<
157 geometry_msgs::Point,
158 ignition::msgs::Vector3d
160 >(
"geometry_msgs/Point", ign_type_name);
163 (ros_type_name ==
"geometry_msgs/Pose" || ros_type_name ==
"") &&
164 ign_type_name ==
"ignition.msgs.Pose")
166 return std::make_shared<
171 >(
"geometry_msgs/Pose", ign_type_name);
174 (ros_type_name ==
"geometry_msgs/PoseArray" || ros_type_name ==
"") &&
175 ign_type_name ==
"ignition.msgs.Pose_V")
177 return std::make_shared<
179 geometry_msgs::PoseArray,
180 ignition::msgs::Pose_V
182 >(
"geometry_msgs/PoseArray", ign_type_name);
185 (ros_type_name ==
"geometry_msgs/PoseStamped" || ros_type_name ==
"") &&
186 ign_type_name ==
"ignition.msgs.Pose")
188 return std::make_shared<
190 geometry_msgs::PoseStamped,
193 >(
"geometry_msgs/PoseStamped", ign_type_name);
196 (ros_type_name ==
"geometry_msgs/Transform" || ros_type_name ==
"") &&
197 ign_type_name ==
"ignition.msgs.Pose")
199 return std::make_shared<
201 geometry_msgs::Transform,
204 >(
"geometry_msgs/Transform", ign_type_name);
207 (ros_type_name ==
"geometry_msgs/TransformStamped" || ros_type_name ==
"") &&
208 ign_type_name ==
"ignition.msgs.Pose")
210 return std::make_shared<
212 geometry_msgs::TransformStamped,
215 >(
"geometry_msgs/TransformStamped", ign_type_name);
218 (ros_type_name ==
"tf2_msgs/TFMessage" || ros_type_name ==
"") &&
219 ign_type_name ==
"ignition.msgs.Pose_V")
221 return std::make_shared<
224 ignition::msgs::Pose_V
226 >(
"tf2_msgs/TFMessage", ign_type_name);
229 (ros_type_name ==
"geometry_msgs/Twist" || ros_type_name ==
"") &&
230 ign_type_name ==
"ignition.msgs.Twist")
232 return std::make_shared<
234 geometry_msgs::Twist,
235 ignition::msgs::Twist
237 >(
"geometry_msgs/Twist", ign_type_name);
251 (ros_type_name ==
"nav_msgs/OccupancyGrid" || ros_type_name ==
"") &&
252 ign_type_name ==
"ignition.msgs.OccupancyGrid")
254 return std::make_shared<
256 nav_msgs::OccupancyGrid,
257 ignition::msgs::OccupancyGrid
259 >(
"nav_msgs/OccupancyGrid", ign_type_name);
262 (ros_type_name ==
"nav_msgs/Odometry" || ros_type_name ==
"") &&
263 ign_type_name ==
"ignition.msgs.Odometry")
265 return std::make_shared<
268 ignition::msgs::Odometry
270 >(
"nav_msgs/Odometry", ign_type_name);
273 (ros_type_name ==
"sensor_msgs/FluidPressure" || ros_type_name ==
"") &&
274 ign_type_name ==
"ignition.msgs.FluidPressure")
276 return std::make_shared<
278 sensor_msgs::FluidPressure,
279 ignition::msgs::FluidPressure
281 >(
"sensor_msgs/FluidPressure", ign_type_name);
284 (ros_type_name ==
"sensor_msgs/Image" || ros_type_name ==
"") &&
285 ign_type_name ==
"ignition.msgs.Image")
287 return std::make_shared<
290 ignition::msgs::Image
292 >(
"sensor_msgs/Image", ign_type_name);
295 (ros_type_name ==
"sensor_msgs/CameraInfo" || ros_type_name ==
"") &&
296 ign_type_name ==
"ignition.msgs.CameraInfo")
298 return std::make_shared<
300 sensor_msgs::CameraInfo,
301 ignition::msgs::CameraInfo
303 >(
"sensor_msgs/CameraInfo", ign_type_name);
306 (ros_type_name ==
"sensor_msgs/Imu" || ros_type_name ==
"") &&
307 ign_type_name ==
"ignition.msgs.IMU")
309 return std::make_shared<
314 >(
"sensor_msgs/Imu", ign_type_name);
317 (ros_type_name ==
"sensor_msgs/JointState" || ros_type_name ==
"") &&
318 ign_type_name ==
"ignition.msgs.Model")
320 return std::make_shared<
322 sensor_msgs::JointState,
323 ignition::msgs::Model
325 >(
"sensor_msgs/JointState", ign_type_name);
328 (ros_type_name ==
"sensor_msgs/LaserScan" || ros_type_name ==
"") &&
329 ign_type_name ==
"ignition.msgs.LaserScan")
331 return std::make_shared<
333 sensor_msgs::LaserScan,
334 ignition::msgs::LaserScan
336 >(
"sensor_msgs/LaserScan", ign_type_name);
339 (ros_type_name ==
"sensor_msgs/MagneticField" || ros_type_name ==
"") &&
340 ign_type_name ==
"ignition.msgs.Magnetometer")
342 return std::make_shared<
344 sensor_msgs::MagneticField,
345 ignition::msgs::Magnetometer
347 >(
"sensor_msgs/Magnetometer", ign_type_name);
350 (ros_type_name ==
"sensor_msgs/NavSatFix" || ros_type_name ==
"") &&
351 ign_type_name ==
"ignition.msgs.NavSat")
353 return std::make_shared<
355 sensor_msgs::NavSatFix,
356 ignition::msgs::NavSat
358 >(
"sensor_msgs/NavSatFix", ign_type_name);
361 (ros_type_name ==
"sensor_msgs/PointCloud2" || ros_type_name ==
"") &&
362 ign_type_name ==
"ignition.msgs.PointCloudPacked")
364 return std::make_shared<
366 sensor_msgs::PointCloud2,
367 ignition::msgs::PointCloudPacked
369 >(
"sensor_msgs/PointCloud2", ign_type_name);
372 (ros_type_name ==
"sensor_msgs/BatteryState" || ros_type_name ==
"") &&
373 ign_type_name ==
"ignition.msgs.BatteryState")
375 return std::make_shared<
377 sensor_msgs::BatteryState,
378 ignition::msgs::BatteryState
380 >(
"sensor_msgs/BatteryState", ign_type_name);
383 (ros_type_name ==
"visualization_msgs/Marker" || ros_type_name ==
"") &&
384 ign_type_name ==
"ignition.msgs.Marker")
386 return std::make_shared<
388 visualization_msgs::Marker,
389 ignition::msgs::Marker
391 >(
"visualization_msgs/Marker", ign_type_name);
394 (ros_type_name ==
"visualization_msgs/MarkerArray" || ros_type_name ==
"") &&
395 ign_type_name ==
"ignition.msgs.Marker_V")
397 return std::make_shared<
399 visualization_msgs::MarkerArray,
400 ignition::msgs::Marker_V
402 >(
"visualization_msgs/MarkerArray", ign_type_name);
404 return std::shared_ptr<FactoryInterface>();
407 std::shared_ptr<FactoryInterface>
409 const std::string & ign_type_name)
411 std::shared_ptr<FactoryInterface> factory;
416 throw std::runtime_error(
"No template specialization for the pair");
426 ignition::msgs::Boolean
428 const std_msgs::Bool & ros_msg,
429 ignition::msgs::Boolean & ign_msg)
438 ignition::msgs::Boolean
440 const ignition::msgs::Boolean & ign_msg,
441 std_msgs::Bool & ros_msg)
450 ignition::msgs::Color
452 const std_msgs::ColorRGBA & ros_msg,
453 ignition::msgs::Color & ign_msg)
462 ignition::msgs::Color
464 const ignition::msgs::Color & ign_msg,
465 std_msgs::ColorRGBA & ros_msg)
474 ignition::msgs::Empty
476 const std_msgs::Empty & ros_msg,
477 ignition::msgs::Empty & ign_msg)
486 ignition::msgs::Empty
488 const ignition::msgs::Empty & ign_msg,
489 std_msgs::Empty & ros_msg)
498 ignition::msgs::Int32
500 const std_msgs::Int32 & ros_msg,
501 ignition::msgs::Int32 & ign_msg)
510 ignition::msgs::Int32
512 const ignition::msgs::Int32 & ign_msg,
513 std_msgs::Int32 & ros_msg)
522 ignition::msgs::Float
524 const std_msgs::Float32 & ros_msg,
525 ignition::msgs::Float & ign_msg)
534 ignition::msgs::Float
536 const ignition::msgs::Float & ign_msg,
537 std_msgs::Float32 & ros_msg)
546 ignition::msgs::Double
548 const std_msgs::Float64 & ros_msg,
549 ignition::msgs::Double & ign_msg)
558 ignition::msgs::Double
560 const ignition::msgs::Double & ign_msg,
561 std_msgs::Float64 & ros_msg)
570 ignition::msgs::Header
572 const std_msgs::Header & ros_msg,
573 ignition::msgs::Header & ign_msg)
582 ignition::msgs::Header
584 const ignition::msgs::Header & ign_msg,
585 std_msgs::Header & ros_msg)
594 ignition::msgs::StringMsg
596 const std_msgs::String & ros_msg,
597 ignition::msgs::StringMsg & ign_msg)
606 ignition::msgs::StringMsg
608 const ignition::msgs::StringMsg & ign_msg,
609 std_msgs::String & ros_msg)
618 rosgraph_msgs::Clock,
619 ignition::msgs::Clock
621 const rosgraph_msgs::Clock & ros_msg,
622 ignition::msgs::Clock & ign_msg)
630 rosgraph_msgs::Clock,
631 ignition::msgs::Clock
633 const ignition::msgs::Clock & ign_msg,
634 rosgraph_msgs::Clock & ros_msg)
643 geometry_msgs::Quaternion,
644 ignition::msgs::Quaternion
646 const geometry_msgs::Quaternion & ros_msg,
647 ignition::msgs::Quaternion & ign_msg)
655 geometry_msgs::Quaternion,
656 ignition::msgs::Quaternion
658 const ignition::msgs::Quaternion & ign_msg,
659 geometry_msgs::Quaternion & ros_msg)
667 geometry_msgs::Vector3,
668 ignition::msgs::Vector3d
670 const geometry_msgs::Vector3 & ros_msg,
671 ignition::msgs::Vector3d & ign_msg)
679 geometry_msgs::Vector3,
680 ignition::msgs::Vector3d
682 const ignition::msgs::Vector3d & ign_msg,
683 geometry_msgs::Vector3 & ros_msg)
691 geometry_msgs::Point,
692 ignition::msgs::Vector3d
694 const geometry_msgs::Point & ros_msg,
695 ignition::msgs::Vector3d & ign_msg)
703 geometry_msgs::Point,
704 ignition::msgs::Vector3d
706 const ignition::msgs::Vector3d & ign_msg,
707 geometry_msgs::Point & ros_msg)
718 const geometry_msgs::Pose & ros_msg,
719 ignition::msgs::Pose & ign_msg)
730 const ignition::msgs::Pose & ign_msg,
731 geometry_msgs::Pose & ros_msg)
739 geometry_msgs::PoseArray,
740 ignition::msgs::Pose_V
742 const geometry_msgs::PoseArray & ros_msg,
743 ignition::msgs::Pose_V & ign_msg)
751 geometry_msgs::PoseArray,
752 ignition::msgs::Pose_V
754 const ignition::msgs::Pose_V & ign_msg,
755 geometry_msgs::PoseArray & ros_msg)
763 geometry_msgs::PoseStamped,
766 const geometry_msgs::PoseStamped & ros_msg,
767 ignition::msgs::Pose & ign_msg)
775 geometry_msgs::PoseStamped,
778 const ignition::msgs::Pose & ign_msg,
779 geometry_msgs::PoseStamped & ros_msg)
787 geometry_msgs::Transform,
790 const geometry_msgs::Transform & ros_msg,
791 ignition::msgs::Pose & ign_msg)
799 geometry_msgs::Transform,
802 const ignition::msgs::Pose & ign_msg,
803 geometry_msgs::Transform & ros_msg)
811 geometry_msgs::TransformStamped,
814 const geometry_msgs::TransformStamped & ros_msg,
815 ignition::msgs::Pose & ign_msg)
823 geometry_msgs::TransformStamped,
826 const ignition::msgs::Pose & ign_msg,
827 geometry_msgs::TransformStamped & ros_msg)
836 ignition::msgs::Pose_V
838 const tf2_msgs::TFMessage & ros_msg,
839 ignition::msgs::Pose_V & ign_msg)
848 ignition::msgs::Pose_V
850 const ignition::msgs::Pose_V & ign_msg,
851 tf2_msgs::TFMessage & ros_msg)
859 geometry_msgs::Twist,
860 ignition::msgs::Twist
862 const geometry_msgs::Twist & ros_msg,
863 ignition::msgs::Twist & ign_msg)
871 geometry_msgs::Twist,
872 ignition::msgs::Twist
874 const ignition::msgs::Twist & ign_msg,
875 geometry_msgs::Twist & ros_msg)
909 nav_msgs::OccupancyGrid,
910 ignition::msgs::OccupancyGrid
912 const nav_msgs::OccupancyGrid & ros_msg,
913 ignition::msgs::OccupancyGrid & ign_msg)
921 nav_msgs::OccupancyGrid,
922 ignition::msgs::OccupancyGrid
924 const ignition::msgs::OccupancyGrid & ign_msg,
925 nav_msgs::OccupancyGrid & ros_msg)
934 ignition::msgs::Odometry
936 const nav_msgs::Odometry & ros_msg,
937 ignition::msgs::Odometry & ign_msg)
946 ignition::msgs::Odometry
948 const ignition::msgs::Odometry & ign_msg,
949 nav_msgs::Odometry & ros_msg)
958 sensor_msgs::FluidPressure,
959 ignition::msgs::FluidPressure
961 const sensor_msgs::FluidPressure & ros_msg,
962 ignition::msgs::FluidPressure & ign_msg)
970 sensor_msgs::FluidPressure,
971 ignition::msgs::FluidPressure
973 const ignition::msgs::FluidPressure & ign_msg,
974 sensor_msgs::FluidPressure & ros_msg)
983 ignition::msgs::Image
985 const sensor_msgs::Image & ros_msg,
986 ignition::msgs::Image & ign_msg)
995 ignition::msgs::Image
997 const ignition::msgs::Image & ign_msg,
998 sensor_msgs::Image & ros_msg)
1006 sensor_msgs::CameraInfo,
1007 ignition::msgs::CameraInfo
1009 const sensor_msgs::CameraInfo & ros_msg,
1010 ignition::msgs::CameraInfo & ign_msg)
1018 sensor_msgs::CameraInfo,
1019 ignition::msgs::CameraInfo
1021 const ignition::msgs::CameraInfo & ign_msg,
1022 sensor_msgs::CameraInfo & ros_msg)
1033 const sensor_msgs::Imu & ros_msg,
1034 ignition::msgs::IMU & ign_msg)
1045 const ignition::msgs::IMU & ign_msg,
1046 sensor_msgs::Imu & ros_msg)
1054 sensor_msgs::JointState,
1055 ignition::msgs::Model
1057 const sensor_msgs::JointState & ros_msg,
1058 ignition::msgs::Model & ign_msg)
1066 sensor_msgs::JointState,
1067 ignition::msgs::Model
1069 const ignition::msgs::Model & ign_msg,
1070 sensor_msgs::JointState & ros_msg)
1078 sensor_msgs::LaserScan,
1079 ignition::msgs::LaserScan
1081 const sensor_msgs::LaserScan & ros_msg,
1082 ignition::msgs::LaserScan & ign_msg)
1090 sensor_msgs::LaserScan,
1091 ignition::msgs::LaserScan
1093 const ignition::msgs::LaserScan & ign_msg,
1094 sensor_msgs::LaserScan & ros_msg)
1102 sensor_msgs::MagneticField,
1103 ignition::msgs::Magnetometer
1105 const sensor_msgs::MagneticField & ros_msg,
1106 ignition::msgs::Magnetometer & ign_msg)
1114 sensor_msgs::MagneticField,
1115 ignition::msgs::Magnetometer
1117 const ignition::msgs::Magnetometer & ign_msg,
1118 sensor_msgs::MagneticField & ros_msg)
1126 sensor_msgs::NavSatFix,
1127 ignition::msgs::NavSat
1129 const sensor_msgs::NavSatFix & ros_msg,
1130 ignition::msgs::NavSat & ign_msg)
1138 sensor_msgs::NavSatFix,
1139 ignition::msgs::NavSat
1141 const ignition::msgs::NavSat & ign_msg,
1142 sensor_msgs::NavSatFix & ros_msg)
1150 sensor_msgs::PointCloud2,
1151 ignition::msgs::PointCloudPacked
1153 const sensor_msgs::PointCloud2 & ros_msg,
1154 ignition::msgs::PointCloudPacked & ign_msg)
1162 sensor_msgs::PointCloud2,
1163 ignition::msgs::PointCloudPacked
1165 const ignition::msgs::PointCloudPacked & ign_msg,
1166 sensor_msgs::PointCloud2 & ros_msg)
1174 sensor_msgs::BatteryState,
1175 ignition::msgs::BatteryState
1177 const sensor_msgs::BatteryState & ros_msg,
1178 ignition::msgs::BatteryState & ign_msg)
1186 sensor_msgs::BatteryState,
1187 ignition::msgs::BatteryState
1189 const ignition::msgs::BatteryState & ign_msg,
1190 sensor_msgs::BatteryState & ros_msg)
1198 visualization_msgs::Marker,
1199 ignition::msgs::Marker
1201 const visualization_msgs::Marker & ros_msg,
1202 ignition::msgs::Marker & ign_msg)
1210 visualization_msgs::Marker,
1211 ignition::msgs::Marker
1213 const ignition::msgs::Marker & ign_msg,
1214 visualization_msgs::Marker & ros_msg)
1222 visualization_msgs::MarkerArray,
1223 ignition::msgs::Marker_V
1225 const visualization_msgs::MarkerArray & ros_msg,
1226 ignition::msgs::Marker_V & ign_msg)
1234 visualization_msgs::MarkerArray,
1235 ignition::msgs::Marker_V
1237 const ignition::msgs::Marker_V & ign_msg,
1238 visualization_msgs::MarkerArray & ros_msg)