61
61
#include < string>
62
62
63
63
#include " ignition/gazebo/Conversions.hh"
64
+ #include " ignition/gazebo/Export.hh"
64
65
#include " ignition/gazebo/Util.hh"
65
66
66
67
using namespace ignition ;
67
68
68
69
// ////////////////////////////////////////////////
69
70
template <>
71
+ IGNITION_GAZEBO_VISIBLE
70
72
msgs::Entity_Type ignition::gazebo::convert (const std::string &_in)
71
73
{
72
74
msgs::Entity_Type out = msgs::Entity_Type_NONE;
@@ -104,6 +106,7 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)
104
106
105
107
// ////////////////////////////////////////////////
106
108
template <>
109
+ IGNITION_GAZEBO_VISIBLE
107
110
math::Pose3d ignition::gazebo::convert (const msgs::Pose &_in)
108
111
{
109
112
math::Pose3d out (_in.position ().x (),
@@ -120,6 +123,7 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in)
120
123
121
124
// ////////////////////////////////////////////////
122
125
template <>
126
+ IGNITION_GAZEBO_VISIBLE
123
127
msgs::Collision ignition::gazebo::convert (const sdf::Collision &_in)
124
128
{
125
129
msgs::Collision out;
@@ -132,6 +136,7 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in)
132
136
133
137
// ////////////////////////////////////////////////
134
138
template <>
139
+ IGNITION_GAZEBO_VISIBLE
135
140
sdf::Collision ignition::gazebo::convert (const msgs::Collision &_in)
136
141
{
137
142
sdf::Collision out;
@@ -143,6 +148,7 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in)
143
148
144
149
// ////////////////////////////////////////////////
145
150
template <>
151
+ IGNITION_GAZEBO_VISIBLE
146
152
msgs::Geometry ignition::gazebo::convert (const sdf::Geometry &_in)
147
153
{
148
154
msgs::Geometry out;
@@ -192,6 +198,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in)
192
198
193
199
// ////////////////////////////////////////////////
194
200
template <>
201
+ IGNITION_GAZEBO_VISIBLE
195
202
sdf::Geometry ignition::gazebo::convert (const msgs::Geometry &_in)
196
203
{
197
204
sdf::Geometry out;
@@ -255,6 +262,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in)
255
262
256
263
// ////////////////////////////////////////////////
257
264
template <>
265
+ IGNITION_GAZEBO_VISIBLE
258
266
msgs::Material ignition::gazebo::convert (const sdf::Material &_in)
259
267
{
260
268
msgs::Material out;
@@ -314,6 +322,7 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in)
314
322
315
323
// ////////////////////////////////////////////////
316
324
template <>
325
+ IGNITION_GAZEBO_VISIBLE
317
326
sdf::Material ignition::gazebo::convert (const msgs::Material &_in)
318
327
{
319
328
sdf::Material out;
@@ -360,6 +369,7 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in)
360
369
361
370
// ////////////////////////////////////////////////
362
371
template <>
372
+ IGNITION_GAZEBO_VISIBLE
363
373
msgs::Actor ignition::gazebo::convert (const sdf::Actor &_in)
364
374
{
365
375
msgs::Actor out;
@@ -399,6 +409,7 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in)
399
409
400
410
// ////////////////////////////////////////////////
401
411
template <>
412
+ IGNITION_GAZEBO_VISIBLE
402
413
sdf::Actor ignition::gazebo::convert (const msgs::Actor &_in)
403
414
{
404
415
sdf::Actor out;
@@ -441,6 +452,7 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in)
441
452
442
453
// ////////////////////////////////////////////////
443
454
template <>
455
+ IGNITION_GAZEBO_VISIBLE
444
456
msgs::Light ignition::gazebo::convert (const sdf::Light &_in)
445
457
{
446
458
msgs::Light out;
@@ -468,6 +480,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in)
468
480
469
481
// ////////////////////////////////////////////////
470
482
template <>
483
+ IGNITION_GAZEBO_VISIBLE
471
484
sdf::Light ignition::gazebo::convert (const msgs::Light &_in)
472
485
{
473
486
sdf::Light out;
@@ -495,6 +508,7 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in)
495
508
496
509
// ////////////////////////////////////////////////
497
510
template <>
511
+ IGNITION_GAZEBO_VISIBLE
498
512
msgs::GUI ignition::gazebo::convert (const sdf::Gui &_in)
499
513
{
500
514
msgs::GUI out;
@@ -533,6 +547,7 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in)
533
547
534
548
// ////////////////////////////////////////////////
535
549
template <>
550
+ IGNITION_GAZEBO_VISIBLE
536
551
msgs::Time ignition::gazebo::convert (
537
552
const std::chrono::steady_clock::duration &_in)
538
553
{
@@ -548,6 +563,7 @@ msgs::Time ignition::gazebo::convert(
548
563
549
564
// ////////////////////////////////////////////////
550
565
template <>
566
+ IGNITION_GAZEBO_VISIBLE
551
567
std::chrono::steady_clock::duration ignition::gazebo::convert (
552
568
const msgs::Time &_in)
553
569
{
@@ -556,6 +572,7 @@ std::chrono::steady_clock::duration ignition::gazebo::convert(
556
572
557
573
// ////////////////////////////////////////////////
558
574
template <>
575
+ IGNITION_GAZEBO_VISIBLE
559
576
msgs::Inertial ignition::gazebo::convert (const math::Inertiald &_in)
560
577
{
561
578
msgs::Inertial out;
@@ -572,6 +589,7 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in)
572
589
573
590
// ////////////////////////////////////////////////
574
591
template <>
592
+ IGNITION_GAZEBO_VISIBLE
575
593
math::Inertiald ignition::gazebo::convert (const msgs::Inertial &_in)
576
594
{
577
595
math::MassMatrix3d massMatrix;
@@ -591,6 +609,7 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in)
591
609
592
610
// ////////////////////////////////////////////////
593
611
template <>
612
+ IGNITION_GAZEBO_VISIBLE
594
613
msgs::Axis ignition::gazebo::convert (const sdf::JointAxis &_in)
595
614
{
596
615
msgs::Axis out;
@@ -620,6 +639,7 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)
620
639
621
640
// ////////////////////////////////////////////////
622
641
template <>
642
+ IGNITION_GAZEBO_VISIBLE
623
643
sdf::JointAxis ignition::gazebo::convert (const msgs::Axis &_in)
624
644
{
625
645
sdf::JointAxis out;
@@ -639,6 +659,7 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)
639
659
640
660
// ////////////////////////////////////////////////
641
661
template <>
662
+ IGNITION_GAZEBO_VISIBLE
642
663
msgs::Scene ignition::gazebo::convert (const sdf::Scene &_in)
643
664
{
644
665
msgs::Scene out;
@@ -669,6 +690,7 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
669
690
670
691
// ////////////////////////////////////////////////
671
692
template <>
693
+ IGNITION_GAZEBO_VISIBLE
672
694
sdf::Scene ignition::gazebo::convert (const msgs::Scene &_in)
673
695
{
674
696
sdf::Scene out;
@@ -698,6 +720,7 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)
698
720
699
721
// ////////////////////////////////////////////////
700
722
template <>
723
+ IGNITION_GAZEBO_VISIBLE
701
724
msgs::Atmosphere ignition::gazebo::convert (const sdf::Atmosphere &_in)
702
725
{
703
726
msgs::Atmosphere out;
@@ -715,6 +738,7 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in)
715
738
716
739
// ////////////////////////////////////////////////
717
740
template <>
741
+ IGNITION_GAZEBO_VISIBLE
718
742
sdf::Atmosphere ignition::gazebo::convert (const msgs::Atmosphere &_in)
719
743
{
720
744
sdf::Atmosphere out;
@@ -779,6 +803,7 @@ void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
779
803
780
804
// ////////////////////////////////////////////////
781
805
template <>
806
+ IGNITION_GAZEBO_VISIBLE
782
807
sdf::Noise ignition::gazebo::convert (const msgs::SensorNoise &_in)
783
808
{
784
809
sdf::Noise out;
@@ -811,6 +836,7 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in)
811
836
812
837
// ////////////////////////////////////////////////
813
838
template <>
839
+ IGNITION_GAZEBO_VISIBLE
814
840
msgs::Sensor ignition::gazebo::convert (const sdf::Sensor &_in)
815
841
{
816
842
msgs::Sensor out;
@@ -1027,6 +1053,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in)
1027
1053
1028
1054
// ////////////////////////////////////////////////
1029
1055
template <>
1056
+ IGNITION_GAZEBO_VISIBLE
1030
1057
sdf::Sensor ignition::gazebo::convert (const msgs::Sensor &_in)
1031
1058
{
1032
1059
sdf::Sensor out;
@@ -1266,6 +1293,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)
1266
1293
1267
1294
// ////////////////////////////////////////////////
1268
1295
template <>
1296
+ IGNITION_GAZEBO_VISIBLE
1269
1297
msgs::WorldStatistics ignition::gazebo::convert (const gazebo::UpdateInfo &_in)
1270
1298
{
1271
1299
msgs::WorldStatistics out;
@@ -1275,6 +1303,7 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in)
1275
1303
1276
1304
// ////////////////////////////////////////////////
1277
1305
template <>
1306
+ IGNITION_GAZEBO_VISIBLE
1278
1307
gazebo::UpdateInfo ignition::gazebo::convert (const msgs::WorldStatistics &_in)
1279
1308
{
1280
1309
gazebo::UpdateInfo out;
@@ -1288,6 +1317,7 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in)
1288
1317
1289
1318
// ////////////////////////////////////////////////
1290
1319
template <>
1320
+ IGNITION_GAZEBO_VISIBLE
1291
1321
msgs::AxisAlignedBox ignition::gazebo::convert (const math::AxisAlignedBox &_in)
1292
1322
{
1293
1323
msgs::AxisAlignedBox out;
@@ -1298,6 +1328,7 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in)
1298
1328
1299
1329
// ////////////////////////////////////////////////
1300
1330
template <>
1331
+ IGNITION_GAZEBO_VISIBLE
1301
1332
math::AxisAlignedBox ignition::gazebo::convert (const msgs::AxisAlignedBox &_in)
1302
1333
{
1303
1334
math::AxisAlignedBox out;
0 commit comments