diff --git a/src/Conversions.cc b/src/Conversions.cc index ad8b304a70..df6b8ffbd6 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -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; @@ -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(), @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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) { @@ -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) { @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; diff --git a/src/gui/AboutDialogHandler.hh b/src/gui/AboutDialogHandler.hh index b5f71b543d..14f1bbd20c 100644 --- a/src/gui/AboutDialogHandler.hh +++ b/src/gui/AboutDialogHandler.hh @@ -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 diff --git a/src/gui/GuiFileHandler.hh b/src/gui/GuiFileHandler.hh index 017a575346..981b9fb769 100644 --- a/src/gui/GuiFileHandler.hh +++ b/src/gui/GuiFileHandler.hh @@ -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 diff --git a/src/gui/PathManager.hh b/src/gui/PathManager.hh index 2247916a60..341e382cf2 100644 --- a/src/gui/PathManager.hh +++ b/src/gui/PathManager.hh @@ -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 diff --git a/src/network/NetworkConfig.hh b/src/network/NetworkConfig.hh index 0bd1dfdfc4..b1b0893ff4 100644 --- a/src/network/NetworkConfig.hh +++ b/src/network/NetworkConfig.hh @@ -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. diff --git a/src/network/NetworkManager.hh b/src/network/NetworkManager.hh index c26c2bf058..3250298c72 100644 --- a/src/network/NetworkManager.hh +++ b/src/network/NetworkManager.hh @@ -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; diff --git a/src/network/NetworkManagerPrimary.hh b/src/network/NetworkManagerPrimary.hh index c95fe25e48..1d01c91cf1 100644 --- a/src/network/NetworkManagerPrimary.hh +++ b/src/network/NetworkManagerPrimary.hh @@ -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 diff --git a/src/network/NetworkManagerPrivate.hh b/src/network/NetworkManagerPrivate.hh index 16e91c1d5c..314f105d0a 100644 --- a/src/network/NetworkManagerPrivate.hh +++ b/src/network/NetworkManagerPrivate.hh @@ -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; diff --git a/src/network/NetworkManagerSecondary.hh b/src/network/NetworkManagerSecondary.hh index a4f7b3343d..3b4163d58a 100644 --- a/src/network/NetworkManagerSecondary.hh +++ b/src/network/NetworkManagerSecondary.hh @@ -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 diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index c44e461f56..2fd3ba9f71 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -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); @@ -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 diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index 1b7515bd6c..e19a8d42f6 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -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; diff --git a/src/systems/air_pressure/AirPressure.hh b/src/systems/air_pressure/AirPressure.hh index c40fb0b194..68be696d37 100644 --- a/src/systems/air_pressure/AirPressure.hh +++ b/src/systems/air_pressure/AirPressure.hh @@ -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 diff --git a/src/systems/altimeter/Altimeter.hh b/src/systems/altimeter/Altimeter.hh index 17db658027..aede9336e0 100644 --- a/src/systems/altimeter/Altimeter.hh +++ b/src/systems/altimeter/Altimeter.hh @@ -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 diff --git a/src/systems/apply_joint_force/ApplyJointForce.hh b/src/systems/apply_joint_force/ApplyJointForce.hh index 8ec0fadbe8..10dfabf196 100644 --- a/src/systems/apply_joint_force/ApplyJointForce.hh +++ b/src/systems/apply_joint_force/ApplyJointForce.hh @@ -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 diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index bf1b51eb57..9e0f243e37 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -58,7 +58,7 @@ namespace systems /// (Required if is set to true) /// 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, diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index bb34021344..fb874c0272 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -79,7 +79,7 @@ namespace systems /// Defaults to false. /// ``: This is the model used as a template for deploying /// breadcrumbs. - class IGNITION_GAZEBO_VISIBLE Breadcrumbs + class Breadcrumbs : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 3a9c42418e..7d9f1a4ae5 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -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 diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index 8be4740d0f..b8627f7355 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -41,7 +41,7 @@ namespace systems /// not specified, the topic defaults to: /// /world//link// /// sensor//record_video - class IGNITION_GAZEBO_VISIBLE CameraVideoRecorder: + class CameraVideoRecorder: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/contact/Contact.hh b/src/systems/contact/Contact.hh index 1ee98dec4c..98d77f4258 100644 --- a/src/systems/contact/Contact.hh +++ b/src/systems/contact/Contact.hh @@ -37,7 +37,7 @@ namespace systems **/ /// \brief Contact sensor system which manages all contact sensors in /// simulation - class IGNITION_GAZEBO_VISIBLE Contact : + class Contact : public System, public ISystemPreUpdate, public ISystemPostUpdate diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh index 8c98dfd9aa..5a1089321a 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -54,7 +54,7 @@ namespace systems /// will not print a warning message if a child model does not exist yet. /// Otherwise, a warning message is printed. Defaults to false. - class IGNITION_GAZEBO_VISIBLE DetachableJoint + class DetachableJoint : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/diff_drive/DiffDrive.hh b/src/systems/diff_drive/DiffDrive.hh index d2905a23ca..35002495d5 100644 --- a/src/systems/diff_drive/DiffDrive.hh +++ b/src/systems/diff_drive/DiffDrive.hh @@ -77,7 +77,7 @@ namespace systems /// `ignition.msgs.Pose_V` message and the `` /// `ignition.msgs.Odometry` message. This element if optional, /// and the default value is `{name_of_model}/{name_of_link}`. - class IGNITION_GAZEBO_VISIBLE DiffDrive + class DiffDrive : public System, public ISystemConfigure, public ISystemPreUpdate, diff --git a/src/systems/diff_drive/SpeedLimiter.hh b/src/systems/diff_drive/SpeedLimiter.hh index 5a86ac2b10..34286bc3ae 100644 --- a/src/systems/diff_drive/SpeedLimiter.hh +++ b/src/systems/diff_drive/SpeedLimiter.hh @@ -57,7 +57,7 @@ namespace systems /// \brief Class to limit velocity, acceleration and jerk. /// \ref https://github.com/ros-controls/ros_controllers/tree/melodic-devel/diff_drive_controller - class IGNITION_GAZEBO_VISIBLE SpeedLimiter + class SpeedLimiter { /// \brief Constructor. /// \param [in] _hasVelocityLimits if true, applies velocity limits. diff --git a/src/systems/imu/Imu.hh b/src/systems/imu/Imu.hh index 86b021c33e..74d5d87750 100644 --- a/src/systems/imu/Imu.hh +++ b/src/systems/imu/Imu.hh @@ -37,7 +37,7 @@ namespace systems /// \brief This system manages all IMU sensors in simulation. /// Each IMU sensor eports vertical position, angular velocity /// and lienar acceleration readings over Ignition Transport. - class IGNITION_GAZEBO_VISIBLE Imu: + class Imu: public System, public ISystemPreUpdate, public ISystemPostUpdate diff --git a/src/systems/joint_controller/JointController.hh b/src/systems/joint_controller/JointController.hh index b06e49297d..815a53c772 100644 --- a/src/systems/joint_controller/JointController.hh +++ b/src/systems/joint_controller/JointController.hh @@ -69,7 +69,7 @@ namespace systems /// /// `` Command offset (feed-forward) of the PID. /// The default value is 0. - class IGNITION_GAZEBO_VISIBLE JointController + class JointController : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/joint_position_controller/JointPositionController.hh b/src/systems/joint_position_controller/JointPositionController.hh index 97fb486609..f1bd6765ed 100644 --- a/src/systems/joint_position_controller/JointPositionController.hh +++ b/src/systems/joint_position_controller/JointPositionController.hh @@ -71,7 +71,7 @@ namespace systems /// /// `` Command offset (feed-forward) of the PID. Optional /// parameter. The default value is 0. - class IGNITION_GAZEBO_VISIBLE JointPositionController + class JointPositionController : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/joint_state_publisher/JointStatePublisher.hh b/src/systems/joint_state_publisher/JointStatePublisher.hh index 597cefa59c..352137edae 100644 --- a/src/systems/joint_state_publisher/JointStatePublisher.hh +++ b/src/systems/joint_state_publisher/JointStatePublisher.hh @@ -45,7 +45,7 @@ namespace systems /// ``: Name of a joint to publish. This parameter can be /// specified multiple times, and is optional. All joints in a model will /// be published if joint names are not specified. - class IGNITION_GAZEBO_VISIBLE JointStatePublisher + class JointStatePublisher : public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/lift_drag/LiftDrag.hh b/src/systems/lift_drag/LiftDrag.hh index 08736b7ab5..c03eab6f15 100644 --- a/src/systems/lift_drag/LiftDrag.hh +++ b/src/systems/lift_drag/LiftDrag.hh @@ -59,7 +59,7 @@ namespace systems /// coefficient curve. /// cda_stall : The ratio of coefficient of drag and alpha slope after /// stall. - class IGNITION_GAZEBO_VISIBLE LiftDrag + class LiftDrag : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/log/LogPlayback.hh b/src/systems/log/LogPlayback.hh index a9c46d8548..90e41cb3c0 100644 --- a/src/systems/log/LogPlayback.hh +++ b/src/systems/log/LogPlayback.hh @@ -37,7 +37,7 @@ namespace systems /// \class LogPlayback LogPlayback.hh /// ignition/gazebo/systems/log/LogPlayback.hh /// \brief Log state playback - class IGNITION_GAZEBO_VISIBLE LogPlayback: + class LogPlayback: public System, public ISystemConfigure, public ISystemUpdate diff --git a/src/systems/log/LogRecord.hh b/src/systems/log/LogRecord.hh index 60bd972feb..6bf80578e8 100644 --- a/src/systems/log/LogRecord.hh +++ b/src/systems/log/LogRecord.hh @@ -36,7 +36,7 @@ namespace systems /// \class LogRecord LogRecord.hh ignition/gazebo/systems/log/LogRecord.hh /// \brief Log state recorder - class IGNITION_GAZEBO_VISIBLE LogRecord: + class LogRecord: public System, public ISystemConfigure, public ISystemPreUpdate, diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index ccaac0168e..e8d54fb3f3 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -50,7 +50,7 @@ namespace systems /// When recording is finished. An `end` string will be published to the /// `/log_video_recorder/status` topic and the videos are saved to a /// timestamped directory - class IGNITION_GAZEBO_VISIBLE LogVideoRecorder: + class LogVideoRecorder: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh index 5f0d261a1c..6ec0c390ab 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -128,7 +128,7 @@ namespace systems /// /mic_/detection topic, where is the scoped name /// for the microphone - see ignition::gazebo::scopedName for more details - /// and is the value specified in the microphone's tag from the SDF. - class IGNITION_GAZEBO_VISIBLE LogicalAudioSensorPlugin : + class LogicalAudioSensorPlugin : public System, public ISystemConfigure, public ISystemPreUpdate, diff --git a/src/systems/logical_camera/LogicalCamera.hh b/src/systems/logical_camera/LogicalCamera.hh index 8c8b87e9fa..bb17adaa32 100644 --- a/src/systems/logical_camera/LogicalCamera.hh +++ b/src/systems/logical_camera/LogicalCamera.hh @@ -38,7 +38,7 @@ namespace systems **/ /// \brief A logical camera sensor that reports objects detected within its /// frustum readings over ign transport - class IGNITION_GAZEBO_VISIBLE LogicalCamera: + class LogicalCamera: public System, public ISystemPreUpdate, public ISystemPostUpdate diff --git a/src/systems/magnetometer/Magnetometer.hh b/src/systems/magnetometer/Magnetometer.hh index d97ff2ddc9..cda2e5e970 100644 --- a/src/systems/magnetometer/Magnetometer.hh +++ b/src/systems/magnetometer/Magnetometer.hh @@ -36,7 +36,7 @@ namespace systems /// \class Magnetometer Magnetometer.hh /// \brief An magnetometer sensor that reports the magnetic field in its /// current location. - class IGNITION_GAZEBO_VISIBLE Magnetometer: + class Magnetometer: public System, public ISystemPreUpdate, public ISystemPostUpdate diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index db21ef5770..72b73015f1 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -146,7 +146,7 @@ namespace systems /// # Examples /// See examples/worlds/quadcopter.sdf for a demonstration. /// - class IGNITION_GAZEBO_VISIBLE MulticopterVelocityControl + class MulticopterVelocityControl : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh index 4d8d89a3ce..1c736bf505 100644 --- a/src/systems/multicopter_motor_model/MulticopterMotorModel.hh +++ b/src/systems/multicopter_motor_model/MulticopterMotorModel.hh @@ -33,7 +33,7 @@ namespace systems /// \brief This system applies a thrust force to models with spinning /// propellers. See examples/worlds/quadcopter.sdf for a demonstration. - class IGNITION_GAZEBO_VISIBLE MulticopterMotorModel + class MulticopterMotorModel : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index 58b6fdc326..ebb0bb8f4c 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -77,7 +77,7 @@ namespace systems /// contents are interpreted as strings. Keys value pairs are stored in a /// map, which means the keys are unique. - class IGNITION_GAZEBO_VISIBLE PerformerDetector + class PerformerDetector : public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/physics/Physics.hh b/src/systems/physics/Physics.hh index 77d6ac8ff5..cc39d373a0 100644 --- a/src/systems/physics/Physics.hh +++ b/src/systems/physics/Physics.hh @@ -62,7 +62,7 @@ namespace systems /// \class Physics Physics.hh ignition/gazebo/systems/Physics.hh /// \brief Base class for a System. - class IGNITION_GAZEBO_VISIBLE Physics: + class Physics: public System, public ISystemConfigure, public ISystemUpdate diff --git a/src/systems/pose_publisher/PosePublisher.hh b/src/systems/pose_publisher/PosePublisher.hh index 55dd8e34dd..21ceed3a6f 100644 --- a/src/systems/pose_publisher/PosePublisher.hh +++ b/src/systems/pose_publisher/PosePublisher.hh @@ -63,7 +63,7 @@ namespace systems /// negative frequency publishes as fast as /// possible (i.e, at the rate of the simulation /// step). - class IGNITION_GAZEBO_VISIBLE PosePublisher + class PosePublisher : public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/scene_broadcaster/SceneBroadcaster.hh b/src/systems/scene_broadcaster/SceneBroadcaster.hh index 9506d080ba..5a23d01d9c 100644 --- a/src/systems/scene_broadcaster/SceneBroadcaster.hh +++ b/src/systems/scene_broadcaster/SceneBroadcaster.hh @@ -38,7 +38,7 @@ namespace systems **/ /// \brief System which periodically publishes an ignition::msgs::Scene /// message with updated information. - class IGNITION_GAZEBO_VISIBLE SceneBroadcaster: + class SceneBroadcaster: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/sensors/Sensors.hh b/src/systems/sensors/Sensors.hh index ea0e1248e2..3461256bbc 100644 --- a/src/systems/sensors/Sensors.hh +++ b/src/systems/sensors/Sensors.hh @@ -39,7 +39,7 @@ namespace systems /// \class Sensors Sensors.hh ignition/gazebo/systems/Sensors.hh /// \brief TODO(louise) Have one system for all sensors, or one per /// sensor / sensor type? - class IGNITION_GAZEBO_VISIBLE Sensors: + class Sensors: public System, public ISystemConfigure, public ISystemPostUpdate diff --git a/src/systems/thermal/Thermal.hh b/src/systems/thermal/Thermal.hh index e133e1803a..e033a21fbc 100644 --- a/src/systems/thermal/Thermal.hh +++ b/src/systems/thermal/Thermal.hh @@ -34,7 +34,7 @@ namespace systems class ThermalPrivate; /// \brief A thermal plugin that sets the temperature for the parent entity - class IGNITION_GAZEBO_VISIBLE Thermal: + class Thermal: public System, public ISystemConfigure { diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index 80aac1b9f3..b74097d751 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -57,7 +57,7 @@ namespace systems /// /// Set this to true so the plugin works from the start and doesn't /// need to be enabled. - class IGNITION_GAZEBO_VISIBLE TouchPlugin + class TouchPlugin : public System, public ISystemConfigure, public ISystemPreUpdate, diff --git a/src/systems/triggered_publisher/TriggeredPublisher.hh b/src/systems/triggered_publisher/TriggeredPublisher.hh index 3109771915..2834d5399a 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.hh +++ b/src/systems/triggered_publisher/TriggeredPublisher.hh @@ -153,7 +153,7 @@ namespace systems /// The current implementation of this system does not support specifying a /// subfield of a repeated field in the "field" attribute. i.e, if /// `field="f1.f2"`, `f1` cannot be a repeated field. - class IGNITION_GAZEBO_VISIBLE TriggeredPublisher : public System, + class TriggeredPublisher : public System, public ISystemConfigure { /// \brief Constructor diff --git a/src/systems/user_commands/UserCommands.hh b/src/systems/user_commands/UserCommands.hh index d7f659eeae..6bbeb67afa 100644 --- a/src/systems/user_commands/UserCommands.hh +++ b/src/systems/user_commands/UserCommands.hh @@ -55,7 +55,7 @@ namespace systems /// * **Response type*: ignition.msgs.Boolean /// /// Try some examples described on examples/worlds/empty.sdf - class IGNITION_GAZEBO_VISIBLE UserCommands: + class UserCommands: public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/velocity_control/VelocityControl.hh b/src/systems/velocity_control/VelocityControl.hh index a4427f22c2..7b83c4e16b 100644 --- a/src/systems/velocity_control/VelocityControl.hh +++ b/src/systems/velocity_control/VelocityControl.hh @@ -34,7 +34,7 @@ namespace systems /// \brief Linear and angular velocity controller /// which is directly set on a model. - class IGNITION_GAZEBO_VISIBLE VelocityControl + class VelocityControl : public System, public ISystemConfigure, public ISystemPreUpdate, diff --git a/src/systems/wheel_slip/WheelSlip.hh b/src/systems/wheel_slip/WheelSlip.hh index db6ce328ef..0400da23dc 100644 --- a/src/systems/wheel_slip/WheelSlip.hh +++ b/src/systems/wheel_slip/WheelSlip.hh @@ -104,7 +104,7 @@ namespace systems \endverbatim */ - class IGNITION_GAZEBO_VISIBLE WheelSlip + class WheelSlip : public System, public ISystemConfigure, public ISystemPreUpdate diff --git a/src/systems/wind_effects/WindEffects.hh b/src/systems/wind_effects/WindEffects.hh index 73df8c95d2..f477c7667f 100644 --- a/src/systems/wind_effects/WindEffects.hh +++ b/src/systems/wind_effects/WindEffects.hh @@ -87,7 +87,7 @@ namespace systems /// /// Parameters for the noise that is added to the vertical wind velocity /// magnitude. - class IGNITION_GAZEBO_VISIBLE WindEffects: + class WindEffects: public System, public ISystemConfigure, public ISystemPreUpdate