Skip to content

Commit c809e31

Browse files
authored
Add missing IGNITION_GAZEBO_VISIBLE macros (#563)
Signed-off-by: Jose Luis Rivero <[email protected]>
1 parent 694e248 commit c809e31

File tree

5 files changed

+43
-5
lines changed

5 files changed

+43
-5
lines changed

include/ignition/gazebo/Conversions.hh

+6-3
Original file line numberDiff line numberDiff line change
@@ -63,20 +63,23 @@ namespace ignition
6363
/// to the values contained in a sdf::Noise object.
6464
/// \param[out] _msg SensorNoise message to set.
6565
/// \param[in] _sdf SDF Noise object.
66-
void set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
66+
void IGNITION_GAZEBO_VISIBLE
67+
set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
6768

6869
/// \brief Helper function that sets a mutable msgs::WorldStatistics object
6970
/// to the values contained in a gazebo::UpdateInfo object.
7071
/// \param[out] _msg WorldStatistics message to set.
7172
/// \param[in] _in UpdateInfo object.
72-
void set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
73+
void IGNITION_GAZEBO_VISIBLE
74+
set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
7375

7476
/// \brief Helper function that sets a mutable msgs::Time object
7577
/// to the values contained in a std::chrono::steady_clock::duration
7678
/// object.
7779
/// \param[out] _msg Time message to set.
7880
/// \param[in] _in Chrono duration object.
79-
void set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
81+
void IGNITION_GAZEBO_VISIBLE
82+
set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
8083

8184
/// \brief Generic conversion from an SDF geometry to another type.
8285
/// \param[in] _in SDF geometry.

include/ignition/gazebo/ServerConfig.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ namespace ignition
4949
/// type and name, but it can't tell apart multiple entities with the same
5050
/// name in different parts of the entity tree.
5151
/// \sa const std::list<PluginInfo> &Plugins() const
52-
public: class PluginInfo
52+
public: class IGNITION_GAZEBO_VISIBLE PluginInfo
5353
{
5454
/// \brief Default constructor.
5555
public: PluginInfo();

src/Conversions.cc

+31
Original file line numberDiff line numberDiff line change
@@ -61,12 +61,14 @@
6161
#include <string>
6262

6363
#include "ignition/gazebo/Conversions.hh"
64+
#include "ignition/gazebo/Export.hh"
6465
#include "ignition/gazebo/Util.hh"
6566

6667
using namespace ignition;
6768

6869
//////////////////////////////////////////////////
6970
template<>
71+
IGNITION_GAZEBO_VISIBLE
7072
msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)
7173
{
7274
msgs::Entity_Type out = msgs::Entity_Type_NONE;
@@ -104,6 +106,7 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)
104106

105107
//////////////////////////////////////////////////
106108
template<>
109+
IGNITION_GAZEBO_VISIBLE
107110
math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in)
108111
{
109112
math::Pose3d out(_in.position().x(),
@@ -120,6 +123,7 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in)
120123

121124
//////////////////////////////////////////////////
122125
template<>
126+
IGNITION_GAZEBO_VISIBLE
123127
msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in)
124128
{
125129
msgs::Collision out;
@@ -132,6 +136,7 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in)
132136

133137
//////////////////////////////////////////////////
134138
template<>
139+
IGNITION_GAZEBO_VISIBLE
135140
sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in)
136141
{
137142
sdf::Collision out;
@@ -143,6 +148,7 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in)
143148

144149
//////////////////////////////////////////////////
145150
template<>
151+
IGNITION_GAZEBO_VISIBLE
146152
msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in)
147153
{
148154
msgs::Geometry out;
@@ -192,6 +198,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in)
192198

193199
//////////////////////////////////////////////////
194200
template<>
201+
IGNITION_GAZEBO_VISIBLE
195202
sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in)
196203
{
197204
sdf::Geometry out;
@@ -255,6 +262,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in)
255262

256263
//////////////////////////////////////////////////
257264
template<>
265+
IGNITION_GAZEBO_VISIBLE
258266
msgs::Material ignition::gazebo::convert(const sdf::Material &_in)
259267
{
260268
msgs::Material out;
@@ -314,6 +322,7 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in)
314322

