factories.cpp
Go to the documentation of this file.
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <memory>
16 #include <string>
17 
18 #include "factories.hpp"
20 
21 namespace ros_ign_bridge
22 {
23 
24 std::shared_ptr<FactoryInterface>
26  const std::string & ros_type_name,
27  const std::string & ign_type_name)
28 {
29  // mapping from string to specialized template
30  if (
31  (ros_type_name == "std_msgs/Bool" || ros_type_name == "") &&
32  ign_type_name == "ignition.msgs.Boolean")
33  {
34  return std::make_shared<
35  Factory<
36  std_msgs::Bool,
37  ignition::msgs::Boolean
38  >
39  >("std_msgs/Bool", ign_type_name);
40  }
41  if (
42  (ros_type_name == "std_msgs/ColorRGBA" || ros_type_name == "") &&
43  ign_type_name == "ignition.msgs.Color")
44  {
45  return std::make_shared<
46  Factory<
47  std_msgs::ColorRGBA,
48  ignition::msgs::Color
49  >
50  >("std_msgs/ColorRGBA", ign_type_name);
51  }
52  if (
53  (ros_type_name == "std_msgs/Empty" || ros_type_name == "") &&
54  ign_type_name == "ignition.msgs.Empty")
55  {
56  return std::make_shared<
57  Factory<
58  std_msgs::Empty,
59  ignition::msgs::Empty
60  >
61  >("std_msgs/Empty", ign_type_name);
62  }
63  if (
64  (ros_type_name == "std_msgs/Int32" || ros_type_name == "") &&
65  ign_type_name == "ignition.msgs.Int32")
66  {
67  return std::make_shared<
68  Factory<
69  std_msgs::Int32,
70  ignition::msgs::Int32
71  >
72  >("std_msgs/Int32", ign_type_name);
73  }
74  if (
75  (ros_type_name == "std_msgs/Float32" || ros_type_name == "") &&
76  ign_type_name == "ignition.msgs.Float")
77  {
78  return std::make_shared<
79  Factory<
80  std_msgs::Float32,
81  ignition::msgs::Float
82  >
83  >("std_msgs/Float32", ign_type_name);
84  }
85  if (
86  (ros_type_name == "std_msgs/Float64" || ros_type_name == "") &&
87  ign_type_name == "ignition.msgs.Double")
88  {
89  return std::make_shared<
90  Factory<
91  std_msgs::Float64,
92  ignition::msgs::Double
93  >
94  >("std_msgs/Float64", ign_type_name);
95  }
96  if (
97  (ros_type_name == "std_msgs/Header" || ros_type_name == "") &&
98  ign_type_name == "ignition.msgs.Header")
99  {
100  return std::make_shared<
101  Factory<
102  std_msgs::Header,
103  ignition::msgs::Header
104  >
105  >("std_msgs/Header", ign_type_name);
106  }
107  if (
108  (ros_type_name == "std_msgs/String" || ros_type_name == "") &&
109  ign_type_name == "ignition.msgs.StringMsg")
110  {
111  return std::make_shared<
112  Factory<
113  std_msgs::String,
114  ignition::msgs::StringMsg
115  >
116  >("std_msgs/String", ign_type_name);
117  }
118  if (
119  (ros_type_name == "geometry_msgs/Quaternion" || ros_type_name == "") &&
120  ign_type_name == "ignition.msgs.Quaternion")
121  {
122  return std::make_shared<
123  Factory<
124  geometry_msgs::Quaternion,
125  ignition::msgs::Quaternion
126  >
127  >("geometry_msgs/Quaternion", ign_type_name);
128  }
129  if (
130  (ros_type_name == "rosgraph_msgs/Clock" || ros_type_name == "") &&
131  ign_type_name == "ignition.msgs.Clock")
132  {
133  return std::make_shared<
134  Factory<
135  rosgraph_msgs::Clock,
136  ignition::msgs::Clock
137  >
138  >("rosgraph_msgs/Clock", ign_type_name);
139  }
140  if (
141  (ros_type_name == "geometry_msgs/Vector3" || ros_type_name == "") &&
142  ign_type_name == "ignition.msgs.Vector3d")
143  {
144  return std::make_shared<
145  Factory<
146  geometry_msgs::Vector3,
147  ignition::msgs::Vector3d
148  >
149  >("geometry_msgs/Vector3", ign_type_name);
150  }
151  if (
152  (ros_type_name == "geometry_msgs/Point" || ros_type_name == "") &&
153  ign_type_name == "ignition.msgs.Vector3d")
154  {
155  return std::make_shared<
156  Factory<
157  geometry_msgs::Point,
158  ignition::msgs::Vector3d
159  >
160  >("geometry_msgs/Point", ign_type_name);
161  }
162  if (
163  (ros_type_name == "geometry_msgs/Pose" || ros_type_name == "") &&
164  ign_type_name == "ignition.msgs.Pose")
165  {
166  return std::make_shared<
167  Factory<
168  geometry_msgs::Pose,
169  ignition::msgs::Pose
170  >
171  >("geometry_msgs/Pose", ign_type_name);
172  }
173  if (
174  (ros_type_name == "geometry_msgs/PoseArray" || ros_type_name == "") &&
175  ign_type_name == "ignition.msgs.Pose_V")
176  {
177  return std::make_shared<
178  Factory<
179  geometry_msgs::PoseArray,
180  ignition::msgs::Pose_V
181  >
182  >("geometry_msgs/PoseArray", ign_type_name);
183  }
184  if (
185  (ros_type_name == "geometry_msgs/PoseStamped" || ros_type_name == "") &&
186  ign_type_name == "ignition.msgs.Pose")
187  {
188  return std::make_shared<
189  Factory<
190  geometry_msgs::PoseStamped,
191  ignition::msgs::Pose
192  >
193  >("geometry_msgs/PoseStamped", ign_type_name);
194  }
195  if (
196  (ros_type_name == "geometry_msgs/Transform" || ros_type_name == "") &&
197  ign_type_name == "ignition.msgs.Pose")
198  {
199  return std::make_shared<
200  Factory<
201  geometry_msgs::Transform,
202  ignition::msgs::Pose
203  >
204  >("geometry_msgs/Transform", ign_type_name);
205  }
206  if (
207  (ros_type_name == "geometry_msgs/TransformStamped" || ros_type_name == "") &&
208  ign_type_name == "ignition.msgs.Pose")
209  {
210  return std::make_shared<
211  Factory<
212  geometry_msgs::TransformStamped,
213  ignition::msgs::Pose
214  >
215  >("geometry_msgs/TransformStamped", ign_type_name);
216  }
217  if (
218  (ros_type_name == "tf2_msgs/TFMessage" || ros_type_name == "") &&
219  ign_type_name == "ignition.msgs.Pose_V")
220  {
221  return std::make_shared<
222  Factory<
223  tf2_msgs::TFMessage,
224  ignition::msgs::Pose_V
225  >
226  >("tf2_msgs/TFMessage", ign_type_name);
227  }
228  if (
229  (ros_type_name == "geometry_msgs/Twist" || ros_type_name == "") &&
230  ign_type_name == "ignition.msgs.Twist")
231  {
232  return std::make_shared<
233  Factory<
234  geometry_msgs::Twist,
235  ignition::msgs::Twist
236  >
237  >("geometry_msgs/Twist", ign_type_name);
238  }
239 // if (
240 // (ros_type_name == "mav_msgs/Actuators" || ros_type_name == "") &&
241 // ign_type_name == "ignition.msgs.Actuators")
242 // {
243 // return std::make_shared<
244 // Factory<
245 // mav_msgs::Actuators,
246 // ignition::msgs::Actuators
247 // >
248 // >("mav_msgs/Actuators", ign_type_name);
249 // }
250  if (
251  (ros_type_name == "nav_msgs/OccupancyGrid" || ros_type_name == "") &&
252  ign_type_name == "ignition.msgs.OccupancyGrid")
253  {
254  return std::make_shared<
255  Factory<
256  nav_msgs::OccupancyGrid,
257  ignition::msgs::OccupancyGrid
258  >
259  >("nav_msgs/OccupancyGrid", ign_type_name);
260  }
261  if (
262  (ros_type_name == "nav_msgs/Odometry" || ros_type_name == "") &&
263  ign_type_name == "ignition.msgs.Odometry")
264  {
265  return std::make_shared<
266  Factory<
267  nav_msgs::Odometry,
268  ignition::msgs::Odometry
269  >
270  >("nav_msgs/Odometry", ign_type_name);
271  }
272  if (
273  (ros_type_name == "sensor_msgs/FluidPressure" || ros_type_name == "") &&
274  ign_type_name == "ignition.msgs.FluidPressure")
275  {
276  return std::make_shared<
277  Factory<
278  sensor_msgs::FluidPressure,
279  ignition::msgs::FluidPressure
280  >
281  >("sensor_msgs/FluidPressure", ign_type_name);
282  }
283  if (
284  (ros_type_name == "sensor_msgs/Image" || ros_type_name == "") &&
285  ign_type_name == "ignition.msgs.Image")
286  {
287  return std::make_shared<
288  Factory<
289  sensor_msgs::Image,
290  ignition::msgs::Image
291  >
292  >("sensor_msgs/Image", ign_type_name);
293  }
294  if (
295  (ros_type_name == "sensor_msgs/CameraInfo" || ros_type_name == "") &&
296  ign_type_name == "ignition.msgs.CameraInfo")
297  {
298  return std::make_shared<
299  Factory<
300  sensor_msgs::CameraInfo,
301  ignition::msgs::CameraInfo
302  >
303  >("sensor_msgs/CameraInfo", ign_type_name);
304  }
305  if (
306  (ros_type_name == "sensor_msgs/Imu" || ros_type_name == "") &&
307  ign_type_name == "ignition.msgs.IMU")
308  {
309  return std::make_shared<
310  Factory<
311  sensor_msgs::Imu,
312  ignition::msgs::IMU
313  >
314  >("sensor_msgs/Imu", ign_type_name);
315  }
316  if (
317  (ros_type_name == "sensor_msgs/JointState" || ros_type_name == "") &&
318  ign_type_name == "ignition.msgs.Model")
319  {
320  return std::make_shared<
321  Factory<
322  sensor_msgs::JointState,
323  ignition::msgs::Model
324  >
325  >("sensor_msgs/JointState", ign_type_name);
326  }
327  if (
328  (ros_type_name == "sensor_msgs/LaserScan" || ros_type_name == "") &&
329  ign_type_name == "ignition.msgs.LaserScan")
330  {
331  return std::make_shared<
332  Factory<
333  sensor_msgs::LaserScan,
334  ignition::msgs::LaserScan
335  >
336  >("sensor_msgs/LaserScan", ign_type_name);
337  }
338  if (
339  (ros_type_name == "sensor_msgs/MagneticField" || ros_type_name == "") &&
340  ign_type_name == "ignition.msgs.Magnetometer")
341  {
342  return std::make_shared<
343  Factory<
344  sensor_msgs::MagneticField,
345  ignition::msgs::Magnetometer
346  >
347  >("sensor_msgs/Magnetometer", ign_type_name);
348  }
349  if (
350  (ros_type_name == "sensor_msgs/NavSatFix" || ros_type_name == "") &&
351  ign_type_name == "ignition.msgs.NavSat")
352  {
353  return std::make_shared<
354  Factory<
355  sensor_msgs::NavSatFix,
356  ignition::msgs::NavSat
357  >
358  >("sensor_msgs/NavSatFix", ign_type_name);
359  }
360  if (
361  (ros_type_name == "sensor_msgs/PointCloud2" || ros_type_name == "") &&
362  ign_type_name == "ignition.msgs.PointCloudPacked")
363  {
364  return std::make_shared<
365  Factory<
366  sensor_msgs::PointCloud2,
367  ignition::msgs::PointCloudPacked
368  >
369  >("sensor_msgs/PointCloud2", ign_type_name);
370  }
371  if (
372  (ros_type_name == "sensor_msgs/BatteryState" || ros_type_name == "") &&
373  ign_type_name == "ignition.msgs.BatteryState")
374  {
375  return std::make_shared<
376  Factory<
377  sensor_msgs::BatteryState,
378  ignition::msgs::BatteryState
379  >
380  >("sensor_msgs/BatteryState", ign_type_name);
381  }
382  if (
383  (ros_type_name == "visualization_msgs/Marker" || ros_type_name == "") &&
384  ign_type_name == "ignition.msgs.Marker")
385  {
386  return std::make_shared<
387  Factory<
388  visualization_msgs::Marker,
389  ignition::msgs::Marker
390  >
391  >("visualization_msgs/Marker", ign_type_name);
392  }
393  if (
394  (ros_type_name == "visualization_msgs/MarkerArray" || ros_type_name == "") &&
395  ign_type_name == "ignition.msgs.Marker_V")
396  {
397  return std::make_shared<
398  Factory<
399  visualization_msgs::MarkerArray,
400  ignition::msgs::Marker_V
401  >
402  >("visualization_msgs/MarkerArray", ign_type_name);
403  }
404  return std::shared_ptr<FactoryInterface>();
405 }
406 
407 std::shared_ptr<FactoryInterface>
408 get_factory(const std::string & ros_type_name,
409  const std::string & ign_type_name)
410 {
411  std::shared_ptr<FactoryInterface> factory;
412  factory = get_factory_impl(ros_type_name, ign_type_name);
413  if (factory)
414  return factory;
415 
416  throw std::runtime_error("No template specialization for the pair");
417 }
418 
419 // conversion functions for available interfaces
420 
421 // std_msgs
422 template<>
423 void
424 Factory<
425  std_msgs::Bool,
426  ignition::msgs::Boolean
428  const std_msgs::Bool & ros_msg,
429  ignition::msgs::Boolean & ign_msg)
430 {
431  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
432 }
433 
434 template<>
435 void
436 Factory<
437  std_msgs::Bool,
438  ignition::msgs::Boolean
440  const ignition::msgs::Boolean & ign_msg,
441  std_msgs::Bool & ros_msg)
442 {
443  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
444 }
445 
446 template<>
447 void
448 Factory<
449  std_msgs::ColorRGBA,
450  ignition::msgs::Color
452  const std_msgs::ColorRGBA & ros_msg,
453  ignition::msgs::Color & ign_msg)
454 {
455  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
456 }
457 
458 template<>
459 void
460 Factory<
461  std_msgs::ColorRGBA,
462  ignition::msgs::Color
464  const ignition::msgs::Color & ign_msg,
465  std_msgs::ColorRGBA & ros_msg)
466 {
467  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
468 }
469 
470 template<>
471 void
472 Factory<
473  std_msgs::Empty,
474  ignition::msgs::Empty
476  const std_msgs::Empty & ros_msg,
477  ignition::msgs::Empty & ign_msg)
478 {
479  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
480 }
481 
482 template<>
483 void
484 Factory<
485  std_msgs::Empty,
486  ignition::msgs::Empty
488  const ignition::msgs::Empty & ign_msg,
489  std_msgs::Empty & ros_msg)
490 {
491  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
492 }
493 
494 template<>
495 void
496 Factory<
497  std_msgs::Int32,
498  ignition::msgs::Int32
500  const std_msgs::Int32 & ros_msg,
501  ignition::msgs::Int32 & ign_msg)
502 {
503  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
504 }
505 
506 template<>
507 void
508 Factory<
509  std_msgs::Int32,
510  ignition::msgs::Int32
512  const ignition::msgs::Int32 & ign_msg,
513  std_msgs::Int32 & ros_msg)
514 {
515  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
516 }
517 
518 template<>
519 void
520 Factory<
521  std_msgs::Float32,
522  ignition::msgs::Float
524  const std_msgs::Float32 & ros_msg,
525  ignition::msgs::Float & ign_msg)
526 {
527  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
528 }
529 
530 template<>
531 void
532 Factory<
533  std_msgs::Float32,
534  ignition::msgs::Float
536  const ignition::msgs::Float & ign_msg,
537  std_msgs::Float32 & ros_msg)
538 {
539  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
540 }
541 
542 template<>
543 void
544 Factory<
545  std_msgs::Float64,
546  ignition::msgs::Double
548  const std_msgs::Float64 & ros_msg,
549  ignition::msgs::Double & ign_msg)
550 {
551  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
552 }
553 
554 template<>
555 void
556 Factory<
557  std_msgs::Float64,
558  ignition::msgs::Double
560  const ignition::msgs::Double & ign_msg,
561  std_msgs::Float64 & ros_msg)
562 {
563  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
564 }
565 
566 template<>
567 void
568 Factory<
569  std_msgs::Header,
570  ignition::msgs::Header
572  const std_msgs::Header & ros_msg,
573  ignition::msgs::Header & ign_msg)
574 {
575  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
576 }
577 
578 template<>
579 void
580 Factory<
581  std_msgs::Header,
582  ignition::msgs::Header
584  const ignition::msgs::Header & ign_msg,
585  std_msgs::Header & ros_msg)
586 {
587  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
588 }
589 
590 template<>
591 void
592 Factory<
593  std_msgs::String,
594  ignition::msgs::StringMsg
596  const std_msgs::String & ros_msg,
597  ignition::msgs::StringMsg & ign_msg)
598 {
599  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
600 }
601 
602 template<>
603 void
604 Factory<
605  std_msgs::String,
606  ignition::msgs::StringMsg
608  const ignition::msgs::StringMsg & ign_msg,
609  std_msgs::String & ros_msg)
610 {
611  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
612 }
613 
614 // rosgraph_msgs
615 template<>
616 void
617 Factory<
618  rosgraph_msgs::Clock,
619  ignition::msgs::Clock
621  const rosgraph_msgs::Clock & ros_msg,
622  ignition::msgs::Clock & ign_msg)
623 {
624  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
625 }
626 
627 template<>
628 void
629 Factory<
630  rosgraph_msgs::Clock,
631  ignition::msgs::Clock
633  const ignition::msgs::Clock & ign_msg,
634  rosgraph_msgs::Clock & ros_msg)
635 {
636  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
637 }
638 
639 // geometry_msgs
640 template<>
641 void
642 Factory<
643  geometry_msgs::Quaternion,
644  ignition::msgs::Quaternion
646  const geometry_msgs::Quaternion & ros_msg,
647  ignition::msgs::Quaternion & ign_msg)
648 {
649  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
650 }
651 
652 template<>
653 void
654 Factory<
655  geometry_msgs::Quaternion,
656  ignition::msgs::Quaternion
658  const ignition::msgs::Quaternion & ign_msg,
659  geometry_msgs::Quaternion & ros_msg)
660 {
661  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
662 }
663 
664 template<>
665 void
666 Factory<
667  geometry_msgs::Vector3,
668  ignition::msgs::Vector3d
670  const geometry_msgs::Vector3 & ros_msg,
671  ignition::msgs::Vector3d & ign_msg)
672 {
673  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
674 }
675 
676 template<>
677 void
678 Factory<
679  geometry_msgs::Vector3,
680  ignition::msgs::Vector3d
682  const ignition::msgs::Vector3d & ign_msg,
683  geometry_msgs::Vector3 & ros_msg)
684 {
685  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
686 }
687 
688 template<>
689 void
690 Factory<
691  geometry_msgs::Point,
692  ignition::msgs::Vector3d
694  const geometry_msgs::Point & ros_msg,
695  ignition::msgs::Vector3d & ign_msg)
696 {
697  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
698 }
699 
700 template<>
701 void
702 Factory<
703  geometry_msgs::Point,
704  ignition::msgs::Vector3d
706  const ignition::msgs::Vector3d & ign_msg,
707  geometry_msgs::Point & ros_msg)
708 {
709  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
710 }
711 
712 template<>
713 void
714 Factory<
715  geometry_msgs::Pose,
716  ignition::msgs::Pose
718  const geometry_msgs::Pose & ros_msg,
719  ignition::msgs::Pose & ign_msg)
720 {
721  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
722 }
723 
724 template<>
725 void
726 Factory<
727  geometry_msgs::Pose,
728  ignition::msgs::Pose
730  const ignition::msgs::Pose & ign_msg,
731  geometry_msgs::Pose & ros_msg)
732 {
733  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
734 }
735 
736 template<>
737 void
738 Factory<
739  geometry_msgs::PoseArray,
740  ignition::msgs::Pose_V
742  const geometry_msgs::PoseArray & ros_msg,
743  ignition::msgs::Pose_V & ign_msg)
744 {
745  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
746 }
747 
748 template<>
749 void
750 Factory<
751  geometry_msgs::PoseArray,
752  ignition::msgs::Pose_V
754  const ignition::msgs::Pose_V & ign_msg,
755  geometry_msgs::PoseArray & ros_msg)
756 {
757  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
758 }
759 
760 template<>
761 void
762 Factory<
763  geometry_msgs::PoseStamped,
764  ignition::msgs::Pose
766  const geometry_msgs::PoseStamped & ros_msg,
767  ignition::msgs::Pose & ign_msg)
768 {
769  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
770 }
771 
772 template<>
773 void
774 Factory<
775  geometry_msgs::PoseStamped,
776  ignition::msgs::Pose
778  const ignition::msgs::Pose & ign_msg,
779  geometry_msgs::PoseStamped & ros_msg)
780 {
781  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
782 }
783 
784 template<>
785 void
786 Factory<
787  geometry_msgs::Transform,
788  ignition::msgs::Pose
790  const geometry_msgs::Transform & ros_msg,
791  ignition::msgs::Pose & ign_msg)
792 {
793  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
794 }
795 
796 template<>
797 void
798 Factory<
799  geometry_msgs::Transform,
800  ignition::msgs::Pose
802  const ignition::msgs::Pose & ign_msg,
803  geometry_msgs::Transform & ros_msg)
804 {
805  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
806 }
807 
808 template<>
809 void
810 Factory<
811  geometry_msgs::TransformStamped,
812  ignition::msgs::Pose
814  const geometry_msgs::TransformStamped & ros_msg,
815  ignition::msgs::Pose & ign_msg)
816 {
817  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
818 }
819 
820 template<>
821 void
822 Factory<
823  geometry_msgs::TransformStamped,
824  ignition::msgs::Pose
826  const ignition::msgs::Pose & ign_msg,
827  geometry_msgs::TransformStamped & ros_msg)
828 {
829  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
830 }
831 
832 template<>
833 void
834 Factory<
835  tf2_msgs::TFMessage,
836  ignition::msgs::Pose_V
838  const tf2_msgs::TFMessage & ros_msg,
839  ignition::msgs::Pose_V & ign_msg)
840 {
841  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
842 }
843 
844 template<>
845 void
846 Factory<
847  tf2_msgs::TFMessage,
848  ignition::msgs::Pose_V
850  const ignition::msgs::Pose_V & ign_msg,
851  tf2_msgs::TFMessage & ros_msg)
852 {
853  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
854 }
855 
856 template<>
857 void
858 Factory<
859  geometry_msgs::Twist,
860  ignition::msgs::Twist
862  const geometry_msgs::Twist & ros_msg,
863  ignition::msgs::Twist & ign_msg)
864 {
865  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
866 }
867 
868 template<>
869 void
870 Factory<
871  geometry_msgs::Twist,
872  ignition::msgs::Twist
874  const ignition::msgs::Twist & ign_msg,
875  geometry_msgs::Twist & ros_msg)
876 {
877  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
878 }
879 
880 // mav_msgs
881 //template<>
882 //void
883 //Factory<
884 // mav_msgs::Actuators,
885 // ignition::msgs::Actuators
886 //>::convert_ros_to_ign(
887 // const mav_msgs::Actuators & ros_msg,
888 // ignition::msgs::Actuators & ign_msg)
889 //{
890 // ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
891 //}
892 //
893 //template<>
894 //void
895 //Factory<
896 // mav_msgs::Actuators,
897 // ignition::msgs::Actuators
898 //>::convert_ign_to_ros(
899 // const ignition::msgs::Actuators & ign_msg,
900 // mav_msgs::Actuators & ros_msg)
901 //{
902 // ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
903 //}
904 
905 // nav_msgs
906 template<>
907 void
908 Factory<
909  nav_msgs::OccupancyGrid,
910  ignition::msgs::OccupancyGrid
912  const nav_msgs::OccupancyGrid & ros_msg,
913  ignition::msgs::OccupancyGrid & ign_msg)
914 {
915  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
916 }
917 
918 template<>
919 void
920 Factory<
921  nav_msgs::OccupancyGrid,
922  ignition::msgs::OccupancyGrid
924  const ignition::msgs::OccupancyGrid & ign_msg,
925  nav_msgs::OccupancyGrid & ros_msg)
926 {
927  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
928 }
929 
930 template<>
931 void
932 Factory<
933  nav_msgs::Odometry,
934  ignition::msgs::Odometry
936  const nav_msgs::Odometry & ros_msg,
937  ignition::msgs::Odometry & ign_msg)
938 {
939  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
940 }
941 
942 template<>
943 void
944 Factory<
945  nav_msgs::Odometry,
946  ignition::msgs::Odometry
948  const ignition::msgs::Odometry & ign_msg,
949  nav_msgs::Odometry & ros_msg)
950 {
951  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
952 }
953 
954 // sensor_msgs
955 template<>
956 void
957 Factory<
958  sensor_msgs::FluidPressure,
959  ignition::msgs::FluidPressure
961  const sensor_msgs::FluidPressure & ros_msg,
962  ignition::msgs::FluidPressure & ign_msg)
963 {
964  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
965 }
966 
967 template<>
968 void
969 Factory<
970  sensor_msgs::FluidPressure,
971  ignition::msgs::FluidPressure
973  const ignition::msgs::FluidPressure & ign_msg,
974  sensor_msgs::FluidPressure & ros_msg)
975 {
976  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
977 }
978 
979 template<>
980 void
981 Factory<
982  sensor_msgs::Image,
983  ignition::msgs::Image
985  const sensor_msgs::Image & ros_msg,
986  ignition::msgs::Image & ign_msg)
987 {
988  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
989 }
990 
991 template<>
992 void
993 Factory<
994  sensor_msgs::Image,
995  ignition::msgs::Image
997  const ignition::msgs::Image & ign_msg,
998  sensor_msgs::Image & ros_msg)
999 {
1000  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1001 }
1002 
1003 template<>
1004 void
1005 Factory<
1006  sensor_msgs::CameraInfo,
1007  ignition::msgs::CameraInfo
1009  const sensor_msgs::CameraInfo & ros_msg,
1010  ignition::msgs::CameraInfo & ign_msg)
1011 {
1012  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1013 }
1014 
1015 template<>
1016 void
1017 Factory<
1018  sensor_msgs::CameraInfo,
1019  ignition::msgs::CameraInfo
1021  const ignition::msgs::CameraInfo & ign_msg,
1022  sensor_msgs::CameraInfo & ros_msg)
1023 {
1024  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1025 }
1026 
1027 template<>
1028 void
1029 Factory<
1030  sensor_msgs::Imu,
1031  ignition::msgs::IMU
1033  const sensor_msgs::Imu & ros_msg,
1034  ignition::msgs::IMU & ign_msg)
1035 {
1036  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1037 }
1038 
1039 template<>
1040 void
1041 Factory<
1042  sensor_msgs::Imu,
1043  ignition::msgs::IMU
1045  const ignition::msgs::IMU & ign_msg,
1046  sensor_msgs::Imu & ros_msg)
1047 {
1048  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1049 }
1050 
1051 template<>
1052 void
1053 Factory<
1054  sensor_msgs::JointState,
1055  ignition::msgs::Model
1057  const sensor_msgs::JointState & ros_msg,
1058  ignition::msgs::Model & ign_msg)
1059 {
1060  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1061 }
1062 
1063 template<>
1064 void
1065 Factory<
1066  sensor_msgs::JointState,
1067  ignition::msgs::Model
1069  const ignition::msgs::Model & ign_msg,
1070  sensor_msgs::JointState & ros_msg)
1071 {
1072  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1073 }
1074 
1075 template<>
1076 void
1077 Factory<
1078  sensor_msgs::LaserScan,
1079  ignition::msgs::LaserScan
1081  const sensor_msgs::LaserScan & ros_msg,
1082  ignition::msgs::LaserScan & ign_msg)
1083 {
1084  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1085 }
1086 
1087 template<>
1088 void
1089 Factory<
1090  sensor_msgs::LaserScan,
1091  ignition::msgs::LaserScan
1093  const ignition::msgs::LaserScan & ign_msg,
1094  sensor_msgs::LaserScan & ros_msg)
1095 {
1096  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1097 }
1098 
1099 template<>
1100 void
1101 Factory<
1102  sensor_msgs::MagneticField,
1103  ignition::msgs::Magnetometer
1105  const sensor_msgs::MagneticField & ros_msg,
1106  ignition::msgs::Magnetometer & ign_msg)
1107 {
1108  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1109 }
1110 
1111 template<>
1112 void
1113 Factory<
1114  sensor_msgs::MagneticField,
1115  ignition::msgs::Magnetometer
1117  const ignition::msgs::Magnetometer & ign_msg,
1118  sensor_msgs::MagneticField & ros_msg)
1119 {
1120  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1121 }
1122 
1123 template<>
1124 void
1125 Factory<
1126  sensor_msgs::NavSatFix,
1127  ignition::msgs::NavSat
1129  const sensor_msgs::NavSatFix & ros_msg,
1130  ignition::msgs::NavSat & ign_msg)
1131 {
1132  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1133 }
1134 
1135 template<>
1136 void
1137 Factory<
1138  sensor_msgs::NavSatFix,
1139  ignition::msgs::NavSat
1141  const ignition::msgs::NavSat & ign_msg,
1142  sensor_msgs::NavSatFix & ros_msg)
1143 {
1144  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1145 }
1146 
1147 template<>
1148 void
1149 Factory<
1150  sensor_msgs::PointCloud2,
1151  ignition::msgs::PointCloudPacked
1153  const sensor_msgs::PointCloud2 & ros_msg,
1154  ignition::msgs::PointCloudPacked & ign_msg)
1155 {
1156  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1157 }
1158 
1159 template<>
1160 void
1161 Factory<
1162  sensor_msgs::PointCloud2,
1163  ignition::msgs::PointCloudPacked
1165  const ignition::msgs::PointCloudPacked & ign_msg,
1166  sensor_msgs::PointCloud2 & ros_msg)
1167 {
1168  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1169 }
1170 
1171 template<>
1172 void
1173 Factory<
1174  sensor_msgs::BatteryState,
1175  ignition::msgs::BatteryState
1177  const sensor_msgs::BatteryState & ros_msg,
1178  ignition::msgs::BatteryState & ign_msg)
1179 {
1180  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1181 }
1182 
1183 template<>
1184 void
1185 Factory<
1186  sensor_msgs::BatteryState,
1187  ignition::msgs::BatteryState
1189  const ignition::msgs::BatteryState & ign_msg,
1190  sensor_msgs::BatteryState & ros_msg)
1191 {
1192  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1193 }
1194 
1195 template<>
1196 void
1197 Factory<
1198  visualization_msgs::Marker,
1199  ignition::msgs::Marker
1201  const visualization_msgs::Marker & ros_msg,
1202  ignition::msgs::Marker & ign_msg)
1203 {
1204  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1205 }
1206 
1207 template<>
1208 void
1209 Factory<
1210  visualization_msgs::Marker,
1211  ignition::msgs::Marker
1213  const ignition::msgs::Marker & ign_msg,
1214  visualization_msgs::Marker & ros_msg)
1215 {
1216  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1217 }
1218 
1219 template<>
1220 void
1221 Factory<
1222  visualization_msgs::MarkerArray,
1223  ignition::msgs::Marker_V
1225  const visualization_msgs::MarkerArray & ros_msg,
1226  ignition::msgs::Marker_V & ign_msg)
1227 {
1228  ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg);
1229 }
1230 
1231 template<>
1232 void
1233 Factory<
1234  visualization_msgs::MarkerArray,
1235  ignition::msgs::Marker_V
1237  const ignition::msgs::Marker_V & ign_msg,
1238  visualization_msgs::MarkerArray & ros_msg)
1239 {
1240  ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg);
1241 }
1242 
1243 } // namespace ros_ign_bridge
ros_ign_bridge::get_factory
std::shared_ptr< FactoryInterface > get_factory(const std::string &ros_type_name, const std::string &ign_type_name)
Definition: factories.cpp:408
ros_ign_bridge::Factory
Definition: factory.hpp:35
convert.hpp
ros_ign_bridge::convert_ros_to_ign
void convert_ros_to_ign(const std_msgs::Bool &ros_msg, ignition::msgs::Boolean &ign_msg)
Definition: convert.cpp:63
ros_ign_bridge::convert_ign_to_ros
void convert_ign_to_ros(const ignition::msgs::Boolean &ign_msg, std_msgs::Bool &ros_msg)
Definition: convert.cpp:72
ros_ign_bridge::get_factory_impl
std::shared_ptr< FactoryInterface > get_factory_impl(const std::string &ros_type_name, const std::string &ign_type_name)
Definition: factories.cpp:25
ros_ign_bridge
Definition: convert.hpp:59
factories.hpp


ros_ign_bridge
Author(s):
autogenerated on Sat Mar 11 2023 04:02:16