diff --git a/gazebo_plugins/test/test_gazebo_ros_camera.cpp b/gazebo_plugins/test/test_gazebo_ros_camera.cpp index d115b089b..773991e1d 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera.cpp @@ -76,12 +76,10 @@ TEST_P(GazeboRosCameraTest, CameraSubscribeTest) } INSTANTIATE_TEST_CASE_P(GazeboRosCamera, GazeboRosCameraTest, ::testing::Values( - // TODO(louise) Use mapped topics once this issue is solved: - // https://github.com/ros-perception/image_common/issues/93 TestParams({"worlds/gazebo_ros_camera.world", - "test_cam/camera1/image_raw"}), + "test_cam/camera/image_test"}), TestParams({"worlds/gazebo_ros_camera_16bit.world", - "test_cam_16bit/test_camera_name/image_raw"}) + "test_cam_16bit/image_test_16bit"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp b/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp index d8bcd5351..f5c16103c 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera_distortion.cpp @@ -200,18 +200,16 @@ TEST_P(GazeboRosCameraDistortionTest, CameraSubscribeTest) INSTANTIATE_TEST_CASE_P(GazeboRosCameraDistortion, GazeboRosCameraDistortionTest, ::testing::Values( - // TODO(louise) Use mapped topics once this issue is solved: - // https://github.com/ros-perception/image_common/issues/93 TestParams({ "worlds/gazebo_ros_camera_distortion_barrel.world", - "undistorted_camera/image_raw", - "distorted_camera/image_raw", - "distorted_camera/camera_info" + "undistorted_image", + "distorted_image", + "distorted_info" }) // TestParams({"worlds/gazebo_ros_camera_distortion_pincushion.world", -// "undistorted_camera/image_raw", -// "distorted_camera/image_raw", -// "distorted_camera/camera_info"}) +// "undistorted_image", +// "distorted_image", +// "distorted_info"}) ), ); int main(int argc, char ** argv) diff --git a/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp b/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp index 9a2fe4694..19e153080 100644 --- a/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp +++ b/gazebo_plugins/test/test_gazebo_ros_camera_triggered.cpp @@ -48,7 +48,7 @@ TEST_F(GazeboRosTriggeredCameraTest, CameraSubscribeTest) builtin_interfaces::msg::Time image_stamp; auto sub = image_transport::create_subscription(node, - "test_triggered_cam/camera1/image_raw", + "test_triggered_cam/image_raw_test", [&](const sensor_msgs::msg::Image::ConstSharedPtr & msg) { image_stamp = msg->header.stamp; ++msg_count; @@ -63,7 +63,7 @@ TEST_F(GazeboRosTriggeredCameraTest, CameraSubscribeTest) // Trigger camera once auto pub = node->create_publisher( - "test_triggered_cam/camera1/image_trigger"); + "test_triggered_cam/image_trigger_test"); std_msgs::msg::Empty msg; pub->publish(msg); diff --git a/gazebo_plugins/test/worlds/gazebo_ros_camera.world b/gazebo_plugins/test/worlds/gazebo_ros_camera.world index e3b07c912..38b7c1c06 100644 --- a/gazebo_plugins/test/worlds/gazebo_ros_camera.world +++ b/gazebo_plugins/test/worlds/gazebo_ros_camera.world @@ -29,8 +29,7 @@ test_cam - - image_raw:=image_test + camera1/image_raw:=camera/image_test camera_info:=camera_info_test diff --git a/gazebo_plugins/test/worlds/gazebo_ros_camera_16bit.world b/gazebo_plugins/test/worlds/gazebo_ros_camera_16bit.world index dc597caf6..247838a6e 100644 --- a/gazebo_plugins/test/worlds/gazebo_ros_camera_16bit.world +++ b/gazebo_plugins/test/worlds/gazebo_ros_camera_16bit.world @@ -29,7 +29,7 @@ test_cam_16bit - image_raw:=image_test_16bit + test_camera_name/image_raw:=image_test_16bit camera_info:=camera_info_test_16bit test_camera_name diff --git a/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_barrel.world b/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_barrel.world index 5926713a0..b0f95dfcf 100644 --- a/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_barrel.world +++ b/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_barrel.world @@ -39,9 +39,8 @@ - - image_raw:=image_test - camera_info:=camera_info_test + distorted_camera/image_raw:=distorted_image + distorted_camera/camera_info:=distorted_info distorted_camera frame_name @@ -80,9 +79,7 @@ - - image_raw:=image_test - camera_info:=camera_info_test + undistorted_camera/image_raw:=undistorted_image undistorted_camera frame_name diff --git a/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_pincushion.world b/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_pincushion.world index d22cfb0b2..4aba7f1a0 100644 --- a/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_pincushion.world +++ b/gazebo_plugins/test/worlds/gazebo_ros_camera_distortion_pincushion.world @@ -1,5 +1,5 @@ - + @@ -11,13 +11,6 @@ true 0.0 0.0 2.5 0.0 1.5707 0.0 - - - - 0.1 0.1 0.1 - - - 30.0 @@ -46,12 +39,10 @@ - test_cam_distorted - - image_raw:=image_test - camera_info:=camera_info_test + distorted_camera/image_raw:=distorted_image + distorted_camera/camera_info:=distorted_info - camera_name + distorted_camera frame_name 0.07 false @@ -64,13 +55,6 @@ true 0.0 0.0 2.5 0.0 1.5707 0.0 - - - - 0.1 0.1 0.1 - - - 30.0 @@ -95,14 +79,10 @@ - test_cam_undistorted - - image_raw:=image_test - camera_info:=camera_info_test + undistorted_camera/image_raw:=undistorted_image - camera_name + undistorted_camera frame_name - 0.0 @@ -111,5 +91,5 @@ model://checkerboard_plane - + diff --git a/gazebo_plugins/test/worlds/gazebo_ros_camera_triggered.world b/gazebo_plugins/test/worlds/gazebo_ros_camera_triggered.world index d61d56ba8..cdd6d6016 100644 --- a/gazebo_plugins/test/worlds/gazebo_ros_camera_triggered.world +++ b/gazebo_plugins/test/worlds/gazebo_ros_camera_triggered.world @@ -36,11 +36,8 @@ test_triggered_cam - - image_raw:=image_test - camera_info:=camera_info_test - image_trigger:=image_trigger_test + camera1/image_raw:=image_raw_test + camera1/image_trigger:=image_trigger_test true 0.07