Gazebo Gazebo

API Reference

3.15.2
gz/sim/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_GAZEBO_CONVERSIONS_HH_
18 #define GZ_GAZEBO_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/physics.pb.h>
30 #include <gz/msgs/scene.pb.h>
31 #include <gz/msgs/sensor.pb.h>
32 #include <gz/msgs/sensor_noise.pb.h>
33 #include <gz/msgs/time.pb.h>
34 #include <gz/msgs/world_stats.pb.h>
35 
36 #include <chrono>
37 #include <string>
38 
39 #include <gz/common/Console.hh>
40 #include <gz/math/Inertial.hh>
41 #include <sdf/Actor.hh>
42 #include <sdf/Atmosphere.hh>
43 #include <sdf/Collision.hh>
44 #include <sdf/Geometry.hh>
45 #include <sdf/Gui.hh>
46 #include <sdf/JointAxis.hh>
47 #include <sdf/Light.hh>
48 #include <sdf/Material.hh>
49 #include <sdf/Noise.hh>
50 #include <sdf/Physics.hh>
51 #include <sdf/Scene.hh>
52 #include <sdf/Sensor.hh>
53 
54 #include "gz/sim/config.hh"
55 #include "gz/sim/Export.hh"
56 #include "gz/sim/Types.hh"
57 
58 namespace ignition
59 {
60  namespace gazebo
61  {
62  // Inline bracket to help doxygen filtering.
63  inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
68  void IGNITION_GAZEBO_VISIBLE
69  set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
70 
75  void IGNITION_GAZEBO_VISIBLE
76  set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
77 
83  void IGNITION_GAZEBO_VISIBLE
84  set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
85 
90  template<class Out>
91  Out convert(const sdf::Geometry &_in)
92  {
93  (void)_in;
94  Out::ConversionNotImplemented;
95  }
96 
101  template<>
103 
108  template<class Out>
109  Out convert(const msgs::Pose &_in)
110  {
111  (void)_in;
112  Out::ConversionNotImplemented;
113  }
114 
118  template<>
119  math::Pose3d convert(const msgs::Pose &_in);
120 
125  template<class Out>
126  Out convert(const msgs::Geometry &_in)
127  {
128  (void)_in;
129  Out::ConversionNotImplemented;
130  }
131 
136  template<>
138 
143  template<class Out>
144  Out convert(const sdf::Material &_in)
145  {
146  (void)_in;
147  Out::ConversionNotImplemented;
148  }
149 
154  template<>
156 
161  template<class Out>
162  Out convert(const msgs::Material &_in)
163  {
164  (void)_in;
165  Out::ConversionNotImplemented;
166  }
167 
172  template<>
174 
179  template<class Out>
180  Out convert(const sdf::Actor &_in)
181  {
182  (void)_in;
183  Out::ConversionNotImplemented;
184  }
185 
190  template<>
191  msgs::Actor convert(const sdf::Actor &_in);
192 
197  template<class Out>
198  Out convert(const msgs::Actor& _in)
199  {
200  (void)_in;
201  Out::ConversionNotImplemented;
202  }
203 
208  template<>
209  sdf::Actor convert(const msgs::Actor &_in);
210 
215  template<class Out>
216  Out convert(const sdf::Light &_in)
217  {
218  (void)_in;
219  Out::ConversionNotImplemented;
220  }
221 
226  template<>
227  msgs::Light convert(const sdf::Light &_in);
228 
229 
234  template<class Out>
235  Out convert(const msgs::Light& _in)
236  {
237  (void)_in;
238  Out::ConversionNotImplemented;
239  }
240 
245  template<>
246  sdf::Light convert(const msgs::Light &_in);
247 
252  template<class Out>
253  Out convert(const sdf::Gui &_in)
254  {
255  (void)_in;
256  Out::ConversionNotImplemented;
257  }
258 
262  template<>
263  msgs::GUI convert(const sdf::Gui &_in);
264 
269  template<class Out>
270  Out convert(const std::chrono::steady_clock::duration &_in)
271  {
272  (void)_in;
273  Out::ConversionNotImplemented;
274  }
275 
280  template<>
281  msgs::Time convert(const std::chrono::steady_clock::duration &_in);
282 
287  template<class Out>
288  Out convert(const msgs::Time &_in)
289  {
290  (void)_in;
291  Out::ConversionNotImplemented;
292  }
293 
298  template<>
299  std::chrono::steady_clock::duration convert(const msgs::Time &_in);
300 
305  template<class Out>
306  Out convert(const math::Inertiald &_in)
307  {
308  (void)_in;
309  Out::ConversionNotImplemented;
310  }
311 
316  template<>
318 
323  template<class Out>
324  Out convert(const msgs::Inertial &_in)
325  {
326  (void)_in;
327  Out::ConversionNotImplemented;
328  }
329 
334  template<>
336 
341  template<class Out>
342  Out convert(const sdf::JointAxis &_in)
343  {
344  (void)_in;
345  Out::ConversionNotImplemented;
346  }
347 
352  template<>
353  msgs::Axis convert(const sdf::JointAxis &_in);
354 
359  template<class Out>
360  Out convert(const msgs::Axis &_in)
361  {
362  (void)_in;
363  Out::ConversionNotImplemented;
364  }
365 
370  template<>
371  sdf::JointAxis convert(const msgs::Axis &_in);
372 
377  template<class Out>
378  Out convert(const sdf::Scene &_in)
379  {
380  (void)_in;
381  Out::ConversionNotImplemented;
382  }
383 
387  template<>
388  msgs::Scene convert(const sdf::Scene &_in);
389 
394  template<class Out>
395  Out convert(const msgs::Scene &_in)
396  {
397  (void)_in;
398  Out::ConversionNotImplemented;
399  }
400 
405  template<>
406  sdf::Scene convert(const msgs::Scene &_in);
407 
412  template<class Out>
413  Out convert(const sdf::Atmosphere &_in)
414  {
415  (void)_in;
416  Out::ConversionNotImplemented;
417  }
418 
423  template<>
425 
430  template<class Out>
431  Out convert(const msgs::Atmosphere &_in)
432  {
433  (void)_in;
434  Out::ConversionNotImplemented;
435  }
436 
441  template<>
443 
444 
449  template<class Out>
450  Out convert(const sdf::Physics &_in)
451  {
452  (void)_in;
453  Out::ConversionNotImplemented;
454  }
455 
460  template<>
461  msgs::Physics convert(const sdf::Physics &_in);
462 
467  template<class Out>
468  Out convert(const msgs::Physics &_in)
469  {
470  (void)_in;
471  Out::ConversionNotImplemented;
472  }
473 
478  template<>
479  sdf::Physics convert(const msgs::Physics &_in);
480 
481 
486  template<class Out>
487  Out convert(const sdf::Sensor &_in)
488  {
489  (void)_in;
490  Out::ConversionNotImplemented;
491  }
492 
497  template<>
498  msgs::Sensor convert(const sdf::Sensor &_in);
499 
504  template<class Out>
505  Out convert(const msgs::Sensor &_in)
506  {
507  (void)_in;
508  Out::ConversionNotImplemented;
509  }
510 
515  template<>
516  sdf::Sensor convert(const msgs::Sensor &_in);
517 
522  template<class Out>
523  Out convert(const msgs::SensorNoise &_in)
524  {
525  (void)_in;
526  Out::ConversionNotImplemented;
527  }
528 
533  template<>
534  sdf::Noise convert(const msgs::SensorNoise &_in);
535 
541  template<class Out>
543  {
544  (void)_in;
545  Out::ConversionNotImplemented;
546  }
547 
552  template<>
553  UpdateInfo convert(const msgs::WorldStatistics &_in);
554 
559  template<class Out>
560  Out convert(const UpdateInfo &_in)
561  {
562  (void)_in;
563  Out::ConversionNotImplemented;
564  }
565 
570  template<>
571  msgs::WorldStatistics convert(const UpdateInfo &_in);
572 
577  template<class Out>
578  Out convert(const sdf::Collision &_in)
579  {
580  (void)_in;
581  Out::ConversionNotImplemented;
582  }
583 
588  template<>
590 
595  template<class Out>
596  Out convert(const msgs::Collision &_in)
597  {
598  (void)_in;
599  Out::ConversionNotImplemented;
600  }
601 
606  template<>
608 
613  template<class Out>
614  Out convert(const std::string &_in)
615  {
616  (void)_in;
617  Out::ConversionNotImplemented;
618  }
619 
623  template<>
625 
630  template<class Out>
632  {
633  (void)_in;
634  Out::ConversionNotImplemented;
635  }
636 
641  template<>
643 
649  template<class Out>
651  {
652  (void)_in;
653  Out::ConversionNotImplemented;
654  }
655 
660  template<>
662  }
663  }
664 }
665 #endif
This library is part of the Ignition Robotics project.
STL class.
Component< NoData, class CollisionTag > Collision
A component that identifies an entity as being a collision.
Definition: gz/sim/components/Collision.hh:42
Out convert(const sdf::Geometry &_in)
Generic conversion from an SDF geometry to another type.
Definition: gz/sim/Conversions.hh:91
Information passed to systems on the update callback.
Definition: include/gz/sim/Types.hh:37
Component< sdf::Light, class LightTag, serializers::LightSerializer > Light
This component contains light source information. For more information on lights, see SDF's Light ele...
Definition: gz/sim/components/Light.hh:48
Component< sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer > Atmosphere
This component holds atmosphere properties of the world.
Definition: gz/sim/components/Atmosphere.hh:44
Component< sdf::Actor, class ActorTag, serializers::ActorSerializer > Actor
This component contains actor source information. For more information on actors, see SDF's Actor ele...
Definition: gz/sim/components/Actor.hh:48
Component< sdf::Geometry, class GeometryTag, serializers::GeometrySerializer > Geometry
This component holds an entity's geometry.
Definition: gz/sim/components/Geometry.hh:46
Component< sdf::Scene, class SceneTag, serializers::SceneSerializer > Scene
This component holds scene properties of the world.
Definition: gz/sim/components/Scene.hh:45
void set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
Helper function that sets a mutable msgs::SensorNoise object to the values contained in a sdf::Noise ...
Component< sdf::JointAxis, class JointAxisTag, serializers::JointAxisSerializer > JointAxis
A component that contains the joint axis . This is a simple wrapper around sdf::JointAxis.
Definition: gz/sim/components/JointAxis.hh:43
Component< sdf::Material, class MaterialTag, serializers::MaterialSerializer > Material
This component holds an entity's material.
Definition: gz/sim/components/Material.hh:44
Component< sdf::Physics, class PhysicsTag, serializers::PhysicsSerializer > Physics
A component type that contains the physics properties of the World entity.
Definition: include/gz/sim/components/Physics.hh:48
Component< NoData, class SensorTag > Sensor
A component that identifies an entity as being a sensor.
Definition: gz/sim/components/Sensor.hh:35