Gazebo Sim

API Reference

9.0.0~pre1
Conversions.hh
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018 Open Source Robotics Foundation
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *
16*/
17#ifndef GZ_SIM_CONVERSIONS_HH_
18#define GZ_SIM_CONVERSIONS_HH_
19
20#include <gz/msgs/actor.pb.h>
21#include <gz/msgs/atmosphere.pb.h>
22#include <gz/msgs/axis.pb.h>
23#include <gz/msgs/entity.pb.h>
24#include <gz/msgs/geometry.pb.h>
25#include <gz/msgs/gui.pb.h>
26#include <gz/msgs/inertial.pb.h>
27#include <gz/msgs/light.pb.h>
28#include <gz/msgs/material.pb.h>
29#include <gz/msgs/particle_emitter.pb.h>
30#include <gz/msgs/plugin.pb.h>
31#include <gz/msgs/plugin_v.pb.h>
32#include <gz/msgs/physics.pb.h>
33#include <gz/msgs/scene.pb.h>
34#include <gz/msgs/sensor.pb.h>
35#include <gz/msgs/sensor_noise.pb.h>
36#include <gz/msgs/time.pb.h>
37#include <gz/msgs/world_stats.pb.h>
38
39#include <chrono>
40#include <string>
41
42#include <gz/common/Console.hh>
44#include <gz/math/Inertial.hh>
45#include <sdf/Actor.hh>
46#include <sdf/Atmosphere.hh>
47#include <sdf/Collision.hh>
48#include <sdf/Geometry.hh>
49#include <sdf/Gui.hh>
50#include <sdf/JointAxis.hh>
51#include <sdf/Light.hh>
52#include <sdf/Material.hh>
53#include <sdf/Noise.hh>
54#include <sdf/ParticleEmitter.hh>
55#include <sdf/Plugin.hh>
56#include <sdf/Physics.hh>
57#include <sdf/Projector.hh>
58#include <sdf/Scene.hh>
59#include <sdf/Sensor.hh>
60
61#include "gz/sim/config.hh"
62#include "gz/sim/Export.hh"
63#include "gz/sim/Types.hh"
64
65namespace gz
66{
67 namespace sim
68 {
69 // Inline bracket to help doxygen filtering.
70 inline namespace GZ_SIM_VERSION_NAMESPACE {
75 void GZ_SIM_VISIBLE
76 set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
77
82 void GZ_SIM_VISIBLE
83 set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
84
90 void GZ_SIM_VISIBLE
91 set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
92
97 template<class Out>
98 Out convert(const sdf::Geometry &_in)
99 {
100 (void)_in;
101 Out::ConversionNotImplemented;
102 }
103
108 template<>
109 msgs::Geometry convert(const sdf::Geometry &_in);
110
115 template<class Out>
116 Out convert(const msgs::Pose &_in)
117 {
118 (void)_in;
119 Out::ConversionNotImplemented;
120 }
121
125 template<>
126 math::Pose3d convert(const msgs::Pose &_in);
127
132 template<class Out>
133 Out convert(const msgs::Geometry &_in)
134 {
135 (void)_in;
136 Out::ConversionNotImplemented;
137 }
138
143 template<>
144 sdf::Geometry convert(const msgs::Geometry &_in);
145
150 template<class Out>
151 Out convert(const sdf::Material &_in)
152 {
153 (void)_in;
154 Out::ConversionNotImplemented;
155 }
156
161 template<>
162 msgs::Material convert(const sdf::Material &_in);
163
168 template<class Out>
169 Out convert(const msgs::Material &_in)
170 {
171 (void)_in;
172 Out::ConversionNotImplemented;
173 }
174
179 template<>
180 sdf::Material convert(const msgs::Material &_in);
181
186 template<class Out>
187 Out convert(const sdf::Actor &_in)
188 {
189 (void)_in;
190 Out::ConversionNotImplemented;
191 }
192
197 template<>
198 msgs::Actor convert(const sdf::Actor &_in);
199
204 template<class Out>
205 Out convert(const msgs::Actor& _in)
206 {
207 (void)_in;
208 Out::ConversionNotImplemented;
209 }
210
215 template<>
216 sdf::Actor convert(const msgs::Actor &_in);
217
222 template<class Out>
223 Out convert(const sdf::Light &_in)
224 {
225 (void)_in;
226 Out::ConversionNotImplemented;
227 }
228
233 template<>
234 msgs::Light convert(const sdf::Light &_in);
235
240 std::string GZ_SIM_VISIBLE
241 convert(const sdf::LightType &_in);
242
247 template<class Out>
248 Out convert(const msgs::Light& _in)
249 {
250 (void)_in;
251 Out::ConversionNotImplemented;
252 }
253
258 template<>
259 sdf::Light convert(const msgs::Light &_in);
260
264 sdf::LightType GZ_SIM_VISIBLE
265 convert(const std::string &_in);
266
271 template<class Out>
272 Out convert(const sdf::Gui &_in)
273 {
274 (void)_in;
275 Out::ConversionNotImplemented;
276 }
277
281 template<>
282 msgs::GUI convert(const sdf::Gui &_in);
283
288 template<class Out>
289 Out convert(const std::chrono::steady_clock::duration &_in)
290 {
291 (void)_in;
292 Out::ConversionNotImplemented;
293 }
294
299 template<>
300 msgs::Time convert(const std::chrono::steady_clock::duration &_in);
301
306 template<class Out>
307 Out convert(const msgs::Time &_in)
308 {
309 (void)_in;
310 Out::ConversionNotImplemented;
311 }
312
317 template<>
318 std::chrono::steady_clock::duration convert(const msgs::Time &_in);
319
324 template<class Out>
325 Out convert(const math::Inertiald &_in)
326 {
327 (void)_in;
328 Out::ConversionNotImplemented;
329 }
330
335 template<>
336 msgs::Inertial convert(const math::Inertiald &_in);
337
342 template<class Out>
343 Out convert(const msgs::Inertial &_in)
344 {
345 (void)_in;
346 Out::ConversionNotImplemented;
347 }
348
353 template<>
354 math::Inertiald convert(const msgs::Inertial &_in);
355
360 template<class Out>
361 Out convert(const sdf::JointAxis &_in)
362 {
363 (void)_in;
364 Out::ConversionNotImplemented;
365 }
366
371 template<>
372 msgs::Axis convert(const sdf::JointAxis &_in);
373
378 template<class Out>
379 Out convert(const msgs::Axis &_in)
380 {
381 (void)_in;
382 Out::ConversionNotImplemented;
383 }
384
389 template<>
390 sdf::JointAxis convert(const msgs::Axis &_in);
391
396 template<class Out>
397 Out convert(const sdf::Scene &_in)
398 {
399 (void)_in;
400 Out::ConversionNotImplemented;
401 }
402
406 template<>
407 msgs::Scene convert(const sdf::Scene &_in);
408
413 template<class Out>
414 Out convert(const msgs::Scene &_in)
415 {
416 (void)_in;
417 Out::ConversionNotImplemented;
418 }
419
424 template<>
425 sdf::Scene convert(const msgs::Scene &_in);
426
431 template<class Out>
432 Out convert(const sdf::Atmosphere &_in)
433 {
434 (void)_in;
435 Out::ConversionNotImplemented;
436 }
437
442 template<>
443 msgs::Atmosphere convert(const sdf::Atmosphere &_in);
444
449 template<class Out>
450 Out convert(const msgs::Atmosphere &_in)
451 {
452 (void)_in;
453 Out::ConversionNotImplemented;
454 }
455
460 template<>
461 sdf::Atmosphere convert(const msgs::Atmosphere &_in);
462
463
468 template<class Out>
469 Out convert(const sdf::Physics &_in)
470 {
471 (void)_in;
472 Out::ConversionNotImplemented;
473 }
474
479 template<>
480 msgs::Physics convert(const sdf::Physics &_in);
481
486 template<class Out>
487 Out convert(const msgs::Physics &_in)
488 {
489 (void)_in;
490 Out::ConversionNotImplemented;
491 }
492
497 template<>
498 sdf::Physics convert(const msgs::Physics &_in);
499
500
505 template<class Out>
506 Out convert(const sdf::Sensor &_in)
507 {
508 (void)_in;
509 Out::ConversionNotImplemented;
510 }
511
516 template<>
517 msgs::Sensor convert(const sdf::Sensor &_in);
518
523 template<class Out>
524 Out convert(const msgs::Sensor &_in)
525 {
526 (void)_in;
527 Out::ConversionNotImplemented;
528 }
529
534 template<>
535 sdf::Sensor convert(const msgs::Sensor &_in);
536
541 template<class Out>
542 Out convert(const msgs::SensorNoise &_in)
543 {
544 (void)_in;
545 Out::ConversionNotImplemented;
546 }
547
552 template<>
553 sdf::Noise convert(const msgs::SensorNoise &_in);
554
560 template<class Out>
561 Out convert(const msgs::WorldStatistics &_in)
562 {
563 (void)_in;
564 Out::ConversionNotImplemented;
565 }
566
571 template<>
572 UpdateInfo convert(const msgs::WorldStatistics &_in);
573
578 template<class Out>
579 Out convert(const UpdateInfo &_in)
580 {
581 (void)_in;
582 Out::ConversionNotImplemented;
583 }
584
589 template<>
590 msgs::WorldStatistics convert(const UpdateInfo &_in);
591
596 template<class Out>
597 Out convert(const sdf::Collision &_in)
598 {
599 (void)_in;
600 Out::ConversionNotImplemented;
601 }
602
607 template<>
608 msgs::Collision convert(const sdf::Collision &_in);
609
614 template<class Out>
615 Out convert(const msgs::Collision &_in)
616 {
617 (void)_in;
618 Out::ConversionNotImplemented;
619 }
620
625 template<>
626 sdf::Collision convert(const msgs::Collision &_in);
627
632 template<class Out>
633 Out convert(const std::string &_in)
634 {
635 (void)_in;
636 Out::ConversionNotImplemented;
637 }
638
642 template<>
643 msgs::Entity_Type convert(const std::string &_in);
644
649 template<class Out>
651 {
652 (void)_in;
653 Out::ConversionNotImplemented;
654 }
655
660 template<>
661 msgs::AxisAlignedBox convert(const math::AxisAlignedBox &_in);
662
668 template<class Out>
669 Out convert(const msgs::AxisAlignedBox &_in)
670 {
671 (void)_in;
672 Out::ConversionNotImplemented;
673 }
674
679 template<>
680 math::AxisAlignedBox convert(const msgs::AxisAlignedBox &_in);
681
687 template<class Out>
688 Out convert(const sdf::ParticleEmitter &/*_in*/)
689 {
690 Out::ConversionNotImplemented;
691 }
692
697 template<>
698 msgs::ParticleEmitter convert(const sdf::ParticleEmitter &_in);
699
705 template<class Out>
706 Out convert(const msgs::ParticleEmitter &/*_in*/)
707 {
708 Out::ConversionNotImplemented;
709 }
710
715 template<>
716 sdf::ParticleEmitter convert(const msgs::ParticleEmitter &_in);
717
723 template<class Out>
724 Out convert(const sdf::Projector &/*_in*/)
725 {
726 Out::ConversionNotImplemented;
727 }
728
733 template<>
734 msgs::Projector convert(const sdf::Projector &_in);
735
741 template<class Out>
742 Out convert(const msgs::Projector &/*_in*/)
743 {
744 Out::ConversionNotImplemented;
745 }
746
751 template<>
752 sdf::Projector convert(const msgs::Projector &_in);
753
754
759 template<class Out>
760 Out convert(const sdf::Element &/*_in*/)
761 {
762 Out::ConversionNotImplemented;
763 }
764
768 template<>
769 msgs::Plugin convert(const sdf::Element &_in);
770
775 template<class Out>
776 Out convert(const sdf::Plugin &/*_in*/)
777 {
778 Out::ConversionNotImplemented;
779 }
780
784 template<>
785 msgs::Plugin convert(const sdf::Plugin &_in);
786
791 template<class Out>
792 Out convert(const sdf::Plugins &/*_in*/)
793 {
794 Out::ConversionNotImplemented;
795 }
796
800 template<>
801 msgs::Plugin_V convert(const sdf::Plugins &_in);
802
807 template<class Out>
808 Out convert(const msgs::Plugin &/*_in*/)
809 {
810 Out::ConversionNotImplemented;
811 }
812
816 template<>
817 sdf::Plugin convert(const msgs::Plugin &_in);
818
823 template<class Out>
824 Out convert(const msgs::Plugin_V &/*_in*/)
825 {
826 Out::ConversionNotImplemented;
827 }
828
832 template<>
833 sdf::Plugins convert(const msgs::Plugin_V &_in);
834 }
835 }
836}
837#endif