Skip to content

Commit

Permalink
Merge pull request #356 from FS-Driverless/camera_namespace_fix
Browse files Browse the repository at this point in the history
Change camera prefix to follow documentation and to follow lidar naming convention
  • Loading branch information
wouter-heerwegh authored Mar 28, 2023
2 parents ba7b1bd + aa324ae commit 40ced2d
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion ros/src/fsds_ros_bridge/src/fsds_ros_bridge_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ int main(int argc, char ** argv)

// load settings
nh.param<std::string>("camera_name", camera_name, "");
nh.param<std::string>("camera_frame_prefix", camera_frame_prefix, "/fsds/");
nh.param<std::string>("camera_frame_prefix", camera_frame_prefix, "/fsds/camera");
camera_frame_id = camera_frame_prefix + camera_name;

nh.param<double>("framerate", framerate, 0.0);
Expand Down
2 changes: 1 addition & 1 deletion ros2/src/fsds_ros2_bridge/src/fsds_ros2_bridge_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ int main(int argc, char ** argv)

// load settings
camera_name = nh->declare_parameter<std::string>("camera_name", "");
camera_frame_prefix = nh->declare_parameter<std::string>("camera_frame_prefix", "/fsds/");
camera_frame_prefix = nh->declare_parameter<std::string>("camera_frame_prefix", "/fsds/camera");
camera_frame_id = camera_frame_prefix + camera_name;

framerate = nh->declare_parameter<double>("framerate", 0.0);
Expand Down

0 comments on commit 40ced2d

Please sign in to comment.