Skip to content

Commit

Permalink
Change to use SuppressWarning from ign-utils (#193)
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll authored Feb 8, 2022
1 parent 83855aa commit b1f78a5
Show file tree
Hide file tree
Showing 20 changed files with 62 additions and 62 deletions.
6 changes: 3 additions & 3 deletions include/ignition/sensors/AirPressureSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#include <ignition/sensors/config.hh>
#include <ignition/sensors/air_pressure/Export.hh>
Expand Down Expand Up @@ -80,11 +80,11 @@ namespace ignition
/// \return Verical reference position in meters
public: double ReferenceAltitude() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<AirPressureSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/AltimeterSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#include <ignition/sensors/config.hh>
#include <ignition/sensors/altimeter/Export.hh>
Expand Down Expand Up @@ -97,11 +97,11 @@ namespace ignition
/// \return Vertical velocity in meters per second
public: double VerticalVelocity() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<AltimeterSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
Expand Down Expand Up @@ -170,11 +170,11 @@ namespace ignition
/// \param[in] _scene Pointer to the new scene.
private: void OnSceneChange(ignition::rendering::ScenePtr /*_scene*/);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<CameraSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <sdf/sdf.hh>

#include <ignition/common/Event.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
Expand Down Expand Up @@ -166,11 +166,11 @@ namespace ignition
private: void OnSceneChange(ignition::rendering::ScenePtr /*_scene*/)
{ }

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<DepthCameraSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/ForceTorqueSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#include <ignition/math/Pose3.hh>

Expand Down Expand Up @@ -115,11 +115,11 @@ namespace ignition
public: void SetRotationChildInSensor(
const math::Quaterniond &_rotChildInSensor);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<ForceTorqueSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/GpuLidarSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

// TODO(louise) Remove these pragmas once ign-rendering is disabling the
// warnings
Expand Down Expand Up @@ -128,11 +128,11 @@ namespace ignition
unsigned int _heighti, unsigned int _channels,
const std::string &/*_format*/)> _subscriber) override;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<GpuLidarSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/ImuSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <ignition/math/Pose3.hh>

#include <ignition/sensors/config.hh>
Expand Down Expand Up @@ -138,11 +138,11 @@ namespace ignition
/// \return Gravity vectory in meters per second squared.
public: math::Vector3d Gravity() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<ImuSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
10 changes: 5 additions & 5 deletions include/ignition/sensors/Lidar.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <string>
#include <vector>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <ignition/common/Event.hh>

#include "ignition/sensors/lidar/Export.hh"
Expand Down Expand Up @@ -236,10 +236,10 @@ namespace ignition
// Documentation inherited
public: virtual bool IsActive() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Just a mutex for thread safety
public: mutable std::mutex lidarMutex;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING

/// \brief Raw buffer of laser data.
public: float *laserBuffer = nullptr;
Expand All @@ -259,11 +259,11 @@ namespace ignition
unsigned int _heighti, unsigned int _channels,
const std::string &/*_format*/)> _subscriber);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<LidarPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/LogicalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#include <ignition/math/Angle.hh>

Expand Down Expand Up @@ -113,11 +113,11 @@ namespace ignition
/// \return List of detected models.
public: msgs::LogicalCameraImage Image() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<LogicalCameraSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/MagnetometerSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <ignition/math/Pose3.hh>

#include <ignition/sensors/config.hh>
Expand Down Expand Up @@ -93,11 +93,11 @@ namespace ignition
/// \return Magnetic field vector in body frame
public: math::Vector3d MagneticField() const;

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<MagnetometerSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/Manager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <type_traits>
#include <vector>
#include <sdf/sdf.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <ignition/common/Console.hh>
#include <ignition/sensors/config.hh>
#include <ignition/sensors/Export.hh>
Expand Down Expand Up @@ -139,10 +139,10 @@ namespace ignition
/// \brief Adds colon delimited paths sensor plugins may be
public: void IGN_DEPRECATED(6) AddPluginPaths(const std::string &_path);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief private data pointer
private: std::unique_ptr<ManagerPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/NavSatSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <memory>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <sdf/Sensor.hh>

#include "ignition/sensors/config.hh"
Expand Down Expand Up @@ -115,11 +115,11 @@ namespace ignition
public: void SetPosition(const math::Angle &_latitude,
const math::Angle &_longitude, double _altitude = 0.0);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<NavSatPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/RenderingEvents.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#define IGNITION_SENSORS_RENDERINGEVENTS_HH_

#include <ignition/common/Event.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

// TODO(louise) Remove these pragmas once ign-rendering is disabling the
// warnings
Expand Down Expand Up @@ -55,12 +55,12 @@ namespace ignition
std::function<void(const ignition::rendering::ScenePtr &)>
_callback);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Event that is used to trigger callbacks when the scene
/// is changed
public: static ignition::common::EventT<
void(const ignition::rendering::ScenePtr &)> sceneEvent;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/RenderingSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <memory>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

// TODO(louise) Remove these pragmas once ign-rendering is disabling the
// warnings
Expand Down Expand Up @@ -86,11 +86,11 @@ namespace ignition
/// \param[in] _sensor Sensor to add.
protected: void AddSensor(rendering::SensorPtr _sensor);

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \internal
/// \brief Data pointer for private data
private: std::unique_ptr<RenderingSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/RgbdCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <sdf/sdf.hh>

#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>

#include "ignition/sensors/CameraSensor.hh"
#include "ignition/sensors/config.hh"
Expand Down Expand Up @@ -94,11 +94,11 @@ namespace ignition
/// \return True on success.
private: bool CreateCameras();

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<RgbdCameraSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
6 changes: 3 additions & 3 deletions include/ignition/sensors/SegmentationCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include <ignition/common/Event.hh>
#include <ignition/common/PluginMacros.hh>
#include <ignition/common/SuppressWarning.hh>
#include <ignition/utils/SuppressWarning.hh>
#include <ignition/msgs.hh>
#include <ignition/transport/Node.hh>
#include <ignition/transport/Publisher.hh>
Expand Down Expand Up @@ -122,11 +122,11 @@ namespace ignition
/// \return True on success.
private: bool CreateCamera();

IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING
/// \brief Data pointer for private data
/// \internal
private: std::unique_ptr<SegmentationCameraSensorPrivate> dataPtr;
IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING
IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING
};
}
}
Expand Down
Loading

0 comments on commit b1f78a5

Please sign in to comment.