From 933c3d49485e843d80f205464e99d794b59aba79 Mon Sep 17 00:00:00 2001 From: WUYOUJIAN <117335706+YoujianWu@users.noreply.github.com> Date: Sat, 21 Sep 2024 11:10:31 +0800 Subject: [PATCH] Add a variable to select dbus topic. --- src/manual_base.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/manual_base.cpp b/src/manual_base.cpp index 87f73004..de10cc50 100644 --- a/src/manual_base.cpp +++ b/src/manual_base.cpp @@ -8,11 +8,13 @@ namespace rm_manual ManualBase::ManualBase(ros::NodeHandle& nh, ros::NodeHandle& nh_referee) : controller_manager_(nh), tf_listener_(tf_buffer_), nh_(nh) { + std::string dbus_topic_; + dbus_topic_ = getParam(nh, "dbus_topic", std::string("/rm_ecat_hw/dbus")); // sub joint_state_sub_ = nh.subscribe("/joint_states", 10, &ManualBase::jointStateCallback, this); actuator_state_sub_ = nh.subscribe("/actuator_states", 10, &ManualBase::actuatorStateCallback, this); - dbus_sub_ = nh.subscribe("/dbus_data", 10, &ManualBase::dbusDataCallback, this); + dbus_sub_ = nh.subscribe(dbus_topic_, 10, &ManualBase::dbusDataCallback, this); track_sub_ = nh.subscribe("/track", 10, &ManualBase::trackCallback, this); gimbal_des_error_sub_ = nh.subscribe("/controllers/gimbal_controller/error", 10, &ManualBase::gimbalDesErrorCallback, this);