From aa324aed5507745ac6cf1cc4cc8c8e5e158c1c1e Mon Sep 17 00:00:00 2001 From: Wouter Heerwegh Date: Tue, 28 Mar 2023 22:06:39 +0200 Subject: [PATCH] Change camera prefix to follow documentation and to follow lidar naming convention --- ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp | 2 +- ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp b/ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp index 2f056190..60784497 100644 --- a/ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp +++ b/ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp @@ -144,7 +144,7 @@ int main(int argc, char ** argv) // load settings nh.param("camera_name", camera_name, ""); - nh.param("camera_frame_prefix", camera_frame_prefix, "/fsds/"); + nh.param("camera_frame_prefix", camera_frame_prefix, "/fsds/camera"); camera_frame_id = camera_frame_prefix + camera_name; nh.param("framerate", framerate, 0.0); diff --git a/ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp b/ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp index 20181b10..ea126bcd 100644 --- a/ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp +++ b/ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp @@ -170,7 +170,7 @@ int main(int argc, char ** argv) // load settings camera_name = nh->declare_parameter("camera_name", ""); - camera_frame_prefix = nh->declare_parameter("camera_frame_prefix", "/fsds/"); + camera_frame_prefix = nh->declare_parameter("camera_frame_prefix", "/fsds/camera"); camera_frame_id = camera_frame_prefix + camera_name; framerate = nh->declare_parameter("framerate", 0.0);