Skip to content

Commit

Permalink
Fix msgs.hh uses
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Aug 27, 2022
1 parent da58993 commit 183ce30
Show file tree
Hide file tree
Showing 27 changed files with 45 additions and 201 deletions.
1 change: 1 addition & 0 deletions examples/custom_sensor/Odometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <gz/msgs/double.pb.h>

#include <gz/common/Console.hh>
#include <gz/msgs/Utility.hh>
#include <gz/sensors/Noise.hh>
#include <gz/sensors/Util.hh>

Expand Down
12 changes: 2 additions & 10 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,20 +21,12 @@
#include <memory>
#include <string>

#include <gz/msgs/image.pb.h>

#include <sdf/sdf.hh>

#include <gz/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
// warnings
#ifdef _WIN32
Expand Down
10 changes: 1 addition & 9 deletions include/gz/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,7 @@
#include <gz/common/Event.hh>
#include <gz/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/image.pb.h>

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
// warnings
Expand Down
10 changes: 1 addition & 9 deletions include/gz/sensors/LogicalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,7 @@

#include <gz/math/Angle.hh>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/logical_camera_image.pb.h>

#include "gz/sensors/config.hh"
#include "gz/sensors/Export.hh"
Expand Down
3 changes: 2 additions & 1 deletion include/gz/sensors/SegmentationCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,10 @@
#include <memory>
#include <string>

#include <gz/msgs/image.pb.h>

#include <gz/common/Event.hh>
#include <gz/utils/SuppressWarning.hh>
#include <gz/msgs.hh>
#include <gz/transport/Node.hh>
#include <gz/transport/Publisher.hh>
#include <sdf/sdf.hh>
Expand Down
10 changes: 1 addition & 9 deletions include/gz/sensors/ThermalCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,7 @@
#include <gz/common/Event.hh>
#include <gz/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/image.pb.h>

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
// warnings
Expand Down
10 changes: 1 addition & 9 deletions include/gz/sensors/WideAngleCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,7 @@
#include <gz/common/Event.hh>
#include <gz/utils/SuppressWarning.hh>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/image.pb.h>

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
// warnings
Expand Down
1 change: 1 addition & 0 deletions src/BoundingBoxCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <gz/common/Image.hh>
#include <gz/common/Profiler.hh>
#include <gz/common/Util.hh>
#include <gz/msgs/Utility.hh>
#include <gz/rendering/BoundingBoxCamera.hh>
#include <gz/transport/Node.hh>
#include <gz/transport/Publisher.hh>
Expand Down
12 changes: 4 additions & 8 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,10 @@
* limitations under the License.
*
*/
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif

#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/camera_info.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/image.pb.h>

#include <mutex>

Expand All @@ -33,6 +28,7 @@
#include <gz/common/StringUtils.hh>
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>
#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/CameraSensor.hh"
Expand Down
11 changes: 3 additions & 8 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,9 @@
* limitations under the License.
*
*/
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif

#include <gz/msgs/image.pb.h>
#include <gz/msgs/pointcloud_packed.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <mutex>

Expand All @@ -34,6 +28,7 @@
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>

#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/DepthCameraSensor.hh"
Expand Down
9 changes: 0 additions & 9 deletions src/ImuSensor_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,15 +18,6 @@
#include <sdf/sdf.hh>

#include <gz/math/Helpers.hh>
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <gz/common/Console.hh>
#include <gz/sensors/Export.hh>
Expand Down
9 changes: 0 additions & 9 deletions src/Lidar_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,6 @@

#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <gz/sensors/Export.hh>
#include <gz/sensors/Manager.hh>
Expand Down
1 change: 1 addition & 0 deletions src/LogicalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <gz/common/Profiler.hh>
#include <gz/math/Frustum.hh>
#include <gz/math/Helpers.hh>
#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/SensorFactory.hh"
Expand Down
9 changes: 1 addition & 8 deletions src/RgbdCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,16 +15,8 @@
*
*/

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/image.pb.h>
#include <gz/msgs/pointcloud_packed.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <gz/common/Image.hh>
#include <gz/common/Profiler.hh>
Expand All @@ -42,6 +34,7 @@
#pragma warning(pop)
#endif

#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include <sdf/Sensor.hh>
Expand Down
4 changes: 3 additions & 1 deletion src/SegmentationCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,13 @@
#include <memory>
#include <mutex>

#include <gz/msgs/image.pb.h>

#include <gz/common/Console.hh>
#include <gz/common/Image.hh>
#include <gz/common/Profiler.hh>
#include <gz/common/Util.hh>
#include <gz/msgs.hh>
#include <gz/msgs/Utility.hh>
#include <gz/rendering/SegmentationCamera.hh>
#include <gz/transport/Node.hh>
#include <gz/transport/Publisher.hh>
Expand Down
9 changes: 1 addition & 8 deletions src/ThermalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,7 @@
*
*/

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/image.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <algorithm>
#include <mutex>
Expand All @@ -36,6 +28,7 @@
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>

#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/ThermalCameraSensor.hh"
Expand Down
10 changes: 2 additions & 8 deletions src/WideAngleCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,8 @@
* limitations under the License.
*
*/
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif

#include <gz/msgs/camera_info.pb.h>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <mutex>

Expand All @@ -33,6 +26,7 @@
#include <gz/common/StringUtils.hh>
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>
#include <gz/msgs/Utility.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/WideAngleCameraSensor.hh"
Expand Down
12 changes: 2 additions & 10 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <gtest/gtest.h>

#include <gz/msgs/image.pb.h>

#include <gz/common/Console.hh>
#include <gz/common/Filesystem.hh>
#include <gz/sensors/Manager.hh>
Expand All @@ -35,16 +37,6 @@
#pragma warning(pop)
#endif

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include "test_config.hh" // NOLINT(build/include)
#include "TransportTestTools.hh"

Expand Down
10 changes: 1 addition & 9 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,8 @@

#include <gtest/gtest.h>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs/camera_info.pb.h>
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/msgs/image.pb.h>

#include <gz/common/Filesystem.hh>
#include <gz/common/Event.hh>
Expand Down
12 changes: 2 additions & 10 deletions test/integration/distortion_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <gtest/gtest.h>

#include <gz/msgs/image.pb.h>

#include <gz/common/Console.hh>
#include <gz/common/Filesystem.hh>
#include <gz/sensors/Manager.hh>
Expand All @@ -35,16 +37,6 @@
#pragma warning(pop)
#endif

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include "test_config.hh" // NOLINT(build/include)
#include "TransportTestTools.hh"

Expand Down
12 changes: 3 additions & 9 deletions test/integration/gpu_lidar_sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@

#include <gtest/gtest.h>

#include <gz/msgs/laserscan.pb.h>
#include <gz/msgs/pointcloud_packed.pb.h>

#include <gz/common/Console.hh>
#include <gz/common/Filesystem.hh>
#include <gz/common/Event.hh>
Expand All @@ -25,15 +28,6 @@
#include <gz/sensors/GpuLidarSensor.hh>
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
#pragma warning(disable: 4251)
#endif
#include <gz/msgs.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif
#include <gz/transport/Node.hh>

// TODO(louise) Remove these pragmas once gz-rendering is disabling the
Expand Down
Loading

0 comments on commit 183ce30

Please sign in to comment.