Skip to content

Commit

Permalink
Update sensors to use message generation pipeline
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed May 30, 2023
1 parent 4075656 commit 2ec1ae4
Show file tree
Hide file tree
Showing 20 changed files with 95 additions and 21 deletions.
11 changes: 11 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,17 @@ endif()
gz_find_package(gz-msgs10 REQUIRED)
set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR})

# Get the gz-msgs installed messages and generate a library from them
gz_msgs_get_installed_messages(
MESSAGES_PATH_VARIABLE MSGS_PATH
MESSAGES_PROTOS_VARIABLE MSGS_PROTOS)

gz_msgs_generate_messages(
TARGET gz_msgs_gen
PROTO_PACKAGE "gz.msgs"
MSGS_PATH ${MSGS_PATH}
MSGS_PROTOS ${MSGS_PROTOS})

#--------------------------------------
# Find SDFormat
gz_find_package(sdformat13 REQUIRED)
Expand Down
6 changes: 4 additions & 2 deletions src/BoundingBoxCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@

#include <gz/msgs/image.pb.h>
#include <gz/msgs/annotated_axis_aligned_2d_box.pb.h>
#include <gz/msgs/annotated_axis_aligned_2d_box_v.pb.h>
#include <gz/msgs/annotated_oriented_3d_box.pb.h>
#include <gz/msgs/annotated_oriented_3d_box_v.pb.h>

#include <gz/common/Console.hh>
#include <gz/common/Image.hh>
Expand Down Expand Up @@ -494,9 +496,9 @@ bool BoundingBoxCameraSensor::Update(

auto axisAlignedBox = annotatedBox->mutable_box();
msgs::Set(axisAlignedBox->mutable_min_corner(),
{minCorner.X(), minCorner.Y()});
gz::math::Vector2d{minCorner.X(), minCorner.Y()});
msgs::Set(axisAlignedBox->mutable_max_corner(),
{maxCorner.X(), maxCorner.Y()});
gz::math::Vector2d{maxCorner.X(), maxCorner.Y()});
}
// time stamp
auto stampBoxes = boxes2DMsg.mutable_header()->mutable_stamp();
Expand Down
62 changes: 46 additions & 16 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,14 +48,16 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME}
sdformat${SDF_VER}::sdformat${SDF_VER}
PRIVATE
gz-common${GZ_COMMON_VER}::profiler
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
)
target_compile_definitions(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC DepthPoints_EXPORTS)

gz_add_component(rendering SOURCES ${rendering_sources} GET_TARGET_NAME rendering_target)
target_link_libraries(${rendering_target}
PUBLIC
gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER}
PRIVATE
gz_msgs_gen
)

