Skip to content

Commit

Permalink
Merge pull request #117 from YoujianWu/master
Browse files Browse the repository at this point in the history
Add a variable to select dbus topic.
  • Loading branch information
YoujianWu authored Sep 21, 2024
2 parents 0c69cc4 + 933c3d4 commit 8fbed66
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion src/manual_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<sensor_msgs::JointState>("/joint_states", 10, &ManualBase::jointStateCallback, this);
actuator_state_sub_ =
nh.subscribe<rm_msgs::ActuatorState>("/actuator_states", 10, &ManualBase::actuatorStateCallback, this);
dbus_sub_ = nh.subscribe<rm_msgs::DbusData>("/dbus_data", 10, &ManualBase::dbusDataCallback, this);
dbus_sub_ = nh.subscribe<rm_msgs::DbusData>(dbus_topic_, 10, &ManualBase::dbusDataCallback, this);
track_sub_ = nh.subscribe<rm_msgs::TrackData>("/track", 10, &ManualBase::trackCallback, this);
gimbal_des_error_sub_ = nh.subscribe<rm_msgs::GimbalDesError>("/controllers/gimbal_controller/error", 10,
&ManualBase::gimbalDesErrorCallback, this);
Expand Down

0 comments on commit 8fbed66

Please sign in to comment.