315323
//////////////////////////////////////////////////
316324
template<>
325+
IGNITION_GAZEBO_VISIBLE
317326
sdf::Material ignition::gazebo::convert(const msgs::Material &_in)
318327
{
319328
sdf::Material out;
@@ -360,6 +369,7 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in)
360369

361370
//////////////////////////////////////////////////
362371
template<>
372+
IGNITION_GAZEBO_VISIBLE
363373
msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in)
364374
{
365375
msgs::Actor out;
@@ -399,6 +409,7 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in)
399409

400410
//////////////////////////////////////////////////
401411
template<>
412+
IGNITION_GAZEBO_VISIBLE
402413
sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in)
403414
{
404415
sdf::Actor out;
@@ -441,6 +452,7 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in)
441452

442453
//////////////////////////////////////////////////
443454
template<>
455+
IGNITION_GAZEBO_VISIBLE
444456
msgs::Light ignition::gazebo::convert(const sdf::Light &_in)
445457
{
446458
msgs::Light out;
@@ -468,6 +480,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in)
468480

469481
//////////////////////////////////////////////////
470482
template<>
483+
IGNITION_GAZEBO_VISIBLE
471484
sdf::Light ignition::gazebo::convert(const msgs::Light &_in)
472485
{
473486
sdf::Light out;
@@ -495,6 +508,7 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in)
495508

496509
//////////////////////////////////////////////////
497510
template<>
511+
IGNITION_GAZEBO_VISIBLE
498512
msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in)
499513
{
500514
msgs::GUI out;
@@ -533,6 +547,7 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in)
533547

534548
//////////////////////////////////////////////////
535549
template<>
550+
IGNITION_GAZEBO_VISIBLE
536551
msgs::Time ignition::gazebo::convert(
537552
const std::chrono::steady_clock::duration &_in)
538553
{
@@ -548,6 +563,7 @@ msgs::Time ignition::gazebo::convert(
548563

549564
//////////////////////////////////////////////////
550565
template<>
566+
IGNITION_GAZEBO_VISIBLE
551567
std::chrono::steady_clock::duration ignition::gazebo::convert(
552568
const msgs::Time &_in)
553569
{
@@ -556,6 +572,7 @@ std::chrono::steady_clock::duration ignition::gazebo::convert(
556572

557573
//////////////////////////////////////////////////
558574
template<>
575+
IGNITION_GAZEBO_VISIBLE
559576
msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in)
560577
{
561578
msgs::Inertial out;
@@ -572,6 +589,7 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in)
572589

573590
//////////////////////////////////////////////////
574591
template<>
592+
IGNITION_GAZEBO_VISIBLE
575593
math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in)
576594
{
577595
math::MassMatrix3d massMatrix;
@@ -591,6 +609,7 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in)
591609

592610
//////////////////////////////////////////////////
593611
template<>
612+
IGNITION_GAZEBO_VISIBLE
594613
msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)
595614
{
596615
msgs::Axis out;
@@ -620,6 +639,7 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)
620639

621640
//////////////////////////////////////////////////
622641
template<>
642+
IGNITION_GAZEBO_VISIBLE
623643
sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)
624644
{
625645
sdf::JointAxis out;
@@ -639,6 +659,7 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)
639659

640660
//////////////////////////////////////////////////
641661
template<>
662+
IGNITION_GAZEBO_VISIBLE
642663
msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
643664
{
644665
msgs::Scene out;
@@ -669,6 +690,7 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
669690

670691
//////////////////////////////////////////////////
671692
template<>
693+
IGNITION_GAZEBO_VISIBLE
672694
sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)
673695
{
674696
sdf::Scene out;
@@ -698,6 +720,7 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)
698720

699721
//////////////////////////////////////////////////
700722
template<>
723+
IGNITION_GAZEBO_VISIBLE
701724
msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in)
702725
{
703726
msgs::Atmosphere out;
@@ -715,6 +738,7 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in)
715738

716739
//////////////////////////////////////////////////
717740
template<>
741+
IGNITION_GAZEBO_VISIBLE
718742
sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in)
719743
{
720744
sdf::Atmosphere out;
@@ -779,6 +803,7 @@ void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf)
779803

