From f53738aa1430de764d0c2c1c23afbc32239c13d1 Mon Sep 17 00:00:00 2001 From: Tom Creutz Date: Wed, 27 Nov 2024 15:44:20 +0100 Subject: [PATCH] Set UnderwaterCamera ros node name by sdf sensor name --- .../src/UnderwaterCamera.cc | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/gazebo/dave_gz_sensor_plugins/src/UnderwaterCamera.cc b/gazebo/dave_gz_sensor_plugins/src/UnderwaterCamera.cc index 230bcfa8..6618de5e 100644 --- a/gazebo/dave_gz_sensor_plugins/src/UnderwaterCamera.cc +++ b/gazebo/dave_gz_sensor_plugins/src/UnderwaterCamera.cc @@ -104,13 +104,6 @@ void UnderwaterCamera::Configure( gzdbg << "dave_gz_sensor_plugins::UnderwaterCamera::Configure on entity: " << _entity << std::endl; - if (!rclcpp::ok()) - { - rclcpp::init(0, nullptr); - } - - this->ros_node_ = std::make_shared("underwater_camera_node"); - auto rgbdCamera = _ecm.Component(_entity); if (!rgbdCamera) { @@ -133,6 +126,14 @@ void UnderwaterCamera::Configure( return; } + if (!rclcpp::ok()) + { + rclcpp::init(0, nullptr); + } + + std::string rosNodeName = sensorSdf.Name() + "_node"; + this->ros_node_ = std::make_shared(rosNodeName); + if (this->dataPtr->topic.empty()) { auto scoped = gz::sim::scopedName(_entity, _ecm);