set(camera_sources CameraSensor.cc)
Expand All @@ -71,7 +73,7 @@ target_link_libraries(${camera_target}
PUBLIC
${rendering_target}
PRIVATE
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -85,7 +87,7 @@ target_compile_definitions(${depth_camera_target} PUBLIC DepthCameraSensor_EXPOR
target_link_libraries(${depth_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -102,7 +104,7 @@ target_link_libraries(${dvl_target}
PRIVATE
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER})

set(lidar_sources Lidar.cc)
Expand All @@ -116,7 +118,7 @@ target_link_libraries(${lidar_target}
PUBLIC
${rendering_target}
PRIVATE
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -129,7 +131,7 @@ gz_add_component(gpu_lidar
target_compile_definitions(${gpu_lidar_target} PUBLIC GpuLidarSensor_EXPORTS)
target_link_libraries(${gpu_lidar_target}
PRIVATE
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
${lidar_target}
)
Expand All @@ -139,30 +141,58 @@ gz_add_component(logical_camera SOURCES ${logical_camera_sources} GET_TARGET_NAM
target_compile_definitions(${logical_camera_target} PUBLIC LogicalCameraSensor_EXPORTS)
target_link_libraries(${logical_camera_target}
PRIVATE
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

set(magnetometer_sources MagnetometerSensor.cc)
gz_add_component(magnetometer SOURCES ${magnetometer_sources} GET_TARGET_NAME magnetometer_target)
target_link_libraries(${magnetometer_target}
PRIVATE
gz_msgs_gen
)

set(imu_sources ImuSensor.cc)
gz_add_component(imu SOURCES ${imu_sources} GET_TARGET_NAME imu_target)
target_link_libraries(${imu_target}
PRIVATE
gz_msgs_gen
)

set(altimeter_sources AltimeterSensor.cc)
gz_add_component(altimeter SOURCES ${altimeter_sources} GET_TARGET_NAME altimeter_target)
target_link_libraries(${altimeter_target}
PRIVATE
gz_msgs_gen
)

set(air_pressure_sources AirPressureSensor.cc)
gz_add_component(air_pressure SOURCES ${air_pressure_sources} GET_TARGET_NAME air_pressure_target)
target_link_libraries(${air_pressure_target}
PRIVATE
gz_msgs_gen
)

set(air_speed_sources AirSpeedSensor.cc)
gz_add_component(air_speed SOURCES ${air_speed_sources} GET_TARGET_NAME air_speed_target)
target_link_libraries(${air_speed_target}
PRIVATE
gz_msgs_gen
)

set(force_torque_sources ForceTorqueSensor.cc)
gz_add_component(force_torque SOURCES ${force_torque_sources} GET_TARGET_NAME force_torque_target)
target_link_libraries(${force_torque_target}
PRIVATE
gz_msgs_gen
)

set(navsat_sources NavSatSensor.cc)
gz_add_component(navsat SOURCES ${navsat_sources} GET_TARGET_NAME navsat_target)
target_link_libraries(${navsat_target}
PRIVATE
gz_msgs_gen
)

set(rgbd_camera_sources RgbdCameraSensor.cc)
gz_add_component(rgbd_camera
Expand All @@ -174,7 +204,7 @@ target_compile_definitions(${rgbd_camera_target} PUBLIC RgbdCameraSensor_EXPORTS
target_link_libraries(${rgbd_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -187,7 +217,7 @@ gz_add_component(thermal_camera
target_link_libraries(${thermal_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -196,7 +226,7 @@ gz_add_component(boundingbox_camera SOURCES ${boundingbox_camera_sources} GET_TA
target_link_libraries(${boundingbox_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -206,7 +236,7 @@ target_compile_definitions(${segmentation_camera_target} PUBLIC SegmentationCame
target_link_libraries(${segmentation_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

Expand All @@ -215,14 +245,14 @@ gz_add_component(wide_angle_camera SOURCES ${wide_angle_camera_sources} GET_TARG
target_link_libraries(${wide_angle_camera_target}
PRIVATE
${camera_target}
gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}
gz_msgs_gen
gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER}
)

# Build the unit tests.
gz_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${rendering_target})
gz_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${rendering_target} gz_msgs_gen)

# Build the unit tests that depend on components.
gz_build_tests(TYPE UNIT SOURCES Lidar_TEST.cc LIB_DEPS ${lidar_target})
gz_build_tests(TYPE UNIT SOURCES Camera_TEST.cc LIB_DEPS ${camera_target})
gz_build_tests(TYPE UNIT SOURCES ImuSensor_TEST.cc LIB_DEPS ${imu_target})
gz_build_tests(TYPE UNIT SOURCES Lidar_TEST.cc LIB_DEPS ${lidar_target} gz_msgs_gen)
gz_build_tests(TYPE UNIT SOURCES Camera_TEST.cc LIB_DEPS ${camera_target} gz_msgs_gen)
gz_build_tests(TYPE UNIT SOURCES ImuSensor_TEST.cc LIB_DEPS ${imu_target} gz_msgs_gen)
3 changes: 2 additions & 1 deletion src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@
#include <gz/math/Angle.hh>
#include <gz/math/Helpers.hh>

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

#include "gz/sensors/DepthCameraSensor.hh"
Expand Down
3 changes: 2 additions & 1 deletion src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@

#include <gz/common/Console.hh>
#include <gz/common/Profiler.hh>
#include <gz/msgs/Utility.hh>
#include <gz/msgs/convert/StdTypes.hh>
#include <gz/msgs/PointCloudPackedUtils.hh>
#include <gz/transport/Node.hh>

#include "gz/sensors/GpuLidarSensor.hh"
Expand Down
3 changes: 2 additions & 1 deletion src/RgbdCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,8 @@
#include <gz/rendering/Camera.hh>
#include <gz/rendering/DepthCamera.hh>

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

#include <sdf/Sensor.hh>
Expand Down
2 changes: 2 additions & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ if (DRI_TESTS)
${PROJECT_LIBRARY_TARGET_NAME}-thermal_camera
${PROJECT_LIBRARY_TARGET_NAME}-wide_angle_camera
${PROJECT_LIBRARY_TARGET_NAME}-dvl
gz_msgs_gen
)
endif()

Expand All @@ -67,4 +68,5 @@ gz_build_tests(TYPE INTEGRATION
${PROJECT_LIBRARY_TARGET_NAME}-logical_camera
${PROJECT_LIBRARY_TARGET_NAME}-magnetometer
${PROJECT_LIBRARY_TARGET_NAME}-navsat
gz_msgs_gen
)
3 changes: 3 additions & 0 deletions test/integration/air_pressure.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
#include <sdf/sdf.hh>

#include <gz/math/Helpers.hh>

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

#include <gz/sensors/AirPressureSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
3 changes: 3 additions & 0 deletions test/integration/air_speed.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
#include <sdf/sdf.hh>

#include <gz/math/Helpers.hh>

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

#include <gz/sensors/AirSpeedSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
3 changes: 3 additions & 0 deletions test/integration/altimeter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
#include <sdf/sdf.hh>

#include <gz/math/Helpers.hh>

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

#include <gz/sensors/AltimeterSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
2 changes: 2 additions & 0 deletions test/integration/boundingbox_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@
#include <gtest/gtest.h>

#include <gz/msgs/annotated_axis_aligned_2d_box.pb.h>
#include <gz/msgs/annotated_axis_aligned_2d_box_v.pb.h>
#include <gz/msgs/annotated_oriented_3d_box.pb.h>
#include <gz/msgs/annotated_oriented_3d_box_v.pb.h>

#include <gz/common/Filesystem.hh>
#include <gz/sensors/Manager.hh>
Expand Down
1 change: 1 addition & 0 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <cstring>
#include <gtest/gtest.h>

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

#include <gz/common/Console.hh>
Expand Down
2 changes: 2 additions & 0 deletions test/integration/dvl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>

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

#include <gz/rendering/Material.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
Expand Down
2 changes: 2 additions & 0 deletions test/integration/force_torque.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@

#include <gz/math/Helpers.hh>

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

#include <gz/sensors/ForceTorqueSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
2 changes: 2 additions & 0 deletions test/integration/imu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <sdf/sdf.hh>

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

#include <gz/sensors/ImuSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
2 changes: 2 additions & 0 deletions test/integration/magnetometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include <gz/sensors/MagnetometerSensor.hh>
#include <gz/sensors/SensorFactory.hh>

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

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

Expand Down
3 changes: 3 additions & 0 deletions test/integration/navsat.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@
#include <sdf/sdf.hh>

#include <gz/math/Helpers.hh>

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

#include <gz/sensors/NavSatSensor.hh>
#include <gz/sensors/SensorFactory.hh>

Expand Down
1 change: 1 addition & 0 deletions test/integration/rgbd_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

#include <gz/msgs/camera_info.pb.h>
#include <gz/msgs/image.pb.h>
#include <gz/msgs/PointCloudPackedUtils.hh>

#include <gz/common/Filesystem.hh>
#include <gz/common/Event.hh>
Expand Down
1 change: 1 addition & 0 deletions test/integration/segmentation_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>

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

#include <gz/common/Filesystem.hh>
#include <gz/sensors/Manager.hh>
Expand Down
1 change: 1 addition & 0 deletions test/integration/wide_angle_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <cstring>
#include <gtest/gtest.h>

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

#include <gz/common/Console.hh>
Expand Down

0 comments on commit 2ec1ae4

Please sign in to comment.