780804
//////////////////////////////////////////////////
781805
template<>
806+
IGNITION_GAZEBO_VISIBLE
782807
sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in)
783808
{
784809
sdf::Noise out;
@@ -811,6 +836,7 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in)
811836

812837
//////////////////////////////////////////////////
813838
template<>
839+
IGNITION_GAZEBO_VISIBLE
814840
msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in)
815841
{
816842
msgs::Sensor out;
@@ -1027,6 +1053,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in)
10271053

10281054
//////////////////////////////////////////////////
10291055
template<>
1056+
IGNITION_GAZEBO_VISIBLE
10301057
sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)
10311058
{
10321059
sdf::Sensor out;
@@ -1266,6 +1293,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)
12661293

12671294
//////////////////////////////////////////////////
12681295
template<>
1296+
IGNITION_GAZEBO_VISIBLE
12691297
msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in)
12701298
{
12711299
msgs::WorldStatistics out;
@@ -1275,6 +1303,7 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in)
12751303

12761304
//////////////////////////////////////////////////
12771305
template<>
1306+
IGNITION_GAZEBO_VISIBLE
12781307
gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in)
12791308
{
12801309
gazebo::UpdateInfo out;
@@ -1288,6 +1317,7 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in)
12881317

12891318
//////////////////////////////////////////////////
12901319
template<>
1320+
IGNITION_GAZEBO_VISIBLE
12911321
msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in)
12921322
{
12931323
msgs::AxisAlignedBox out;
@@ -1298,6 +1328,7 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in)
12981328

12991329
//////////////////////////////////////////////////
13001330
template<>
1331+
IGNITION_GAZEBO_VISIBLE
13011332
math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in)
13021333
{
13031334
math::AxisAlignedBox out;

src/LevelManager.hh

+1-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ namespace ignition
7474
/// when the level is reloaded. Likewise, they should not be deleted.
7575
/// * Entities spawned during simulation are part of the default level.
7676
///
77-
class LevelManager
77+
class IGNITION_GAZEBO_VISIBLE LevelManager
7878
{
7979
/// \brief Constructor
8080
/// \param[in] _runner A pointer to the simulationrunner that owns this

src/SdfGenerator.hh

+4
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ namespace sdf_generator
4444
/// \input[in] _config Configuration for the world generator
4545
/// \returns Generated world string if generation succeeded.
4646
/// Otherwise, nullopt
47+
IGNITION_GAZEBO_VISIBLE
4748
std::optional<std::string> generateWorld(
4849
const EntityComponentManager &_ecm, const Entity &_entity,
4950
const IncludeUriMap &_includeUriMap = IncludeUriMap(),
@@ -56,6 +57,7 @@ namespace sdf_generator
5657
/// \input[in] _includeUriMap Map from file paths to URIs used to preserve
5758
/// included Fuel models
5859
/// \input[in] _config Configuration for the world generator
60+
IGNITION_GAZEBO_VISIBLE
5961
bool updateWorldElement(
6062
sdf::ElementPtr _elem,
6163
const EntityComponentManager &_ecm, const Entity &_entity,
@@ -68,6 +70,7 @@ namespace sdf_generator
6870
/// \input[in] _ecm Immutable reference to the Entity Component Manager
6971
/// \input[in] _entity Model entity
7072
/// \returns true if update succeeded.
73+
IGNITION_GAZEBO_VISIBLE
7174
bool updateModelElement(const sdf::ElementPtr &_elem,
7275
const EntityComponentManager &_ecm,
7376
const Entity &_entity);
@@ -79,6 +82,7 @@ namespace sdf_generator
7982
/// \input[in] _entity Entity of included resource
8083
/// \input[in] _uri Uri of the resource
8184
/// \returns true if update succeeded.
85+
IGNITION_GAZEBO_VISIBLE
8286
bool updateIncludeElement(const sdf::ElementPtr &_elem,
8387
const EntityComponentManager &_ecm,
8488
const Entity &_entity, const std::string &_uri);

0 commit comments

Comments
 (0)