diff --git a/include/ignition/sensors/AirPressureSensor.hh b/include/ignition/sensors/AirPressureSensor.hh index d3db6b8b..4655944a 100644 --- a/include/ignition/sensors/AirPressureSensor.hh +++ b/include/ignition/sensors/AirPressureSensor.hh @@ -21,6 +21,7 @@ #include +#include #include #include @@ -84,9 +85,11 @@ namespace ignition /// \return Verical reference position in meters public: double ReferenceAltitude() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/AltimeterSensor.hh b/include/ignition/sensors/AltimeterSensor.hh index af582786..59ec82f7 100644 --- a/include/ignition/sensors/AltimeterSensor.hh +++ b/include/ignition/sensors/AltimeterSensor.hh @@ -21,6 +21,7 @@ #include +#include #include #include @@ -101,9 +102,11 @@ namespace ignition /// \return Vertical velocity in meters per second public: double VerticalVelocity() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/CameraSensor.hh b/include/ignition/sensors/CameraSensor.hh index 6da658fc..f7d565ef 100644 --- a/include/ignition/sensors/CameraSensor.hh +++ b/include/ignition/sensors/CameraSensor.hh @@ -23,10 +23,18 @@ #include -#include +#include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + #include #include "ignition/sensors/camera/Export.hh" @@ -162,9 +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 /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/DepthCameraSensor.hh b/include/ignition/sensors/DepthCameraSensor.hh index e5fd8f45..4116e5b4 100644 --- a/include/ignition/sensors/DepthCameraSensor.hh +++ b/include/ignition/sensors/DepthCameraSensor.hh @@ -24,11 +24,17 @@ #include #include - -#include +#include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include @@ -158,9 +164,12 @@ namespace ignition private: void OnSceneChange(ignition::rendering::ScenePtr /*_scene*/) { } + + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/GpuLidarSensor.hh b/include/ignition/sensors/GpuLidarSensor.hh index a7376192..9031a47b 100644 --- a/include/ignition/sensors/GpuLidarSensor.hh +++ b/include/ignition/sensors/GpuLidarSensor.hh @@ -22,6 +22,8 @@ #include +#include + #include #include "ignition/sensors/gpu_lidar/Export.hh" @@ -123,9 +125,11 @@ namespace ignition unsigned int _heighti, unsigned int _channels, const std::string &/*_format*/)> _subscriber) override; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/ImuSensor.hh b/include/ignition/sensors/ImuSensor.hh index c490d0dc..51e9f77f 100644 --- a/include/ignition/sensors/ImuSensor.hh +++ b/include/ignition/sensors/ImuSensor.hh @@ -21,6 +21,7 @@ #include +#include #include #include @@ -128,9 +129,11 @@ namespace ignition /// \return Gravity vectory in meters per second squared. public: math::Vector3d Gravity() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/Lidar.hh b/include/ignition/sensors/Lidar.hh index 44f5c780..bcbb587d 100644 --- a/include/ignition/sensors/Lidar.hh +++ b/include/ignition/sensors/Lidar.hh @@ -21,6 +21,7 @@ #include #include +#include #include #include "ignition/sensors/lidar/Export.hh" @@ -242,8 +243,10 @@ namespace ignition // Documentation inherited public: virtual bool IsActive() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Just a mutex for thread safety public: mutable std::mutex lidarMutex; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING /// \brief Raw buffer of laser data. public: float *laserBuffer = nullptr; @@ -263,9 +266,11 @@ namespace ignition unsigned int _heighti, unsigned int _channels, const std::string &/*_format*/)> _subscriber); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/LogicalCameraSensor.hh b/include/ignition/sensors/LogicalCameraSensor.hh index 54a1b179..d67ba66c 100644 --- a/include/ignition/sensors/LogicalCameraSensor.hh +++ b/include/ignition/sensors/LogicalCameraSensor.hh @@ -23,12 +23,20 @@ #include -#include +#include +#include #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include "ignition/sensors/config.hh" #include "ignition/sensors/Export.hh" @@ -110,9 +118,11 @@ namespace ignition /// \return List of detected models. public: msgs::LogicalCameraImage Image() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/MagnetometerSensor.hh b/include/ignition/sensors/MagnetometerSensor.hh index fe077167..fe0f483b 100644 --- a/include/ignition/sensors/MagnetometerSensor.hh +++ b/include/ignition/sensors/MagnetometerSensor.hh @@ -21,6 +21,7 @@ #include +#include #include #include @@ -97,9 +98,11 @@ namespace ignition /// \return Magnetic field vector in body frame public: math::Vector3d MagneticField() const; + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/Manager.hh b/include/ignition/sensors/Manager.hh index 75dd14b7..03619302 100644 --- a/include/ignition/sensors/Manager.hh +++ b/include/ignition/sensors/Manager.hh @@ -22,6 +22,7 @@ #include #include #include +#include #include #include #include @@ -153,6 +154,14 @@ namespace ignition /// is returned on erro. public: ignition::sensors::SensorId CreateSensor(sdf::ElementPtr _sdf); + /// \brief Add a sensor from a sensor instance. + /// \sa Sensor() + /// \param[in] _sensor pointer to the sensor + /// \return A sensor id that refers to the created sensor. NO_SENSOR + /// is returned on error. + public: ignition::sensors::SensorId AddSensor( + std::unique_ptr _sensor); + /// \brief Create a sensor from SDF without a known sensor type. /// /// This creates sensors by looking at the given sdf element. @@ -207,8 +216,10 @@ namespace ignition private: ignition::sensors::SensorId LoadSensorPlugin( const std::string &_filename, sdf::ElementPtr _sdf); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/RenderingEvents.hh b/include/ignition/sensors/RenderingEvents.hh index f9959863..393940ba 100644 --- a/include/ignition/sensors/RenderingEvents.hh +++ b/include/ignition/sensors/RenderingEvents.hh @@ -19,6 +19,7 @@ #define IGNITION_SENSORS_RENDERINGEVENTS_HH_ #include +#include #include #include #include @@ -43,10 +44,12 @@ namespace ignition std::function _callback); + IGN_COMMON_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 }; } } diff --git a/include/ignition/sensors/RenderingSensor.hh b/include/ignition/sensors/RenderingSensor.hh index 36df85e3..504b0daa 100644 --- a/include/ignition/sensors/RenderingSensor.hh +++ b/include/ignition/sensors/RenderingSensor.hh @@ -19,6 +19,8 @@ #include +#include + #include #include @@ -76,9 +78,11 @@ namespace ignition /// \param[in] _sensor Sensor to add. protected: void AddSensor(rendering::SensorPtr _sensor); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \internal /// \brief Data pointer for private data private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/RgbdCameraSensor.hh b/include/ignition/sensors/RgbdCameraSensor.hh index 17c563a2..d38deab6 100644 --- a/include/ignition/sensors/RgbdCameraSensor.hh +++ b/include/ignition/sensors/RgbdCameraSensor.hh @@ -21,6 +21,7 @@ #include +#include #include #include "ignition/sensors/CameraSensor.hh" @@ -62,6 +63,11 @@ namespace ignition /// \return true if loading was successful public: virtual bool Load(const sdf::Sensor &_sdf) override; + /// \brief Load the sensor with SDF parameters. + /// \param[in] _sdf SDF Sensor parameters. + /// \return true if loading was successful + public: virtual bool Load(sdf::ElementPtr _sdf) override; + /// \brief Initialize values in the sensor /// \return True on success public: virtual bool Init() override; @@ -95,9 +101,11 @@ namespace ignition /// \return True on success. private: bool CreateCameras(); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/Sensor.hh b/include/ignition/sensors/Sensor.hh index adcc1db8..144f1438 100644 --- a/include/ignition/sensors/Sensor.hh +++ b/include/ignition/sensors/Sensor.hh @@ -17,11 +17,19 @@ #ifndef IGNITION_SENSORS_SENSOR_HH_ #define IGNITION_SENSORS_SENSOR_HH_ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include +#include #include #include #include @@ -210,9 +218,11 @@ namespace ignition public: void AddSequence(ignition::msgs::Header *_msg, const std::string &_seqKey = "default"); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \internal /// \brief Data pointer for private data private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/include/ignition/sensors/SensorFactory.hh b/include/ignition/sensors/SensorFactory.hh index 365566fe..73fe7e72 100644 --- a/include/ignition/sensors/SensorFactory.hh +++ b/include/ignition/sensors/SensorFactory.hh @@ -23,7 +23,8 @@ #include #include -#include +#include +#include #include #include @@ -42,9 +43,6 @@ namespace ignition /// \brief Base sensor plugin interface class IGNITION_SENSORS_VISIBLE SensorPlugin { - /// \brief Allows using shorter APIS in common::PluginLoader - public: IGN_COMMON_SPECIALIZE_INTERFACE(ignition::sensors::SensorPlugin) - /// \brief Instantiate new sensor /// \return New sensor public: virtual Sensor *New() = 0; @@ -176,13 +174,15 @@ namespace ignition private: std::shared_ptr LoadSensorPlugin( const std::string &_filename); + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief private data pointer private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; /// \brief Sensor registration macro #define IGN_SENSORS_REGISTER_SENSOR(classname) \ - IGN_COMMON_REGISTER_SINGLE_PLUGIN(\ + IGNITION_ADD_PLUGIN(\ ignition::sensors::SensorTypePlugin, \ ignition::sensors::SensorPlugin) } diff --git a/include/ignition/sensors/ThermalCameraSensor.hh b/include/ignition/sensors/ThermalCameraSensor.hh index 3eab5123..53d2571a 100644 --- a/include/ignition/sensors/ThermalCameraSensor.hh +++ b/include/ignition/sensors/ThermalCameraSensor.hh @@ -24,11 +24,17 @@ #include #include - -#include +#include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include @@ -162,9 +168,11 @@ namespace ignition private: void OnSceneChange(ignition::rendering::ScenePtr /*_scene*/) { } + IGN_COMMON_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Data pointer for private data /// \internal private: std::unique_ptr dataPtr; + IGN_COMMON_WARN_RESUME__DLL_INTERFACE_MISSING }; } } diff --git a/src/AirPressureSensor.cc b/src/AirPressureSensor.cc index cbdf5124..2cfa0de1 100644 --- a/src/AirPressureSensor.cc +++ b/src/AirPressureSensor.cc @@ -15,10 +15,20 @@ * */ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + #include #include +#include + #include "ignition/sensors/GaussianNoiseModel.hh" #include "ignition/sensors/Noise.hh" #include "ignition/sensors/SensorTypes.hh" diff --git a/src/AltimeterSensor.cc b/src/AltimeterSensor.cc index 7d29a9b7..1724da97 100644 --- a/src/AltimeterSensor.cc +++ b/src/AltimeterSensor.cc @@ -16,12 +16,13 @@ */ #include +#include #include +#include "ignition/sensors/AltimeterSensor.hh" #include "ignition/sensors/Noise.hh" -#include "ignition/sensors/SensorTypes.hh" #include "ignition/sensors/SensorFactory.hh" -#include "ignition/sensors/AltimeterSensor.hh" +#include "ignition/sensors/SensorTypes.hh" using namespace ignition; using namespace sensors; diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index bde2e842..f78905c9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -8,6 +8,19 @@ set (sources SensorTypes.cc ) +set(rendering_sources + RenderingSensor.cc + RenderingEvents.cc + ImageGaussianNoiseModel.cc + ImageNoise.cc +) + +set (gtest_sources + Manager_TEST.cc + Noise_TEST.cc + Sensor_TEST.cc +) + # Create the library target. ign_create_core_library(SOURCES ${sources} CXX_STANDARD 14) @@ -19,23 +32,47 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} ignition-math${IGN_MATH_VER}::ignition-math${IGN_MATH_VER} ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} + ignition-plugin${IGN_PLUGIN_VER}::loader sdformat${SDF_VER}::sdformat${SDF_VER} PRIVATE ignition-common${IGN_COMMON_VER}::profiler ) - -set(rendering_sources - RenderingSensor.cc - RenderingEvents.cc - ImageGaussianNoiseModel.cc - ImageNoise.cc -) +target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC DepthPoints_EXPORTS) ign_add_component(rendering SOURCES ${rendering_sources} GET_TARGET_NAME rendering_target) target_link_libraries(${rendering_target} PUBLIC ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER} - ) +) + +if (MSVC) + # Warning #4251 is the "dll-interface" warning that tells you when types used + # by a class are not being exported. These generated source files have private + # members that don't get exported, so they trigger this warning. However, the + # warning is not important since those members do not need to be interfaced + # with. + set_source_files_properties( + ${gtest_sources} + ${rendering_sources} + ${sources} + AirPressureSensor.cc + AltimeterSensor.cc + Camera.cc + CameraSensor.cc + Camera_TEST.cc + DepthCameraSensor.cc + GpuLidarSensor.cc + ImuSensor.cc + ImuSensor_TEST.cc + Lidar.cc + Lidar_TEST.cc + LogicalCameraSensor.cc + MagnetometerSensor.cc + RgbdCameraSensor.cc + ThermalCameraSensor.cc + COMPILE_FLAGS "/wd4251 /wd4146" + ) +endif() set(camera_sources CameraSensor.cc) @@ -47,9 +84,10 @@ target_link_libraries(${camera_target} PUBLIC ${rendering_target} PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) +) set(depth_camera_sources DepthCameraSensor.cc) ign_add_component(depth_camera SOURCES ${depth_camera_sources} GET_TARGET_NAME depth_camera_target) @@ -59,7 +97,7 @@ target_link_libraries(${depth_camera_target} ${camera_target} ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) +) set(lidar_sources Lidar.cc) ign_add_component(lidar SOURCES ${lidar_sources} GET_TARGET_NAME lidar_target) @@ -68,9 +106,10 @@ target_link_libraries(${lidar_target} PUBLIC ${rendering_target} PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) +) set(gpu_lidar_sources GpuLidarSensor.cc) ign_add_component(gpu_lidar SOURCES ${gpu_lidar_sources} GET_TARGET_NAME gpu_lidar_target) @@ -80,28 +119,45 @@ target_link_libraries(${gpu_lidar_target} ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} ${lidar_target} - ) +) set(logical_camera_sources LogicalCameraSensor.cc) ign_add_component(logical_camera SOURCES ${logical_camera_sources} GET_TARGET_NAME logical_camera_target) target_compile_definitions(${logical_camera_target} PUBLIC LogicalCameraSensor_EXPORTS) target_link_libraries(${logical_camera_target} PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) +) set(magnetometer_sources MagnetometerSensor.cc) ign_add_component(magnetometer SOURCES ${magnetometer_sources} GET_TARGET_NAME magnetometer_target) +target_link_libraries(${magnetometer_target} + PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register +) set(imu_sources ImuSensor.cc) ign_add_component(imu SOURCES ${imu_sources} GET_TARGET_NAME imu_target) +target_link_libraries(${imu_target} + PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register +) set(altimeter_sources AltimeterSensor.cc) ign_add_component(altimeter SOURCES ${altimeter_sources} GET_TARGET_NAME altimeter_target) +target_link_libraries(${altimeter_target} + PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register +) set(air_pressure_sources AirPressureSensor.cc) ign_add_component(air_pressure SOURCES ${air_pressure_sources} GET_TARGET_NAME air_pressure_target) +target_link_libraries(${air_pressure_target} + PRIVATE + ignition-plugin${IGN_PLUGIN_VER}::register +) set(rgbd_camera_sources RgbdCameraSensor.cc) ign_add_component(rgbd_camera SOURCES ${rgbd_camera_sources} GET_TARGET_NAME rgbd_camera_target) @@ -111,7 +167,7 @@ target_link_libraries(${rgbd_camera_target} ${camera_target} ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) +) set(thermal_camera_sources ThermalCameraSensor.cc) ign_add_component(thermal_camera SOURCES ${thermal_camera_sources} GET_TARGET_NAME thermal_camera_target) @@ -120,13 +176,6 @@ target_link_libraries(${thermal_camera_target} ${camera_target} ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} - ) - - -set (gtest_sources - Manager_TEST.cc - Noise_TEST.cc - Sensor_TEST.cc ) # Build the unit tests. diff --git a/src/CameraSensor.cc b/src/CameraSensor.cc index 3e3046d1..5421ec64 100644 --- a/src/CameraSensor.cc +++ b/src/CameraSensor.cc @@ -14,7 +14,14 @@ * limitations under the License. * */ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include @@ -24,9 +31,9 @@ #include #include #include -#include - #include +#include +#include #include "ignition/sensors/CameraSensor.hh" #include "ignition/sensors/ImageGaussianNoiseModel.hh" diff --git a/src/Camera_TEST.cc b/src/Camera_TEST.cc index 521070b2..f6118133 100644 --- a/src/Camera_TEST.cc +++ b/src/Camera_TEST.cc @@ -17,9 +17,9 @@ #include #include -#include -#include -#include +#include "ignition/sensors/CameraSensor.hh" +#include "ignition/sensors/Export.hh" +#include "ignition/sensors/Manager.hh" sdf::ElementPtr cameraToBadSdf() { @@ -126,14 +126,13 @@ sdf::ElementPtr CameraToSdf(const std::string &_type, ////////////////////////////////////////////////// TEST(Camera_TEST, CreateCamera) { - ignition::sensors::Manager mgr; - sdf::ElementPtr camSdf = CameraToSdf("camera", "my_camera", 60.0, "/cam", true, true); // Create a CameraSensor - ignition::sensors::CameraSensor *cam = - mgr.CreateSensor(camSdf); + std::unique_ptr cam = + std::make_unique(); + EXPECT_TRUE(cam->Load(camSdf)); // Make sure the above dynamic cast worked. EXPECT_TRUE(cam != nullptr); @@ -152,9 +151,9 @@ TEST(Camera_TEST, CreateCamera) sdf::ElementPtr camBadSdf = cameraToBadSdf(); // Create a CameraSensor - ignition::sensors::CameraSensor *badCam = - mgr.CreateSensor(camBadSdf); - EXPECT_TRUE(badCam == nullptr); + std::unique_ptr badCam = + std::make_unique(); + EXPECT_FALSE(badCam->Load(camBadSdf)); } ///////////////////////////////////////////////// @@ -175,7 +174,12 @@ TEST(Camera_TEST, Topic) auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(cameraSdf); + // Create a CameraSensor + std::unique_ptr cam = + std::make_unique(); + EXPECT_TRUE(cam->Load(cameraSdf)); + + auto sensorId = mgr.AddSensor(std::move(cam)); EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId); auto sensor = mgr.Sensor(sensorId); @@ -193,7 +197,13 @@ TEST(Camera_TEST, Topic) auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(cameraSdf); + // Create a CameraSensor + std::unique_ptr cam = + std::make_unique(); + EXPECT_TRUE(cam->Load(cameraSdf)); + + auto sensorId = mgr.AddSensor(std::move(cam)); + EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId); auto sensor = mgr.Sensor(sensorId); @@ -211,7 +221,15 @@ TEST(Camera_TEST, Topic) auto cameraSdf = CameraToSdf(type, name, updateRate, topic, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(cameraSdf); + // Create a CameraSensor + std::unique_ptr cam = + std::make_unique(); + EXPECT_FALSE(cam->Load(cameraSdf)); + + cam = nullptr; + + auto sensorId = mgr.AddSensor(std::move(cam)); + EXPECT_EQ(ignition::sensors::NO_SENSOR, sensorId); } } diff --git a/src/DepthCameraSensor.cc b/src/DepthCameraSensor.cc index d78822e4..b5e37399 100644 --- a/src/DepthCameraSensor.cc +++ b/src/DepthCameraSensor.cc @@ -14,8 +14,14 @@ * limitations under the License. * */ - +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include @@ -27,6 +33,8 @@ #include #include +#include + #include #include "ignition/sensors/DepthCameraSensor.hh" @@ -160,7 +168,7 @@ bool DepthCameraSensorPrivate::ConvertDepthToImage( double factor = 255 / maxDepth; for (unsigned int j = 0; j < _height * _width; ++j) { - unsigned char d = 255 - (_data[j] * factor); + unsigned char d = static_cast(255 - (_data[j] * factor)); _imageBuffer[j * 3] = d; _imageBuffer[j * 3 + 1] = d; _imageBuffer[j * 3 + 2] = d; diff --git a/src/GpuLidarSensor.cc b/src/GpuLidarSensor.cc index 548e8d2a..12fb58bd 100644 --- a/src/GpuLidarSensor.cc +++ b/src/GpuLidarSensor.cc @@ -14,12 +14,22 @@ * limitations under the License. * */ + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include -#include -#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include +#include +#include +#include + #include "ignition/sensors/GpuLidarSensor.hh" #include "ignition/sensors/SensorFactory.hh" diff --git a/src/ImuSensor.cc b/src/ImuSensor.cc index 2c9103f4..df8119fb 100644 --- a/src/ImuSensor.cc +++ b/src/ImuSensor.cc @@ -14,15 +14,23 @@ * limitations under the License. * */ - +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + #include +#include #include +#include "ignition/sensors/ImuSensor.hh" #include "ignition/sensors/Noise.hh" #include "ignition/sensors/SensorFactory.hh" #include "ignition/sensors/SensorTypes.hh" -#include "ignition/sensors/ImuSensor.hh" using namespace ignition; using namespace sensors; diff --git a/src/ImuSensor_TEST.cc b/src/ImuSensor_TEST.cc index 8ee8fd02..a9e77f90 100644 --- a/src/ImuSensor_TEST.cc +++ b/src/ImuSensor_TEST.cc @@ -18,11 +18,18 @@ #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include -#include -#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif -#include +#include "ignition/sensors/Export.hh" +#include "ignition/sensors/ImuSensor.hh" +#include "ignition/sensors/Manager.hh" using namespace ignition; @@ -177,9 +184,6 @@ sdf::ElementPtr ImuSensorToSDF(const std::string &name, double update_rate, ////////////////////////////////////////////////// TEST(ImuSensor_TEST, CreateImuSensor) { - // Create a sensor manager - ignition::sensors::Manager mgr; - const std::string name = "TestImu"; const std::string topic = "/ignition/sensors/test/imu"; const double update_rate = 100; @@ -191,19 +195,14 @@ TEST(ImuSensor_TEST, CreateImuSensor) sdf::ElementPtr imuSDF = ImuSensorToSDF(name, update_rate, topic, accelNoise, gyroNoise, always_on, visualize); - // Create an ImuSensor - auto sensor = mgr.CreateSensor(imuSDF); - - // Make sure the above dynamic cast worked. - EXPECT_TRUE(sensor != nullptr); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(imuSDF)); } ////////////////////////////////////////////////// TEST(ImuSensor_TEST, ComputeNoise) { - // Create a sensor manager - ignition::sensors::Manager mgr; - sdf::ElementPtr imuSDF, imuSDF_truth; { @@ -235,10 +234,13 @@ TEST(ImuSensor_TEST, ComputeNoise) accelNoise, gyroNoise, always_on, visualize); } - // Create an ImuSensor - auto sensor_truth = mgr.CreateSensor( - imuSDF_truth); - auto sensor = mgr.CreateSensor(imuSDF); + std::unique_ptr sensor_truth = + std::make_unique(); + EXPECT_TRUE(sensor_truth->Load(imuSDF_truth)); + + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(imuSDF)); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); @@ -301,7 +303,3 @@ int main(int argc, char **argv) ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } - - - - diff --git a/src/Lidar.cc b/src/Lidar.cc index b5c6147a..6e55f70f 100644 --- a/src/Lidar.cc +++ b/src/Lidar.cc @@ -17,14 +17,15 @@ #include #include #include +#include #include #include +#include "ignition/sensors/GaussianNoiseModel.hh" #include "ignition/sensors/Lidar.hh" #include "ignition/sensors/Noise.hh" #include "ignition/sensors/SensorFactory.hh" #include "ignition/sensors/SensorTypes.hh" -#include "ignition/sensors/GaussianNoiseModel.hh" using namespace ignition::sensors; @@ -340,7 +341,8 @@ unsigned int Lidar::RayCount() const ////////////////////////////////////////////////// unsigned int Lidar::RangeCount() const { - return this->RayCount() * this->dataPtr->sdfLidar.HorizontalScanResolution(); + return static_cast(this->RayCount() * + this->dataPtr->sdfLidar.HorizontalScanResolution()); } ////////////////////////////////////////////////// @@ -352,12 +354,12 @@ unsigned int Lidar::VerticalRayCount() const ////////////////////////////////////////////////// unsigned int Lidar::VerticalRangeCount() const { - int rows = this->VerticalRayCount() * - this->dataPtr->sdfLidar.VerticalScanResolution(); + unsigned int rows = static_cast(this->VerticalRayCount() * + this->dataPtr->sdfLidar.VerticalScanResolution()); if (rows > 1) return rows; else - return 1; + return 1u; } ////////////////////////////////////////////////// diff --git a/src/Lidar_TEST.cc b/src/Lidar_TEST.cc index 27fe6a4c..e82cd4f2 100644 --- a/src/Lidar_TEST.cc +++ b/src/Lidar_TEST.cc @@ -19,12 +19,18 @@ #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include -#include -#include - -#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif +#include "ignition/sensors/Export.hh" +#include "ignition/sensors/Manager.hh" +#include "ignition/sensors/Lidar.hh" sdf::ElementPtr LidarToSDF(const std::string &name, double update_rate, const std::string &topic, double horz_samples, double horz_resolution, @@ -93,9 +99,6 @@ void OnNewLaserFrame(int *_scanCounter, float *_scanDest, /// \brief Test Creation of a Lidar sensor TEST(Lidar_TEST, CreateLaser) { - // Create a sensor manager - ignition::sensors::Manager mgr; - // Create SDF describing a camera sensor const std::string name = "TestLidar"; const std::string topic = "/ignition/sensors/test/lidar"; @@ -119,9 +122,9 @@ TEST(Lidar_TEST, CreateLaser) vert_samples, vert_resolution, vert_min_angle, vert_max_angle, range_resolution, range_min, range_max, always_on, visualize); - // Create a CameraSensor - ignition::sensors::Lidar *sensor = mgr.CreateSensor( - lidarSDF); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(lidarSDF)); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); diff --git a/src/LogicalCameraSensor.cc b/src/LogicalCameraSensor.cc index 75294581..cd1fbc3e 100644 --- a/src/LogicalCameraSensor.cc +++ b/src/LogicalCameraSensor.cc @@ -25,6 +25,8 @@ #include #include +#include + #include "ignition/sensors/SensorFactory.hh" #include "ignition/sensors/LogicalCameraSensor.hh" diff --git a/src/MagnetometerSensor.cc b/src/MagnetometerSensor.cc index 325b92df..64a5effc 100644 --- a/src/MagnetometerSensor.cc +++ b/src/MagnetometerSensor.cc @@ -15,15 +15,24 @@ * */ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif + #include +#include #include #include +#include "ignition/sensors/MagnetometerSensor.hh" #include "ignition/sensors/Noise.hh" #include "ignition/sensors/SensorFactory.hh" #include "ignition/sensors/SensorTypes.hh" -#include "ignition/sensors/MagnetometerSensor.hh" using namespace ignition; using namespace sensors; diff --git a/src/Manager.cc b/src/Manager.cc index 9f337279..d3ec3a23 100644 --- a/src/Manager.cc +++ b/src/Manager.cc @@ -18,8 +18,7 @@ #include "ignition/sensors/Manager.hh" #include #include -#include -#include +#include #include #include #include @@ -108,6 +107,17 @@ void Manager::RunOnce( } } +///////////////////////////////////////////////// +ignition::sensors::SensorId Manager::AddSensor( + std::unique_ptr _sensor) +{ + if (!_sensor) + return NO_SENSOR; + SensorId id = _sensor->Id(); + this->dataPtr->sensors[id] = std::move(_sensor); + return id; +} + ///////////////////////////////////////////////// ignition::sensors::SensorId Manager::CreateSensor(const sdf::Sensor &_sdf) { diff --git a/src/Manager_TEST.cc b/src/Manager_TEST.cc index 791b303e..f6d1213d 100644 --- a/src/Manager_TEST.cc +++ b/src/Manager_TEST.cc @@ -16,8 +16,8 @@ */ #include -#include +#include "ignition/sensors/Manager.hh" ////////////////////////////////////////////////// TEST(Manager, construct) diff --git a/src/Noise.cc b/src/Noise.cc index 10f589ba..4d25945a 100644 --- a/src/Noise.cc +++ b/src/Noise.cc @@ -23,9 +23,10 @@ #include -#include #include -#include + +#include "ignition/sensors/GaussianNoiseModel.hh" +#include "ignition/sensors/Noise.hh" using namespace ignition; using namespace sensors; diff --git a/src/PointCloudUtil.hh b/src/PointCloudUtil.hh index 46ad45b0..2339fa92 100644 --- a/src/PointCloudUtil.hh +++ b/src/PointCloudUtil.hh @@ -18,7 +18,14 @@ #ifndef IGNITION_SENSORS_POINTCLOUDUTIL_HH_ #define IGNITION_SENSORS_POINTCLOUDUTIL_HH_ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include "ignition/sensors/config.hh" diff --git a/src/RgbdCameraSensor.cc b/src/RgbdCameraSensor.cc index 48ce5af3..4b3720b7 100644 --- a/src/RgbdCameraSensor.cc +++ b/src/RgbdCameraSensor.cc @@ -15,13 +15,22 @@ * */ +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include #include +#include + #include #include #include @@ -156,6 +165,14 @@ bool RgbdCameraSensor::Init() return this->Sensor::Init(); } +////////////////////////////////////////////////// +bool RgbdCameraSensor::Load(sdf::ElementPtr _sdf) +{ + sdf::Sensor sdfSensor; + sdfSensor.Load(_sdf); + return this->Load(sdfSensor); +} + ////////////////////////////////////////////////// bool RgbdCameraSensor::Load(const sdf::Sensor &_sdf) { diff --git a/src/Sensor.cc b/src/Sensor.cc index 11400628..cfbacea3 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -18,11 +18,12 @@ #include "ignition/sensors/Sensor.hh" #include #include -#include #include #include #include +#include "ignition/sensors/Manager.hh" + using namespace ignition::sensors; diff --git a/src/SensorFactory.cc b/src/SensorFactory.cc index b6cb27bf..2286703d 100644 --- a/src/SensorFactory.cc +++ b/src/SensorFactory.cc @@ -15,7 +15,6 @@ * */ -#include #include #include #include "ignition/sensors/config.hh" @@ -35,7 +34,7 @@ class ignition::sensors::SensorFactoryPrivate public: ignition::common::SystemPaths systemPaths; /// \brief For loading plugins - public: ignition::common::PluginLoader pluginLoader; + public: ignition::plugin::Loader pluginLoader; }; using namespace ignition; @@ -75,17 +74,22 @@ std::shared_ptr SensorFactory::LoadSensorPlugin( return std::shared_ptr(); } - auto pluginNames = this->dataPtr->pluginLoader.LoadLibrary(fullPath); + auto pluginNames = this->dataPtr->pluginLoader.LoadLib(fullPath); + if (pluginNames.empty()) { ignerr << "Unable to load sensor plugin file for [" << fullPath << "]\n"; return std::shared_ptr(); } - // Assume the first plugin is the one we're interested in - std::string pluginName = *(pluginNames.begin()); + // Assume the last plugin is the one we're interested in + std::string pluginName = ""; + for (auto name : pluginNames) + { + pluginName = name; + } - common::PluginPtr pluginPtr = + plugin::PluginPtr pluginPtr = this->dataPtr->pluginLoader.Instantiate(pluginName); auto sensorPlugin = pluginPtr->QueryInterfaceSharedPtr< diff --git a/src/Sensor_TEST.cc b/src/Sensor_TEST.cc index e1493f30..89acffd3 100644 --- a/src/Sensor_TEST.cc +++ b/src/Sensor_TEST.cc @@ -16,8 +16,8 @@ */ #include -#include -#include +#include "ignition/sensors/Export.hh" +#include "ignition/sensors/Sensor.hh" using namespace ignition; using namespace sensors; diff --git a/src/ThermalCameraSensor.cc b/src/ThermalCameraSensor.cc index 1b40c67b..cb9299a1 100644 --- a/src/ThermalCameraSensor.cc +++ b/src/ThermalCameraSensor.cc @@ -14,7 +14,15 @@ * limitations under the License. * */ + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include @@ -27,6 +35,8 @@ #include #include +#include + #include #include "ignition/sensors/ThermalCameraSensor.hh" @@ -130,7 +140,7 @@ class ignition::sensors::ThermalCameraSensorPrivate public: float maxTemp = ignition::math::INF_F; /// \brief Linear resolution. Defaults to 10mK - public: float resolution = 0.01; + public: float resolution = 0.01f; }; using namespace ignition; @@ -530,7 +540,7 @@ bool ThermalCameraSensorPrivate::ConvertTemperatureToImage( { uint16_t temp = _data[i*_width + j]; double t = static_cast(temp-*min) / range; - int r = 255*t; + int r = static_cast(255*t); int g = r; int b = r; int index = i*_width*3 + j*3; diff --git a/test/gtest/src/gtest.cc b/test/gtest/src/gtest.cc index ac21ea4b..5e8c3c41 100644 --- a/test/gtest/src/gtest.cc +++ b/test/gtest/src/gtest.cc @@ -30,7 +30,9 @@ // // The Google C++ Testing and Mocking Framework (Google Test) +#ifndef _WIN32 #pragma GCC system_header +#endif #include "gtest/gtest.h" #include "gtest/internal/custom/gtest.h" diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 51802cd5..d915fd23 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -16,6 +16,19 @@ set(tests imu_plugin.cc ) +if (MSVC) + # Warning #4251 is the "dll-interface" warning that tells you when types used + # by a class are not being exported. These generated source files have private + # members that don't get exported, so they trigger this warning. However, the + # warning is not important since those members do not need to be interfaced + # with. + set_source_files_properties( + ${tests} + ${dri_tests} + COMPILE_FLAGS "/wd4251 /wd4146" + ) +endif() + link_directories(${PROJECT_BINARY_DIR}/test) include_directories(${PROJECT_SOURCE_DIR}/src) @@ -52,4 +65,3 @@ ign_build_tests(TYPE INTEGRATION ${PROJECT_LIBRARY_TARGET_NAME}-magnetometer ${PROJECT_LIBRARY_TARGET_NAME}-imu ) - diff --git a/test/integration/TransportTestTools.hh b/test/integration/TransportTestTools.hh index 9281b961..60930860 100644 --- a/test/integration/TransportTestTools.hh +++ b/test/integration/TransportTestTools.hh @@ -24,6 +24,8 @@ #include +using namespace std::chrono_literals; + /// \brief class which simplifies waiting for a message to be received template class WaitForMessageTestHelper @@ -34,9 +36,14 @@ class WaitForMessageTestHelper { if (this->node.Subscribe(_topic, &WaitForMessageTestHelper::OnMessage, this)) + { this->subscriptionCreated = true; + } else + { + std::cerr << "Failed to create subscription to " << _topic << '\n'; this->diagnostics = "Failed to create subscription to " + _topic; + } } protected: void OnMessage(const M &_msg) @@ -56,7 +63,13 @@ class WaitForMessageTestHelper std::unique_lock lock(this->mtx); if (this->subscriptionCreated) { - this->conditionVariable.wait(lock, [this]{return this->gotMessage;}); + if (this->conditionVariable.wait_for( + lock, + 1s, + [this]{return this->gotMessage;})) + { + this->diagnostics = "WaitForMessage timeout"; + } } bool success = this->gotMessage; this->gotMessage = false; diff --git a/test/integration/air_pressure_plugin.cc b/test/integration/air_pressure_plugin.cc index c48fefe2..679b3597 100644 --- a/test/integration/air_pressure_plugin.cc +++ b/test/integration/air_pressure_plugin.cc @@ -126,17 +126,19 @@ TEST_F(AirPressureSensorTest, CreateAirPressure) // create the sensor using sensor factory ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); + std::unique_ptr sensor = - sf.CreateSensor(airPressureSdf); - EXPECT_TRUE(sensor != nullptr); + std::make_unique(); + EXPECT_TRUE(sensor->Load(airPressureSdf)); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); EXPECT_DOUBLE_EQ(updateRate, sensor->UpdateRate()); std::unique_ptr sensorNoise = - sf.CreateSensor( - airPressureSdfNoise); + std::make_unique(); + EXPECT_TRUE(sensorNoise->Load(airPressureSdfNoise)); + EXPECT_TRUE(sensorNoise != nullptr); EXPECT_EQ(name, sensorNoise->Name()); @@ -168,16 +170,23 @@ TEST_F(AirPressureSensorTest, SensorReadings) // try creating without specifying the sensor type and then cast it ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - std::unique_ptr s = - sf.CreateSensor(airPressureSdf); + + std::unique_ptr s = + std::make_unique(); + EXPECT_TRUE(s->Load(airPressureSdf)); + EXPECT_TRUE(s->Init()); + std::unique_ptr sensor( dynamic_cast(s.release())); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); - std::unique_ptr sNoise = - sf.CreateSensor(airPressureSdfNoise); + std::unique_ptr sNoise = + std::make_unique(); + EXPECT_TRUE(sNoise->Load(airPressureSdfNoise)); + EXPECT_TRUE(sNoise->Init()); + std::unique_ptr sensorNoise( dynamic_cast(sNoise.release())); @@ -243,9 +252,9 @@ TEST_F(AirPressureSensorTest, Topic) auto airPressureSdf = AirPressureToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(airPressureSdf); - EXPECT_NE(nullptr, sensor); - + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(airPressureSdf)); auto airPressure = dynamic_cast(sensor.release()); ASSERT_NE(nullptr, airPressure); @@ -259,8 +268,9 @@ TEST_F(AirPressureSensorTest, Topic) auto airPressureSdf = AirPressureToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(airPressureSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(airPressureSdf)); auto airPressure = dynamic_cast(sensor.release()); @@ -275,8 +285,9 @@ TEST_F(AirPressureSensorTest, Topic) auto airPressureSdf = AirPressureToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(airPressureSdf); - ASSERT_EQ(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_FALSE(sensor->Load(airPressureSdf)); } } diff --git a/test/integration/altimeter_plugin.cc b/test/integration/altimeter_plugin.cc index ab202a81..3c4ad07c 100644 --- a/test/integration/altimeter_plugin.cc +++ b/test/integration/altimeter_plugin.cc @@ -133,17 +133,18 @@ TEST_F(AltimeterSensorTest, CreateAltimeter) // create the sensor using sensor factory ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); + std::unique_ptr sensor = - sf.CreateSensor(altimeterSdf); - EXPECT_TRUE(sensor != nullptr); + std::make_unique(); + EXPECT_TRUE(sensor->Load(altimeterSdf)); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); EXPECT_DOUBLE_EQ(updateRate, sensor->UpdateRate()); std::unique_ptr sensorNoise = - sf.CreateSensor(altimeterSdfNoise); - EXPECT_TRUE(sensorNoise != nullptr); + std::make_unique(); + EXPECT_TRUE(sensorNoise->Load(altimeterSdfNoise)); EXPECT_EQ(name, sensorNoise->Name()); EXPECT_EQ(topicNoise, sensorNoise->Topic()); @@ -174,16 +175,21 @@ TEST_F(AltimeterSensorTest, SensorReadings) // try creating without specifying the sensor type and then cast it ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - std::unique_ptr s = - sf.CreateSensor(altimeterSdf); + + std::unique_ptr s = + std::make_unique(); + EXPECT_TRUE(s->Load(altimeterSdf)); + EXPECT_TRUE(s->Init()); std::unique_ptr sensor( dynamic_cast(s.release())); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); - std::unique_ptr sNoise = - sf.CreateSensor(altimeterSdfNoise); + std::unique_ptr sNoise = + std::make_unique(); + EXPECT_TRUE(sNoise->Load(altimeterSdfNoise)); + EXPECT_TRUE(sNoise->Init()); std::unique_ptr sensorNoise( dynamic_cast(sNoise.release())); @@ -271,9 +277,9 @@ TEST_F(AltimeterSensorTest, Topic) auto altimeterSdf = AltimeterToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(altimeterSdf); - EXPECT_NE(nullptr, sensor); - + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(altimeterSdf)); auto altimeter = dynamic_cast(sensor.release()); ASSERT_NE(nullptr, altimeter); @@ -287,8 +293,9 @@ TEST_F(AltimeterSensorTest, Topic) auto altimeterSdf = AltimeterToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(altimeterSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(altimeterSdf)); auto altimeter = dynamic_cast(sensor.release()); @@ -303,8 +310,9 @@ TEST_F(AltimeterSensorTest, Topic) auto altimeterSdf = AltimeterToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(altimeterSdf); - ASSERT_EQ(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_FALSE(sensor->Load(altimeterSdf)); } } diff --git a/test/integration/camera_plugin.cc b/test/integration/camera_plugin.cc index 18bfd38e..a6872d56 100644 --- a/test/integration/camera_plugin.cc +++ b/test/integration/camera_plugin.cc @@ -21,7 +21,14 @@ #include #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include "test_config.h" // NOLINT(build/include) #include "TransportTestTools.hh" @@ -65,9 +72,11 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine) ignition::sensors::Manager mgr; mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - ignition::sensors::CameraSensor *sensor = - mgr.CreateSensor(sensorPtr); - ASSERT_NE(sensor, nullptr); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(sensorPtr)); + EXPECT_TRUE(sensor->Init()); + sensor->SetScene(scene); ASSERT_NE(sensor->RenderingCamera(), nullptr); diff --git a/test/integration/depth_camera_plugin.cc b/test/integration/depth_camera_plugin.cc index fe7aeb31..e4f65065 100644 --- a/test/integration/depth_camera_plugin.cc +++ b/test/integration/depth_camera_plugin.cc @@ -16,14 +16,22 @@ */ #include + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include #include #include #include -#include #include "test_config.h" // NOLINT(build/include) #include "TransportTestTools.hh" @@ -205,9 +213,10 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( ignition::sensors::Manager mgr; mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - ignition::sensors::DepthCameraSensor *depthSensor = - mgr.CreateSensor(sensorPtr); - ASSERT_NE(depthSensor, nullptr); + std::unique_ptr depthSensor = + std::make_unique(); + EXPECT_TRUE(depthSensor->Load(sensorPtr)); + EXPECT_TRUE(depthSensor->Init()); depthSensor->SetScene(scene); EXPECT_EQ(depthSensor->ImageWidth(), static_cast(imgWidth)); @@ -248,8 +257,8 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF( // wait for a few depth camera frames mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); - int midWidth = depthSensor->ImageWidth() * 0.5; - int midHeight = depthSensor->ImageHeight() * 0.5; + int midWidth = static_cast(depthSensor->ImageWidth() * 0.5); + int midHeight = static_cast(depthSensor->ImageHeight() * 0.5); int mid = midHeight * depthSensor->ImageWidth() + midWidth -1; double expectedRangeAtMidPoint = boxPosition.X() - unitBoxSize * 0.5; diff --git a/test/integration/gpu_lidar_sensor_plugin.cc b/test/integration/gpu_lidar_sensor_plugin.cc index 98793a38..5a728427 100644 --- a/test/integration/gpu_lidar_sensor_plugin.cc +++ b/test/integration/gpu_lidar_sensor_plugin.cc @@ -26,7 +26,14 @@ #include #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include #include @@ -194,8 +201,10 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine) scene->SetAmbientLight(0.3, 0.3, 0.3); // Create a GpuLidarSensor - ignition::sensors::GpuLidarSensor *sensor = - mgr.CreateSensor(lidarSdf); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(lidarSdf)); + EXPECT_TRUE(sensor->Init()); sensor->SetParent(parent); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); @@ -321,8 +330,10 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine) mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); // Create a GpuLidarSensor - ignition::sensors::GpuLidarSensor *sensor = - mgr.CreateSensor(lidarSdf); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(lidarSdf)); + EXPECT_TRUE(sensor->Init()); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); sensor->SetParent(parent); @@ -466,12 +477,15 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine) mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); // Create a GpuLidarSensors - ignition::sensors::GpuLidarSensor *sensor1 = - mgr.CreateSensor(lidarSdf1); + std::unique_ptr sensor1 = + std::make_unique(); + EXPECT_TRUE(sensor1->Load(lidarSdf1)); + EXPECT_TRUE(sensor1->Init()); - // Create second GpuLidarSensor - ignition::sensors::GpuLidarSensor *sensor2 = - mgr.CreateSensor(lidarSdf2); + std::unique_ptr sensor2 = + std::make_unique(); + EXPECT_TRUE(sensor2->Load(lidarSdf2)); + EXPECT_TRUE(sensor2->Init()); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor1 != nullptr); @@ -612,8 +626,10 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine) mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); // Create a GpuLidarSensor - ignition::sensors::GpuLidarSensor *sensor = - mgr.CreateSensor(lidarSdf); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(lidarSdf)); + EXPECT_TRUE(sensor->Init()); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor != nullptr); @@ -730,12 +746,16 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine) mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); // Create a GpuLidarSensors - ignition::sensors::GpuLidarSensor *sensor1 = - mgr.CreateSensor(lidarSdf1); + std::unique_ptr sensor1 = + std::make_unique(); + EXPECT_TRUE(sensor1->Load(lidarSdf1)); + EXPECT_TRUE(sensor1->Init()); // Create second GpuLidarSensor - ignition::sensors::GpuLidarSensor *sensor2 = - mgr.CreateSensor(lidarSdf2); + std::unique_ptr sensor2 = + std::make_unique(); + EXPECT_TRUE(sensor2->Load(lidarSdf2)); + EXPECT_TRUE(sensor2->Init()); // Make sure the above dynamic cast worked. EXPECT_TRUE(sensor1 != nullptr); @@ -831,7 +851,12 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine) vertSamples, vertResolution, vertMinAngle, vertMaxAngle, rangeResolution, rangeMin, rangeMax, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(lidarSdf); + // Create second GpuLidarSensor + std::unique_ptr sensorGpuLidar = + std::make_unique(); + EXPECT_TRUE(sensorGpuLidar->Load(lidarSdf)); + + auto sensorId = mgr.AddSensor(std::move(sensorGpuLidar)); EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId); auto sensor = mgr.Sensor(sensorId); @@ -851,7 +876,11 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine) vertSamples, vertResolution, vertMinAngle, vertMaxAngle, rangeResolution, rangeMin, rangeMax, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(lidarSdf); + std::unique_ptr sensorGpuLidar = + std::make_unique(); + EXPECT_TRUE(sensorGpuLidar->Load(lidarSdf)); + + auto sensorId = mgr.AddSensor(std::move(sensorGpuLidar)); EXPECT_NE(ignition::sensors::NO_SENSOR, sensorId); auto sensor = mgr.Sensor(sensorId); @@ -871,7 +900,12 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine) vertSamples, vertResolution, vertMinAngle, vertMaxAngle, rangeResolution, rangeMin, rangeMax, alwaysOn, visualize); - auto sensorId = mgr.CreateSensor(lidarSdf); + std::unique_ptr sensorGpuLidar = + std::make_unique(); + EXPECT_TRUE(sensorGpuLidar->Load(lidarSdf)); + + auto sensorId = mgr.AddSensor(std::move(sensorGpuLidar)); + EXPECT_EQ(ignition::sensors::NO_SENSOR, sensorId); } } diff --git a/test/integration/imu_plugin.cc b/test/integration/imu_plugin.cc index 908ca723..3e579c39 100644 --- a/test/integration/imu_plugin.cc +++ b/test/integration/imu_plugin.cc @@ -81,8 +81,8 @@ TEST_F(ImuSensorTest, CreateImu) ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); std::unique_ptr sensor = - sf.CreateSensor(imuSdf); - EXPECT_TRUE(sensor != nullptr); + std::make_unique(); + EXPECT_TRUE(sensor->Load(imuSdf)); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -109,8 +109,9 @@ TEST_F(ImuSensorTest, SensorReadings) // try creating without specifying the sensor type and then cast it ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - std::unique_ptr s = - sf.CreateSensor(imuSdf); + std::unique_ptr s = + std::make_unique(); + EXPECT_TRUE(s->Load(imuSdf)); std::unique_ptr sensor( dynamic_cast(s.release())); @@ -248,8 +249,9 @@ TEST_F(ImuSensorTest, Topic) auto imuSdf = ImuToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(imuSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(imuSdf)); auto imu = dynamic_cast(sensor.release()); ASSERT_NE(nullptr, imu); @@ -263,8 +265,9 @@ TEST_F(ImuSensorTest, Topic) auto imuSdf = ImuToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(imuSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(imuSdf)); auto imu = dynamic_cast(sensor.release()); @@ -279,8 +282,9 @@ TEST_F(ImuSensorTest, Topic) auto imuSdf = ImuToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(imuSdf); - ASSERT_EQ(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_FALSE(sensor->Load(imuSdf)); } } diff --git a/test/integration/logical_camera_plugin.cc b/test/integration/logical_camera_plugin.cc index b5c14b81..7cabbdd4 100644 --- a/test/integration/logical_camera_plugin.cc +++ b/test/integration/logical_camera_plugin.cc @@ -27,7 +27,14 @@ #include #include +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include "test_config.h" // NOLINT(build/include) @@ -106,9 +113,10 @@ TEST_F(LogicalCameraSensorTest, CreateLogicalCamera) // create the sensor using sensor factory ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); + std::unique_ptr sensor = - sf.CreateSensor(logicalCameraSdf); - EXPECT_TRUE(sensor != nullptr); + std::make_unique(); + EXPECT_TRUE(sensor->Load(logicalCameraSdf)); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(topic, sensor->Topic()); @@ -145,8 +153,10 @@ TEST_F(LogicalCameraSensorTest, DetectBox) // try creating without specifying the sensor type and then cast it ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - std::unique_ptr s = - sf.CreateSensor(logicalCameraSdf); + + std::unique_ptr s = + std::make_unique(); + EXPECT_TRUE(s->Load(logicalCameraSdf)); std::unique_ptr sensor( dynamic_cast(s.release())); @@ -255,8 +265,9 @@ TEST_F(LogicalCameraSensorTest, Topic) updateRate, topic, near, far, horzFov, aspectRatio, alwaysOn, visualize); - auto sensor = factory.CreateSensor(logicalCameraSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(logicalCameraSdf)); auto logicalCamera = dynamic_cast( @@ -273,8 +284,9 @@ TEST_F(LogicalCameraSensorTest, Topic) updateRate, topic, near, far, horzFov, aspectRatio, alwaysOn, visualize); - auto sensor = factory.CreateSensor(logicalCameraSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(logicalCameraSdf)); auto logicalCamera = dynamic_cast( @@ -291,8 +303,9 @@ TEST_F(LogicalCameraSensorTest, Topic) updateRate, topic, near, far, horzFov, aspectRatio, alwaysOn, visualize); - auto sensor = factory.CreateSensor(logicalCameraSdf); - ASSERT_EQ(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_FALSE(sensor->Load(logicalCameraSdf)); } } diff --git a/test/integration/magnetometer_plugin.cc b/test/integration/magnetometer_plugin.cc index ee44ccae..4235fa11 100644 --- a/test/integration/magnetometer_plugin.cc +++ b/test/integration/magnetometer_plugin.cc @@ -140,14 +140,14 @@ TEST_F(MagnetometerSensorTest, CreateMagnetometer) // create the sensor using sensor factory ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); + std::unique_ptr sensor = - sf.CreateSensor(magnetometerSdf); - EXPECT_TRUE(sensor != nullptr); + std::make_unique(); + EXPECT_TRUE(sensor->Load(magnetometerSdf)); std::unique_ptr sensorNoise = - sf.CreateSensor( - magnetometerNoiseSdf); - EXPECT_TRUE(sensorNoise != nullptr); + std::make_unique(); + EXPECT_TRUE(sensorNoise->Load(magnetometerNoiseSdf)); EXPECT_EQ(name, sensor->Name()); EXPECT_EQ(name, sensorNoise->Name()); @@ -180,13 +180,18 @@ TEST_F(MagnetometerSensorTest, SensorReadings) // try creating without specifying the sensor type and then cast it ignition::sensors::SensorFactory sf; sf.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - std::unique_ptr s = - sf.CreateSensor(magnetometerSdf); + + std::unique_ptr s = + std::make_unique(); + EXPECT_TRUE(s->Load(magnetometerSdf)); + EXPECT_TRUE(s->Init()); std::unique_ptr sensor( dynamic_cast(s.release())); - std::unique_ptr sNoise = - sf.CreateSensor(magnetometerSdfNoise); + std::unique_ptr sNoise = + std::make_unique(); + EXPECT_TRUE(sNoise->Load(magnetometerSdfNoise)); + EXPECT_TRUE(sNoise->Init()); std::unique_ptr sensorNoise( dynamic_cast(sNoise.release())); @@ -308,8 +313,9 @@ TEST_F(MagnetometerSensorTest, Topic) auto magnetometerSdf = MagnetometerToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(magnetometerSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(magnetometerSdf)); auto magnetometer = dynamic_cast(sensor.release()); @@ -324,8 +330,9 @@ TEST_F(MagnetometerSensorTest, Topic) auto magnetometerSdf = MagnetometerToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(magnetometerSdf); - EXPECT_NE(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_TRUE(sensor->Load(magnetometerSdf)); auto magnetometer = dynamic_cast(sensor.release()); @@ -340,8 +347,9 @@ TEST_F(MagnetometerSensorTest, Topic) auto magnetometerSdf = MagnetometerToSdf(name, sensorPose, updateRate, topic, alwaysOn, visualize); - auto sensor = factory.CreateSensor(magnetometerSdf); - ASSERT_EQ(nullptr, sensor); + std::unique_ptr sensor = + std::make_unique(); + EXPECT_FALSE(sensor->Load(magnetometerSdf)); } } diff --git a/test/integration/rgbd_camera_plugin.cc b/test/integration/rgbd_camera_plugin.cc index df6b2909..5c27dbd3 100644 --- a/test/integration/rgbd_camera_plugin.cc +++ b/test/integration/rgbd_camera_plugin.cc @@ -16,14 +16,22 @@ */ #include + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include #include #include #include -#include #include "test_config.h" // NOLINT(build/include) #include "TransportTestTools.hh" @@ -225,8 +233,10 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( ignition::sensors::Manager mgr; mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - ignition::sensors::RgbdCameraSensor *rgbdSensor = - mgr.CreateSensor(sensorPtr); + std::unique_ptr rgbdSensor = + std::make_unique(); + EXPECT_TRUE(rgbdSensor->Load(sensorPtr)); + EXPECT_TRUE(rgbdSensor->Init()); ASSERT_NE(rgbdSensor, nullptr); rgbdSensor->SetScene(scene); @@ -319,8 +329,8 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF( pcCounter = 0; // depth image indices - int midWidth = rgbdSensor->ImageWidth() * 0.5; - int midHeight = rgbdSensor->ImageHeight() * 0.5; + int midWidth = static_cast(rgbdSensor->ImageWidth() * 0.5); + int midHeight = static_cast(rgbdSensor->ImageHeight() * 0.5); int mid = midHeight * rgbdSensor->ImageWidth() + midWidth -1; double expectedRangeAtMidPoint = boxPosition.X() - unitBoxSize * 0.5; int left = midHeight * rgbdSensor->ImageWidth(); diff --git a/test/integration/thermal_camera_plugin.cc b/test/integration/thermal_camera_plugin.cc index 42e1d043..7898f598 100644 --- a/test/integration/thermal_camera_plugin.cc +++ b/test/integration/thermal_camera_plugin.cc @@ -16,14 +16,23 @@ */ #include + +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable: 4005) +#endif #include +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include #include #include #include #include -#include + #include "test_config.h" // NOLINT(build/include) #include "TransportTestTools.hh" @@ -138,13 +147,14 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( ignition::sensors::Manager mgr; mgr.AddPluginPaths(ignition::common::joinPaths(PROJECT_BUILD_PATH, "lib")); - ignition::sensors::ThermalCameraSensor *thermalSensor = - mgr.CreateSensor(sensorPtr); - ASSERT_NE(thermalSensor, nullptr); + std::unique_ptr thermalSensor = + std::make_unique(); + EXPECT_TRUE(thermalSensor->Load(sensorPtr)); + EXPECT_TRUE(thermalSensor->Init()); - float ambientTemp = 296.0; - float ambientTempRange = 4.0; - float linearResolution = 0.01; + float ambientTemp = 296.0f; + float ambientTempRange = 4.0f; + float linearResolution = 0.01f; thermalSensor->SetAmbientTemperature(ambientTemp); thermalSensor->SetAmbientTemperatureRange(ambientTempRange); thermalSensor->SetLinearResolution(linearResolution); @@ -177,8 +187,8 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( // wait for a few thermal camera frames mgr.RunOnce(std::chrono::steady_clock::duration::zero(), true); - int midWidth = thermalSensor->ImageWidth() * 0.5; - int midHeight = thermalSensor->ImageHeight() * 0.5; + int midWidth = static_cast(thermalSensor->ImageWidth() * 0.5); + int midHeight = static_cast(thermalSensor->ImageHeight() * 0.5); int mid = midHeight * thermalSensor->ImageWidth() + midWidth -1; int left = midHeight * thermalSensor->ImageWidth(); int right = (midHeight+1) * thermalSensor->ImageWidth() - 1;