Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add missing IGNITION_GAZEBO_VISIBLE macros #563

Merged
merged 2 commits into from
Jan 20, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 6 additions & 3 deletions include/ignition/gazebo/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -63,20 +63,23 @@ namespace ignition
/// to the values contained in a sdf::Noise object.
/// \param[out] _msg SensorNoise message to set.
/// \param[in] _sdf SDF Noise object.
void set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);
void IGNITION_GAZEBO_VISIBLE
set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf);

/// \brief Helper function that sets a mutable msgs::WorldStatistics object
/// to the values contained in a gazebo::UpdateInfo object.
/// \param[out] _msg WorldStatistics message to set.
/// \param[in] _in UpdateInfo object.
void set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);
void IGNITION_GAZEBO_VISIBLE
set(msgs::WorldStatistics *_msg, const UpdateInfo &_in);

/// \brief Helper function that sets a mutable msgs::Time object
/// to the values contained in a std::chrono::steady_clock::duration
/// object.
/// \param[out] _msg Time message to set.
/// \param[in] _in Chrono duration object.
void set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);
void IGNITION_GAZEBO_VISIBLE
set(msgs::Time *_msg, const std::chrono::steady_clock::duration &_in);

/// \brief Generic conversion from an SDF geometry to another type.
/// \param[in] _in SDF geometry.
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/gazebo/ServerConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace ignition
/// type and name, but it can't tell apart multiple entities with the same
/// name in different parts of the entity tree.
/// \sa const std::list<PluginInfo> &Plugins() const
public: class PluginInfo
public: class IGNITION_GAZEBO_VISIBLE PluginInfo
{
/// \brief Default constructor.
public: PluginInfo();
Expand Down
2 changes: 2 additions & 0 deletions include/ignition/gazebo/rendering/MarkerManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <memory>
#include <string>

#include <ignition/gazebo/rendering/Export.hh>

#include "ignition/rendering/RenderTypes.hh"

namespace ignition
Expand Down
31 changes: 31 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,14 @@
#include <string>

#include "ignition/gazebo/Conversions.hh"
#include "ignition/gazebo/Export.hh"
#include "ignition/gazebo/Util.hh"

using namespace ignition;

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
chapulina marked this conversation as resolved.
Show resolved Hide resolved
msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)
{
msgs::Entity_Type out = msgs::Entity_Type_NONE;
Expand Down Expand Up @@ -104,6 +106,7 @@ msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in)
{
math::Pose3d out(_in.position().x(),
Expand All @@ -120,6 +123,7 @@ math::Pose3d ignition::gazebo::convert(const msgs::Pose &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in)
{
msgs::Collision out;
Expand All @@ -132,6 +136,7 @@ msgs::Collision ignition::gazebo::convert(const sdf::Collision &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in)
{
sdf::Collision out;
Expand All @@ -143,6 +148,7 @@ sdf::Collision ignition::gazebo::convert(const msgs::Collision &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in)
{
msgs::Geometry out;
Expand Down Expand Up @@ -192,6 +198,7 @@ msgs::Geometry ignition::gazebo::convert(const sdf::Geometry &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in)
{
sdf::Geometry out;
Expand Down Expand Up @@ -255,6 +262,7 @@ sdf::Geometry ignition::gazebo::convert(const msgs::Geometry &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Material ignition::gazebo::convert(const sdf::Material &_in)
{
msgs::Material out;
Expand Down Expand Up @@ -314,6 +322,7 @@ msgs::Material ignition::gazebo::convert(const sdf::Material &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Material ignition::gazebo::convert(const msgs::Material &_in)
{
sdf::Material out;
Expand Down Expand Up @@ -360,6 +369,7 @@ sdf::Material ignition::gazebo::convert(const msgs::Material &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in)
{
msgs::Actor out;
Expand Down Expand Up @@ -399,6 +409,7 @@ msgs::Actor ignition::gazebo::convert(const sdf::Actor &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in)
{
sdf::Actor out;
Expand Down Expand Up @@ -441,6 +452,7 @@ sdf::Actor ignition::gazebo::convert(const msgs::Actor &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Light ignition::gazebo::convert(const sdf::Light &_in)
{
msgs::Light out;
Expand Down Expand Up @@ -468,6 +480,7 @@ msgs::Light ignition::gazebo::convert(const sdf::Light &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Light ignition::gazebo::convert(const msgs::Light &_in)
{
sdf::Light out;
Expand Down Expand Up @@ -495,6 +508,7 @@ sdf::Light ignition::gazebo::convert(const msgs::Light &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in)
{
msgs::GUI out;
Expand Down Expand Up @@ -533,6 +547,7 @@ msgs::GUI ignition::gazebo::convert(const sdf::Gui &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Time ignition::gazebo::convert(
const std::chrono::steady_clock::duration &_in)
{
Expand All @@ -548,6 +563,7 @@ msgs::Time ignition::gazebo::convert(

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
std::chrono::steady_clock::duration ignition::gazebo::convert(
const msgs::Time &_in)
{
Expand All @@ -556,6 +572,7 @@ std::chrono::steady_clock::duration ignition::gazebo::convert(

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in)
{
msgs::Inertial out;
Expand All @@ -572,6 +589,7 @@ msgs::Inertial ignition::gazebo::convert(const math::Inertiald &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in)
{
math::MassMatrix3d massMatrix;
Expand All @@ -591,6 +609,7 @@ math::Inertiald ignition::gazebo::convert(const msgs::Inertial &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)
{
msgs::Axis out;
Expand Down Expand Up @@ -620,6 +639,7 @@ msgs::Axis ignition::gazebo::convert(const sdf::JointAxis &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)
{
sdf::JointAxis out;
Expand All @@ -639,6 +659,7 @@ sdf::JointAxis ignition::gazebo::convert(const msgs::Axis &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
{
msgs::Scene out;
Expand Down Expand Up @@ -669,6 +690,7 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)
{
sdf::Scene out;
Expand Down Expand Up @@ -698,6 +720,7 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in)
{
msgs::Atmosphere out;
Expand All @@ -715,6 +738,7 @@ msgs::Atmosphere ignition::gazebo::convert(const sdf::Atmosphere &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Atmosphere ignition::gazebo::convert(const msgs::Atmosphere &_in)
{
sdf::Atmosphere out;
Expand Down Expand Up @@ -779,6 +803,7 @@ void ignition::gazebo::set(msgs::SensorNoise *_msg, const sdf::Noise &_sdf)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in)
{
sdf::Noise out;
Expand Down Expand Up @@ -811,6 +836,7 @@ sdf::Noise ignition::gazebo::convert(const msgs::SensorNoise &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in)
{
msgs::Sensor out;
Expand Down Expand Up @@ -1027,6 +1053,7 @@ msgs::Sensor ignition::gazebo::convert(const sdf::Sensor &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)
{
sdf::Sensor out;
Expand Down Expand Up @@ -1266,6 +1293,7 @@ sdf::Sensor ignition::gazebo::convert(const msgs::Sensor &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in)
{
msgs::WorldStatistics out;
Expand All @@ -1275,6 +1303,7 @@ msgs::WorldStatistics ignition::gazebo::convert(const gazebo::UpdateInfo &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in)
{
gazebo::UpdateInfo out;
Expand All @@ -1288,6 +1317,7 @@ gazebo::UpdateInfo ignition::gazebo::convert(const msgs::WorldStatistics &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in)
{
msgs::AxisAlignedBox out;
Expand All @@ -1298,6 +1328,7 @@ msgs::AxisAlignedBox ignition::gazebo::convert(const math::AxisAlignedBox &_in)

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in)
{
math::AxisAlignedBox out;
Expand Down
2 changes: 1 addition & 1 deletion src/LevelManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ namespace ignition
/// when the level is reloaded. Likewise, they should not be deleted.
/// * Entities spawned during simulation are part of the default level.
///
class LevelManager
class IGNITION_GAZEBO_VISIBLE LevelManager
chapulina marked this conversation as resolved.
Show resolved Hide resolved
{
/// \brief Constructor
/// \param[in] _runner A pointer to the simulationrunner that owns this
Expand Down
4 changes: 4 additions & 0 deletions src/SdfGenerator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ namespace sdf_generator
/// \input[in] _config Configuration for the world generator
/// \returns Generated world string if generation succeeded.
/// Otherwise, nullopt
IGNITION_GAZEBO_VISIBLE
chapulina marked this conversation as resolved.
Show resolved Hide resolved
std::optional<std::string> generateWorld(
const EntityComponentManager &_ecm, const Entity &_entity,
const IncludeUriMap &_includeUriMap = IncludeUriMap(),
Expand All @@ -56,6 +57,7 @@ namespace sdf_generator
/// \input[in] _includeUriMap Map from file paths to URIs used to preserve
/// included Fuel models
/// \input[in] _config Configuration for the world generator
IGNITION_GAZEBO_VISIBLE
bool updateWorldElement(
sdf::ElementPtr _elem,
const EntityComponentManager &_ecm, const Entity &_entity,
Expand All @@ -68,6 +70,7 @@ namespace sdf_generator
/// \input[in] _ecm Immutable reference to the Entity Component Manager
/// \input[in] _entity Model entity
/// \returns true if update succeeded.
IGNITION_GAZEBO_VISIBLE
bool updateModelElement(const sdf::ElementPtr &_elem,
const EntityComponentManager &_ecm,
const Entity &_entity);
Expand All @@ -79,6 +82,7 @@ namespace sdf_generator
/// \input[in] _entity Entity of included resource
/// \input[in] _uri Uri of the resource
/// \returns true if update succeeded.
IGNITION_GAZEBO_VISIBLE
bool updateIncludeElement(const sdf::ElementPtr &_elem,
const EntityComponentManager &_ecm,
const Entity &_entity, const std::string &_uri);
Expand Down