Skip to content

Commit

Permalink
Remove visibility from headers that are not installed (#665)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Ashton Larkin <[email protected]>
  • Loading branch information
chapulina and adlarkin authored Mar 15, 2021
1 parent b47e7e5 commit 6603455
Show file tree
Hide file tree
Showing 47 changed files with 78 additions and 48 deletions.
30 changes: 30 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ using namespace ignition;

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::Entity_Type ignition::gazebo::convert(const std::string &_in)
{
msgs::Entity_Type out = msgs::Entity_Type_NONE;
Expand Down Expand Up @@ -104,6 +105,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 +122,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 +135,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 +147,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 +197,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 +261,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 @@ -308,6 +315,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 @@ -346,6 +354,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 @@ -385,6 +394,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 @@ -427,6 +437,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 @@ -454,6 +465,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 @@ -481,6 +493,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 @@ -519,6 +532,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 @@ -534,6 +548,7 @@ msgs::Time ignition::gazebo::convert(

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
std::chrono::steady_clock::duration ignition::gazebo::convert(
const msgs::Time &_in)
{
Expand All @@ -542,6 +557,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 @@ -558,6 +574,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 @@ -577,6 +594,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 @@ -614,6 +632,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 @@ -638,6 +657,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 All @@ -653,6 +673,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 All @@ -668,6 +689,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 @@ -685,6 +707,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 @@ -749,6 +772,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 @@ -781,6 +805,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 @@ -997,6 +1022,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 @@ -1236,6 +1262,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 @@ -1245,6 +1272,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 @@ -1258,6 +1286,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 @@ -1268,6 +1297,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/gui/AboutDialogHandler.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace gui
{
/// \brief Class for handling about dialog
class IGNITION_GAZEBO_VISIBLE AboutDialogHandler : public QObject
class AboutDialogHandler : public QObject
{
Q_OBJECT

Expand Down
2 changes: 1 addition & 1 deletion src/gui/GuiFileHandler.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace gui
{
/// \brief Class for handling saving and loading of SDFormat files
class IGNITION_GAZEBO_VISIBLE GuiFileHandler : public QObject
class GuiFileHandler : public QObject
{
Q_OBJECT

Expand Down
2 changes: 1 addition & 1 deletion src/gui/PathManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ namespace gui
/// \brief Class for handling paths and their environment variables.
/// It queries the server for paths at startup, and keeps paths updated
/// whenever they change in the server.
class IGNITION_GAZEBO_VISIBLE PathManager : public QObject
class PathManager : public QObject
{
Q_OBJECT

Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace ignition
///
/// NetworkConfig can either be created programatically, or populated from
/// environment variables set before the execution of the Gazebo server.
class IGNITION_GAZEBO_VISIBLE NetworkConfig
class NetworkConfig
{
/// \brief Populate a new NetworkConfig object based on
/// values.
Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace ignition
/// \brief The NetworkManager provides a common interface to derived
/// objects that control the flow of information in the distributed
/// simulation environment.
class IGNITION_GAZEBO_VISIBLE NetworkManager
class NetworkManager
{
/// \brief Convenience type alias for NodeOptions
public: using NodeOptions = ignition::transport::NodeOptions;
Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkManagerPrimary.hh
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace ignition
/// \class NetworkManagerPrimary NetworkManagerPrimary.hh
/// ignition/gazebo/network/NetworkManagerPrimary.hh
/// \brief Simulation primary specific behaviors
class IGNITION_GAZEBO_VISIBLE NetworkManagerPrimary:
class NetworkManagerPrimary:
public NetworkManager
{
// Documentation inherited
Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkManagerPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ namespace ignition
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \class NetworkManagerPrivate NetworkManagerPrivate.hh
/// ignition/gazebo/NetworkManagerPrivate.hh
class IGNITION_GAZEBO_VISIBLE NetworkManagerPrivate
class NetworkManagerPrivate
{
/// \brief Network Configuration
public: NetworkConfig config;
Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkManagerSecondary.hh
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ namespace ignition
/// \class NetworkManagerSecondary NetworkManagerSecondary.hh
/// ignition/gazebo/network/NetworkManagerSecondary.hh
/// \brief Secondary specific behaviors
class IGNITION_GAZEBO_VISIBLE NetworkManagerSecondary:
class NetworkManagerSecondary:
public NetworkManager
{
// Documentation inherited
Expand Down
6 changes: 3 additions & 3 deletions src/network/PeerInfo.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace ignition
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
class IGNITION_GAZEBO_VISIBLE PeerInfo {
class PeerInfo {
/// \brief Constructor
public: explicit PeerInfo(const NetworkRole &_role = NetworkRole::None);

Expand All @@ -53,13 +53,13 @@ namespace ignition
/// \brief Construct a `PeerInfo` object from a message.
/// \param[in] _proto Message
/// \result Equivalent PeerInfo
IGNITION_GAZEBO_VISIBLE PeerInfo fromProto(
PeerInfo fromProto(
const private_msgs::PeerInfo &_proto);

/// \brief Construct a `PeerInfo` message from an object.
/// \param[in] _info Peer info object
/// \result Equivalent message
IGNITION_GAZEBO_VISIBLE private_msgs::PeerInfo toProto(
private_msgs::PeerInfo toProto(
const PeerInfo &_info);
} // namespace gazebo
} // namespace ignition
Expand Down
2 changes: 1 addition & 1 deletion src/network/PeerTracker.hh
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ namespace ignition
///
/// It is used to both announce the existence of a peer, as well as track
/// announcements and heartbeats from other peers.
class IGNITION_GAZEBO_VISIBLE PeerTracker {
class PeerTracker {
/// \brief Convenience type alias for NodeOptions
public: using NodeOptions = ignition::transport::NodeOptions;

Expand Down
2 changes: 1 addition & 1 deletion src/systems/air_pressure/AirPressure.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace systems
/// \class AirPressure AirPressure.hh ignition/gazebo/systems/AirPressure.hh
/// \brief An air pressure sensor that reports vertical position and velocity
/// readings over ign transport
class IGNITION_GAZEBO_VISIBLE AirPressure:
class AirPressure:
public System,
public ISystemPreUpdate,
public ISystemPostUpdate
Expand Down
2 changes: 1 addition & 1 deletion src/systems/altimeter/Altimeter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace systems
/// \class Altimeter Altimeter.hh ignition/gazebo/systems/Altimeter.hh
/// \brief An altimeter sensor that reports vertical position and velocity
/// readings over ign transport
class IGNITION_GAZEBO_VISIBLE Altimeter:
class Altimeter:
public System,
public ISystemPreUpdate,
public ISystemPostUpdate
Expand Down
2 changes: 1 addition & 1 deletion src/systems/apply_joint_force/ApplyJointForce.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace systems
class ApplyJointForcePrivate;

/// \brief This system applies a force to the first axis of a specified joint.
class IGNITION_GAZEBO_VISIBLE ApplyJointForce
class ApplyJointForce
: public System,
public ISystemConfigure,
public ISystemPreUpdate
Expand Down
2 changes: 1 addition & 1 deletion src/systems/battery_plugin/LinearBatteryPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ namespace systems
/// (Required if <enable_recharge> is set to true)
/// <fix_issue_225> True to change the battery behavior to fix some issues
/// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225.
class IGNITION_GAZEBO_VISIBLE LinearBatteryPlugin
class LinearBatteryPlugin
: public System,
public ISystemConfigure,
public ISystemPreUpdate,
Expand Down
2 changes: 1 addition & 1 deletion src/systems/breadcrumbs/Breadcrumbs.hh
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ namespace systems
/// Defaults to false.
/// `<breadcrumb>`: This is the model used as a template for deploying
/// breadcrumbs.
class IGNITION_GAZEBO_VISIBLE Breadcrumbs
class Breadcrumbs
: public System,
public ISystemConfigure,
public ISystemPreUpdate
Expand Down
2 changes: 1 addition & 1 deletion src/systems/buoyancy/Buoyancy.hh
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace systems
/// ```
/// ign gazebo -v 4 buoyancy.sdf
/// ```
class IGNITION_GAZEBO_VISIBLE Buoyancy
class Buoyancy
: public System,
public ISystemConfigure,
public ISystemPreUpdate
Expand Down
Loading

0 comments on commit 6603455

Please sign in to comment.