Ignition Gazebo

API Reference

4.6.0
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 IGNITION_GAZEBO_CONVERSIONS_HH_
18 #define IGNITION_GAZEBO_CONVERSIONS_HH_
19 
20 #include <ignition/msgs/actor.pb.h>
22 #include <ignition/msgs/axis.pb.h>
25 #include <ignition/msgs/gui.pb.h>
27 #include <ignition/msgs/light.pb.h>
30 #include <ignition/msgs/scene.pb.h>
33 #include <ignition/msgs/time.pb.h>
35 
36 #include <chrono>
37 #include <string>
38 
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 "ignition/gazebo/config.hh"
55 #include "ignition/gazebo/Export.hh"
56 #include "ignition/gazebo/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 set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
69 
74  void set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
75 
81  void set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
82 
87  template<class Out>
88  Out convert(const sdf::Geometry &/*_in*/)
89  {
90  Out::ConversionNotImplemented;
91  }
92 
97  template<>
99 
104  template<class Out>
105  Out convert(const msgs::Pose &/*_in*/)
106  {
107  Out::ConversionNotImplemented;
108  }
109 
113  template<>
114  math::Pose3d convert(const msgs::Pose &_in);
115 
120  template<class Out>
121  Out convert(const msgs::Geometry &/*_in*/)
122  {
123  Out::ConversionNotImplemented;
124  }
125 
130  template<>
132 
137  template<class Out>
138  Out convert(const sdf::Material &/*_in*/)
139  {
140  Out::ConversionNotImplemented;
141  }
142 
147  template<>
149 
154  template<class Out>
155  Out convert(const msgs::Material &/*_in*/)
156  {
157  Out::ConversionNotImplemented;
158  }
159 
164  template<>
166 
171  template<class Out>
172  Out convert(const sdf::Actor &/*_in*/)
173  {
174  Out::ConversionNotImplemented;
175  }
176 
181  template<>
182  msgs::Actor convert(const sdf::Actor &_in);
183 
188  template<class Out>
189  Out convert(const msgs::Actor& /*_in*/)
190  {
191  Out::ConversionNotImplemented;
192  }
193 
198  template<>
199  sdf::Actor convert(const msgs::Actor &_in);
200 
205  template<class Out>
206  Out convert(const sdf::Light &/*_in*/)
207  {
208  Out::ConversionNotImplemented;
209  }
210 
215  template<>
216  msgs::Light convert(const sdf::Light &_in);
217 
218 
223  template<class Out>
224  Out convert(const msgs::Light& /*_in*/)
225  {
226  Out::ConversionNotImplemented;
227  }
228 
233  template<>
234  sdf::Light convert(const msgs::Light &_in);
235 
240  template<class Out>
241  Out convert(const sdf::Gui &/*_in*/)
242  {
243  Out::ConversionNotImplemented;
244  }
245 
249  template<>
250  msgs::GUI convert(const sdf::Gui &_in);
251 
256  template<class Out>
257  Out convert(const std::chrono::steady_clock::duration &/*_in*/)
258  {
259  Out::ConversionNotImplemented;
260  }
261 
266  template<>
267  msgs::Time convert(const std::chrono::steady_clock::duration &_in);
268 
273  template<class Out>
274  Out convert(const msgs::Time &/*_in*/)
275  {
276  Out::ConversionNotImplemented;
277  }
278 
283  template<>
284  std::chrono::steady_clock::duration convert(const msgs::Time &_in);
285 
290  template<class Out>
291  Out convert(const math::Inertiald &/*_in*/)
292  {
293  Out::ConversionNotImplemented;
294  }
295 
300  template<>
302 
307  template<class Out>
308  Out convert(const msgs::Inertial &/*_in*/)
309  {
310  Out::ConversionNotImplemented;
311  }
312 
317  template<>
319 
324  template<class Out>
325  Out convert(const sdf::JointAxis &/*_in*/)
326  {
327  Out::ConversionNotImplemented;
328  }
329 
334  template<>
335  msgs::Axis convert(const sdf::JointAxis &_in);
336 
341  template<class Out>
342  Out convert(const msgs::Axis &/*_in*/)
343  {
344  Out::ConversionNotImplemented;
345  }
346 
351  template<>
352  sdf::JointAxis convert(const msgs::Axis &_in);
353 
358  template<class Out>
359  Out convert(const sdf::Scene &/*_in*/)
360  {
361  Out::ConversionNotImplemented;
362  }
363 
367  template<>
368  msgs::Scene convert(const sdf::Scene &_in);
369 
374  template<class Out>
375  Out convert(const msgs::Scene &/*_in*/)
376  {
377  Out::ConversionNotImplemented;
378  }
379 
384  template<>
385  sdf::Scene convert(const msgs::Scene &_in);
386 
391  template<class Out>
392  Out convert(const sdf::Atmosphere &/*_in*/)
393  {
394  Out::ConversionNotImplemented;
395  }
396 
401  template<>
403 
408  template<class Out>
409  Out convert(const msgs::Atmosphere &/*_in*/)
410  {
411  Out::ConversionNotImplemented;
412  }
413 
418  template<>
420 
421 
426  template<class Out>
427  Out convert(const sdf::Physics &/*_in*/)
428  {
429  Out::ConversionNotImplemented;
430  }
431 
436  template<>
437  msgs::Physics convert(const sdf::Physics &_in);
438 
443  template<class Out>
444  Out convert(const msgs::Physics &/*_in*/)
445  {
446  Out::ConversionNotImplemented;
447  }
448 
453  template<>
454  sdf::Physics convert(const msgs::Physics &_in);
455 
456 
461  template<class Out>
462  Out convert(const sdf::Sensor &/*_in*/)
463  {
464  Out::ConversionNotImplemented;
465  }
466 
471  template<>
472  msgs::Sensor convert(const sdf::Sensor &_in);
473 
478  template<class Out>
479  Out convert(const msgs::Sensor &/*_in*/)
480  {
481  Out::ConversionNotImplemented;
482  }
483 
488  template<>
489  sdf::Sensor convert(const msgs::Sensor &_in);
490 
495  template<class Out>
496  Out convert(const msgs::SensorNoise &/*_in*/)
497  {
498  Out::ConversionNotImplemented;
499  }
500 
505  template<>
506  sdf::Noise convert(const msgs::SensorNoise &_in);
507 
513  template<class Out>
514  Out convert(const msgs::WorldStatistics &/*_in*/)
515  {
516  Out::ConversionNotImplemented;
517  }
518 
523  template<>
525 
530  template<class Out>
531  Out convert(const UpdateInfo &/*_in*/)
532  {
533  Out::ConversionNotImplemented;
534  }
535 
540  template<>
542 
547  template<class Out>
548  Out convert(const sdf::Collision &/*_in*/)
549  {
550  Out::ConversionNotImplemented;
551  }
552 
557  template<>
559 
564  template<class Out>
565  Out convert(const msgs::Collision &/*_in*/)
566  {
567  Out::ConversionNotImplemented;
568  }
569 
574  template<>
576 
581  template<class Out>
582  Out convert(const std::string &/*_in*/)
583  {
584  Out::ConversionNotImplemented;
585  }
586 
590  template<>
592 
597  template<class Out>
598  Out convert(const math::AxisAlignedBox &/*_in*/)
599  {
600  Out::ConversionNotImplemented;
601  }
602 
607  template<>
609 
615  template<class Out>
616  Out convert(const msgs::AxisAlignedBox &/*_in*/)
617  {
618  Out::ConversionNotImplemented;
619  }
620 
625  template<>
627  }
628  }
629 }
630 #endif
Component< sdf::JointAxis, class JointAxisTag, serializers::JointAxisSerializer > JointAxis
A component that contains the joint axis . This is a simple wrapper around sdf::JointAxis.
Definition: JointAxis.hh:43
Component< sdf::Geometry, class GeometryTag, serializers::GeometrySerializer > Geometry
This component holds an entity&#39;s geometry.
Definition: Geometry.hh:46
Component< sdf::Atmosphere, class AtmosphereTag, serializers::AtmosphereSerializer > Atmosphere
This component holds atmosphere properties of the world.
Definition: Atmosphere.hh:44
Information passed to systems on the update callback.
Definition: Types.hh:36
Component< sdf::Scene, class SceneTag, serializers::SceneSerializer > Scene
This component holds scene properties of the world.
Definition: Scene.hh:45
STL class.
Out convert(const sdf::Geometry &)
Generic conversion from an SDF geometry to another type.
Definition: Conversions.hh:88
Component< sdf::Material, class MaterialTag, serializers::MaterialSerializer > Material
This component holds an entity&#39;s material.
Definition: Material.hh:44
Component< sdf::Light, class LightTag, serializers::LightSerializer > Light
This component contains light source information. For more information on lights, see SDF&#39;s Light ele...
Definition: Light.hh:48
Component< NoData, class CollisionTag > Collision
A component that identifies an entity as being a collision.
Definition: Collision.hh:42
Component< sdf::Actor, class ActorTag, serializers::ActorSerializer > Actor
This component contains actor source information. For more information on actors, see SDF&#39;s Actor ele...
Definition: Actor.hh:80
This library is part of the Ignition Robotics project.
Component< sdf::Physics, class PhysicsTag, serializers::PhysicsSerializer > Physics
A component type that contains the physics properties of the World entity.
Definition: include/ignition/gazebo/components/Physics.hh:48
Component< NoData, class SensorTag > Sensor
A component that identifies an entity as being a link.
Definition: Sensor.hh:35