Skip to content

Commit

Permalink
Modify wrong.
Browse files Browse the repository at this point in the history
  • Loading branch information
liyixin135 committed Jul 18, 2024
1 parent 64b79a6 commit 5904f01
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion include/rm_manual/manual_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ class ManualBase

ros::Subscriber odom_sub_, dbus_sub_, track_sub_, referee_sub_, capacity_sub_, game_status_sub_, joint_state_sub_,
game_robot_hp_sub_, actuator_state_sub_, power_heat_data_sub_, gimbal_des_error_sub_, game_robot_status_sub_,
suggest_fire_sub_, shoot_beforehand_cmd_sub_, gimbal_pos_state_pub_;
suggest_fire_sub_, shoot_beforehand_cmd_sub_, gimbal_pos_state_sub_;

sensor_msgs::JointState joint_state_;
rm_msgs::TrackData track_data_;
Expand Down
2 changes: 1 addition & 1 deletion src/manual_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ ManualBase::ManualBase(ros::NodeHandle& nh, ros::NodeHandle& nh_referee)
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);
gimbal_pos_state_pub_ = nh.subscribe<rm_msgs::GimbalPosState>("/controllers/gimbal_controller/pitch/pos_state", 10,
gimbal_pos_state_sub_ = nh.subscribe<rm_msgs::GimbalPosState>("/controllers/gimbal_controller/pitch/pos_state", 10,
&ManualBase::gimbalPosStateCallback, this);
odom_sub_ = nh.subscribe<nav_msgs::Odometry>("/odom", 10, &ManualBase::odomCallback, this);

Expand Down

0 comments on commit 5904f01

Please sign in to comment.