diff --git a/rmcs_ws/src/rmcs_bringup/config/steering-hero.yaml b/rmcs_ws/src/rmcs_bringup/config/steering-hero.yaml
new file mode 100644
index 00000000..61946dff
--- /dev/null
+++ b/rmcs_ws/src/rmcs_bringup/config/steering-hero.yaml
@@ -0,0 +1,276 @@
+rmcs_executor:
+ ros__parameters:
+ update_rate: 1000.0
+ components:
+ - rmcs_core::hardware::SteeringHero -> hero_hardware
+
+ - rmcs_core::referee::Status -> referee_status
+ - rmcs_core::referee::command::Interaction -> referee_interaction
+ # - rmcs_core::referee::command::interaction::Ui -> referee_ui
+ # - rmcs_core::referee::app::ui::Hero -> referee_ui_hero
+ - rmcs_core::referee::Command -> referee_command
+
+ - rmcs_core::controller::gimbal::HeroGimbalController -> gimbal_controller
+ - rmcs_core::controller::gimbal::DualYawController -> dual_yaw_controller
+ - rmcs_core::controller::pid::ErrorPidController -> pitch_angle_pid_controller
+ - rmcs_core::controller::pid::PidController -> pitch_velocity_pid_controller
+
+ # - rmcs_core::controller::gimbal::PlayerViewer -> gimbal_player_viewer_controller
+ # - rmcs_core::controller::pid::ErrorPidController -> viewer_angle_pid_controller
+
+ - rmcs_core::controller::shooting::FrictionWheelController -> friction_wheel_controller
+ - rmcs_core::controller::shooting::HeatController -> heat_controller
+ - rmcs_core::controller::shooting::PutterController -> bullet_feeder_controller
+ - rmcs_core::controller::pid::PidController -> first_left_friction_velocity_pid_controller
+ - rmcs_core::controller::pid::PidController -> first_right_friction_velocity_pid_controller
+ - rmcs_core::controller::pid::PidController -> second_left_friction_velocity_pid_controller
+ - rmcs_core::controller::pid::PidController -> second_right_friction_velocity_pid_controller
+ # - rmcs_core::controller::shooting::ShootingRecorder -> shooting_recorder
+
+ - rmcs_core::controller::chassis::ChassisController -> chassis_controller
+ - rmcs_core::controller::chassis::ChassisPowerController -> chassis_power_controller
+ - rmcs_core::controller::chassis::SteeringWheelController -> steering_wheel_controller
+ - rmcs_core::controller::chassis::ChassisClimberController -> climber_controller
+
+ # - rmcs_auto_aim::AutoAimInitializer -> auto_aim_initializer
+ # - rmcs_auto_aim::AutoAimController -> auto_aim_controller
+
+ - rmcs_core::broadcaster::ValueBroadcaster -> value_broadcaster
+
+hero_hardware:
+ ros__parameters:
+ board_serial_top_board: "D4-2BCA-2E47-76CD-23BC-0B78-684B"
+ board_serial_bottom_board_one: "D4-7973-19A9-EA40-4A3E-306F-10F9"
+ board_serial_bottom_board_two: "D4-3674-7174-8768-879E-E44A-3931"
+ bottom_yaw_motor_zero_point: 52508
+ pitch_motor_zero_point: 63917
+ top_yaw_motor_zero_point: 58744
+ viewer_motor_zero_point: 3030
+ external_imu_port: /dev/ttyUSB0
+ left_front_zero_point: 4438
+ right_front_zero_point: 7167
+ left_back_zero_point: 370
+ right_back_zero_point: 5156
+ q0: 0.0
+ q1: 0.0
+ q2: 0.0
+ q3: 1.0
+ # left_front_zero_point: 3473
+ # left_back_zero_point: 6124
+ # right_back_zero_point: 6157
+ # right_front_zero_point: 2723
+
+value_broadcaster:
+ ros__parameters:
+ forward_list:
+ - /chassis/left_front_steering/angle
+ - /chassis/left_back_steering/angle
+ - /chassis/right_back_steering/angle
+ - /chassis/right_front_steering/angle
+ - /chassis/left_front_steering/control_torque
+ - /chassis/left_back_steering/control_torque
+ - /chassis/right_back_steering/control_torque
+ - /chassis/right_front_steering/control_torque
+ - /gimbal/pitch/control_torque
+ - /gimbal/pitch/velocity
+ - /gimbal/pitch/control_velocity
+ - /gimbal/pitch/control_angle_error
+ - /chassis/climber/left_back_motor/torque
+ - /chassis/climber/right_back_motor/torque
+ - /chassis/climber/left_back_motor/velocity
+ - /chassis/climber/right_back_motor/velocity
+ - /chassis/climber/right_back_motor/control_torque
+ - /chassis/climber/left_back_motor/control_torque
+
+climber_controller:
+ ros__parameters:
+ front_climber_velocity: 60.0
+ back_climber_velocity: 20.0
+ auto_climb_dash_velocity: 3.0
+ auto_climb_support_retract_velocity: 30.0
+ sync_coefficient: 0.3
+ climb_timeout_limit: 1000
+ first_stair_approach_pitch: 0.485
+ second_stair_approach_pitch: 0.35
+ back_climber_burst_velocity: 15.0
+ back_climber_burst_duration: 300
+ front_kp: 1.0
+ front_ki: 0.0
+ front_kd: 0.5
+ back_kp: 1.0
+ back_ki: 0.0
+ back_kd: 0.0
+
+gimbal_controller:
+ ros__parameters:
+ upper_limit: -0.6266
+ lower_limit: 0.4629
+
+dual_yaw_controller:
+ ros__parameters:
+ top_yaw_angle_kp: 10.0
+ top_yaw_angle_ki: 0.0
+ top_yaw_angle_kd: 0.0
+ top_yaw_velocity_kp: 50.0
+ top_yaw_velocity_ki: 0.004
+ top_yaw_velocity_kd: 0.0
+ bottom_yaw_angle_kp: 5.0
+ bottom_yaw_angle_ki: 0.0
+ bottom_yaw_angle_kd: 0.0
+ bottom_yaw_velocity_kp: 10.0
+ bottom_yaw_velocity_ki: 0.0
+ bottom_yaw_velocity_kd: 50.0
+
+# dual_yaw_controller:
+# ros__parameters:
+# top_yaw_angle_kp: 24.5
+# top_yaw_angle_ki: 0.0
+# top_yaw_angle_kd: 0.0
+# top_yaw_velocity_kp: 77.4
+# top_yaw_velocity_ki: 0.004
+# top_yaw_velocity_kd: 1.0
+# bottom_yaw_angle_kp: 8.6
+# bottom_yaw_angle_ki: 0.0
+# bottom_yaw_angle_kd: 0.0
+# bottom_yaw_velocity_kp: 25.85
+# bottom_yaw_velocity_ki: 0.0
+# bottom_yaw_velocity_kd: 50.0
+
+pitch_angle_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/pitch/control_angle_error
+ control: /gimbal/pitch/control_velocity
+ kp: 28.0 #28.00
+ ki: 0.0
+ kd: 0.6 #0.6
+
+pitch_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/pitch/velocity_imu
+ setpoint: /gimbal/pitch/control_velocity
+ control: /gimbal/pitch/control_torque
+ kp: 45.0 #45.00
+ ki: 0.00
+ kd: 1.0 #1.00
+
+gimbal_player_viewer_controller:
+ ros__parameters:
+ upper_limit: 0.0101
+ lower_limit: 0.6191
+
+viewer_angle_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/player_viewer/control_angle_error
+ control: /gimbal/player_viewer/control_velocity
+ kp: 17.00
+ ki: 0.00
+ kd: 2.00
+
+friction_wheel_controller:
+ ros__parameters:
+ friction_wheels:
+ - /gimbal/first_left_friction
+ - /gimbal/first_right_friction
+ - /gimbal/second_left_friction
+ - /gimbal/second_right_friction
+ friction_velocities:
+ - 450.00
+ - 450.00
+ - 535.00
+ - 535.00
+ friction_soft_start_stop_time: 1.0
+
+heat_controller:
+ ros__parameters:
+ heat_per_shot: 100000
+ reserved_heat: 0
+
+shooting_recorder:
+ ros__parameters:
+ friction_wheel_count: 2
+ log_mode: 2 # 1: trigger, 2: timing
+
+first_left_friction_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/first_left_friction/velocity
+ setpoint: /gimbal/first_left_friction/control_velocity
+ control: /gimbal/first_left_friction/control_torque
+ kp: 0.003436926
+ ki: 0.00
+ kd: 0.009373434
+
+first_right_friction_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/first_right_friction/velocity
+ setpoint: /gimbal/first_right_friction/control_velocity
+ control: /gimbal/first_right_friction/control_torque
+ kp: 0.003436926
+ ki: 0.00
+ kd: 0.009373434
+
+second_left_friction_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/second_left_friction/velocity
+ setpoint: /gimbal/second_left_friction/control_velocity
+ control: /gimbal/second_left_friction/control_torque
+ kp: 0.003436926
+ ki: 0.00
+ kd: 0.009373434
+
+second_right_friction_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/second_right_friction/velocity
+ setpoint: /gimbal/second_right_friction/control_velocity
+ control: /gimbal/second_right_friction/control_torque
+ kp: 0.003436926
+ ki: 0.00
+ kd: 0.009373434
+
+steering_wheel_controller:
+ ros__parameters:
+ mess: 22.0
+ moment_of_inertia: 1.08
+ vehicle_radius: 0.28284271247462
+ wheel_radius: 0.055
+ friction_coefficient: 0.6
+ k1: 2.958580e+00
+ k2: 3.082190e-03
+ no_load_power: 11.37
+
+auto_aim_controller:
+ ros__parameters:
+ # capture
+ use_video: false # If true, use video stream instead of camera.
+ video_path: "/workspaces/RMCS/rmcs_ws/resources/1.avi"
+ exposure_time: 1
+ invert_image: false
+ # identifier
+ armor_model_path: "/models/mlp.onnx"
+ # pnp
+ fx: 1.722231837421459e+03
+ fy: 1.724876404292754e+03
+ cx: 7.013056440882832e+02
+ cy: 5.645821718351237e+02
+ k1: -0.064232403853946
+ k2: -0.087667493884102
+ k3: 0.792381808294582
+ # tracker
+ armor_predict_duration: 500
+ # controller
+ gimbal_predict_duration: 100
+ yaw_error: 0.
+ pitch_error: 0.
+ shoot_velocity: 28.0
+ predict_sec: 0.095
+ # etc
+ buff_predict_duration: 200
+ buff_model_path: "/models/buff_nocolor_v6.onnx"
+ omni_exposure: 1000.0
+ record_fps: 120
+ debug: false # Setup in actual using.Debug mode is used when referee is not ready
+ debug_color: 0 # 0 For blue while 1 for red. mine
+ debug_robot_id: 4
+ debug_buff_mode: false
+ record: false
+ raw_img_pub: false # Set false in actual use
+ image_viewer_type: 2
diff --git a/rmcs_ws/src/rmcs_core/plugins.xml b/rmcs_ws/src/rmcs_core/plugins.xml
index f7847151..9df7668b 100644
--- a/rmcs_ws/src/rmcs_core/plugins.xml
+++ b/rmcs_ws/src/rmcs_core/plugins.xml
@@ -1,29 +1,128 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Steering wheel controller.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Gimbal player viewer
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ the recorder of Hero
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Feedforward pid controller.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
+ Test plugin.
+
+
\ No newline at end of file
diff --git a/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_climber_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_climber_controller.cpp
new file mode 100644
index 00000000..76d0ffd0
--- /dev/null
+++ b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_climber_controller.cpp
@@ -0,0 +1,481 @@
+#include "controller/pid/matrix_pid_calculator.hpp"
+#include "rmcs_msgs/keyboard.hpp"
+#include "rmcs_msgs/switch.hpp"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace rmcs_core::controller::chassis {
+
+enum class AutoClimbState { IDLE, APPROACH, SUPPORT_DEPLOY, DASH, SUPPORT_RETRACT };
+
+class ChassisClimberController
+ : public rmcs_executor::Component
+ , public rclcpp::Node {
+public:
+ ChassisClimberController()
+ : Node(
+ get_component_name(),
+ rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true))
+ , logger_(get_logger())
+ , front_velocity_pid_calculator_(
+ get_parameter("front_kp").as_double(), get_parameter("front_ki").as_double(),
+ get_parameter("front_kd").as_double())
+ , back_velocity_pid_calculator_(
+ get_parameter("back_kp").as_double(), get_parameter("back_ki").as_double(),
+ get_parameter("back_kd").as_double()) {
+
+ track_velocity_max_ = get_parameter("front_climber_velocity").as_double();
+ climber_back_control_velocity_abs_ = get_parameter("back_climber_velocity").as_double();
+ auto_climb_dash_velocity_ = get_parameter("auto_climb_dash_velocity").as_double();
+ auto_climb_support_retract_velocity_abs_ =
+ get_parameter("auto_climb_support_retract_velocity").as_double();
+ sync_coefficient_ = get_parameter("sync_coefficient").as_double();
+ climb_timeout_limit_ = get_parameter("climb_timeout_limit").as_int();
+ first_stair_approach_pitch_ = get_parameter("first_stair_approach_pitch").as_double();
+ second_stair_approach_pitch_ = get_parameter("second_stair_approach_pitch").as_double();
+
+ burst_velocity_abs_ = get_parameter("back_climber_burst_velocity").as_double();
+ burst_duration_ = get_parameter("back_climber_burst_duration").as_int();
+
+ back_climber_block_count_ = 0;
+ back_climber_timer_ = 0;
+
+ register_output(
+ "/chassis/climber/left_front_motor/control_torque", climber_front_left_control_torque_,
+ nan_);
+ register_output(
+ "/chassis/climber/right_front_motor/control_torque",
+ climber_front_right_control_torque_, nan_);
+ register_output(
+ "/chassis/climber/left_back_motor/control_torque", climber_back_left_control_torque_,
+ nan_);
+ register_output(
+ "/chassis/climber/right_back_motor/control_torque", climber_back_right_control_torque_,
+ nan_);
+ register_output("/chassis/climbing_forward_velocity", climbing_forward_velocity_, nan_);
+
+ register_input("/chassis/climber/left_front_motor/velocity", climber_front_left_velocity_);
+ register_input(
+ "/chassis/climber/right_front_motor/velocity", climber_front_right_velocity_);
+ register_input("/chassis/climber/left_back_motor/velocity", climber_back_left_velocity_);
+ register_input("/chassis/climber/right_back_motor/velocity", climber_back_right_velocity_);
+
+ register_input("/chassis/climber/left_back_motor/torque", climber_back_left_torque_);
+ register_input("/chassis/climber/right_back_motor/torque", climber_back_right_torque_);
+
+ register_input("/remote/switch/right", switch_right_);
+ register_input("/remote/switch/left", switch_left_);
+ register_input("/remote/joystick/right", joystick_right_);
+ register_input("/remote/keyboard", keyboard_);
+ register_input("/remote/rotary_knob_switch", rotary_knob_switch_);
+ register_input("/chassis/pitch_imu", chassis_pitch_imu_);
+ }
+
+ void update() override {
+ using namespace rmcs_msgs;
+
+ auto switch_right = *switch_right_;
+ auto switch_left = *switch_left_;
+ auto keyboard = *keyboard_;
+ auto rotary_knob_switch = *rotary_knob_switch_;
+
+ // RCLCPP_INFO(logger_, "%lf", *chassis_pitch_imu_);
+
+ bool rotary_knob_to_up =
+ (last_rotary_knob_switch_ != Switch::UP && rotary_knob_switch == Switch::UP);
+ bool rotary_knob_from_up =
+ (last_rotary_knob_switch_ == Switch::UP && rotary_knob_switch != Switch::UP);
+
+ if ((switch_left == Switch::UNKNOWN || switch_right == Switch::UNKNOWN)
+ || (switch_left == Switch::DOWN && switch_right == Switch::DOWN)) {
+ reset_all_controls();
+ } else {
+ handle_auto_climb_requests(
+ (!last_keyboard_.g && keyboard.g) || rotary_knob_to_up, rotary_knob_from_up,
+ rotary_knob_switch);
+
+ if (auto_climb_state_ != AutoClimbState::IDLE) {
+ apply_auto_climb_control(update_auto_climb_control());
+ } else if (switch_left != Switch::DOWN) {
+ update_manual_control();
+ }
+ }
+
+ last_switch_left_ = switch_left;
+ last_switch_right_ = switch_right;
+ last_keyboard_ = keyboard;
+ last_rotary_knob_switch_ = rotary_knob_switch;
+ }
+
+private:
+ struct AutoClimbControl {
+ double front_track_velocity = 0.0;
+ double back_climber_velocity = 0.0;
+ double override_chassis_vx = nan_;
+ };
+
+ void handle_auto_climb_requests(
+ bool start_requested, bool abort_by_rotary, rmcs_msgs::Switch rotary_knob_switch) {
+
+ if (start_requested) {
+ if (auto_climb_state_ == AutoClimbState::IDLE) {
+ start_auto_climb(
+ rotary_knob_switch == rmcs_msgs::Switch::UP ? "Rotary Knob" : "Keyboard G");
+ } else {
+ abort_auto_climb("toggled again");
+ }
+ } else if (abort_by_rotary && auto_climb_state_ != AutoClimbState::IDLE) {
+ abort_auto_climb("rotary knob left UP");
+ }
+ }
+
+ void start_auto_climb(const char* source) {
+ auto_climb_continue_ = true;
+ auto_climb_stair_index_ = 0;
+ auto_climb_support_block_count_ = 0;
+ enter_auto_climb_state(AutoClimbState::APPROACH);
+
+ RCLCPP_INFO(logger_, "Auto climb started by %s.", source);
+ }
+
+ void abort_auto_climb(const char* reason) {
+ reset_all_controls();
+ RCLCPP_INFO(logger_, "Auto climb aborted (%s).", reason);
+ }
+
+ AutoClimbControl update_auto_climb_control() {
+ auto_climb_timer_++;
+
+ switch (auto_climb_state_) {
+ case AutoClimbState::IDLE: return {};
+ case AutoClimbState::APPROACH: return update_auto_climb_approach();
+ case AutoClimbState::SUPPORT_DEPLOY: return update_auto_climb_support_deploy();
+ case AutoClimbState::DASH: return update_auto_climb_dash();
+ case AutoClimbState::SUPPORT_RETRACT: return update_auto_climb_support_retract();
+ }
+
+ return {};
+ }
+
+ AutoClimbControl update_auto_climb_approach() {
+ AutoClimbControl control{
+ .front_track_velocity = track_velocity_max_,
+ .back_climber_velocity = 0.0,
+ .override_chassis_vx = kAutoClimbApproachVelocity,
+ };
+
+ double pitch = *chassis_pitch_imu_;
+ double target_pitch = auto_climb_stair_index_ == 0 ? first_stair_approach_pitch_
+ : second_stair_approach_pitch_;
+
+ RCLCPP_INFO_THROTTLE(
+ logger_, *get_clock(), 500, "APPROACH (step %d): pitch=%.3f, target>%.3f",
+ auto_climb_stair_index_ + 1, pitch, target_pitch);
+
+ if (pitch > target_pitch) {
+ enter_auto_climb_state(AutoClimbState::SUPPORT_DEPLOY);
+ RCLCPP_INFO(
+ logger_, "Auto climb entering SUPPORT_DEPLOY (step %d).",
+ auto_climb_stair_index_ + 1);
+ }
+
+ return control;
+ }
+
+ AutoClimbControl update_auto_climb_support_deploy() {
+ AutoClimbControl control{
+ .front_track_velocity = 0.0,
+ .back_climber_velocity = climber_back_control_velocity_abs_,
+ .override_chassis_vx = 0.2,
+ };
+
+ if (is_back_climber_blocked()) {
+ auto_climb_support_block_count_++;
+ } else {
+ auto_climb_support_block_count_ = 0;
+ }
+
+ RCLCPP_INFO_THROTTLE(
+ logger_, *get_clock(), 500, "SUPPORT_DEPLOY (step %d): blocked_ticks=%d",
+ auto_climb_stair_index_ + 1, auto_climb_support_block_count_);
+
+ if (auto_climb_support_block_count_ >= kAutoClimbSupportConfirmTicks) {
+ enter_auto_climb_state(AutoClimbState::DASH);
+ RCLCPP_INFO(
+ logger_, "Auto climb entering DASH (step %d).", auto_climb_stair_index_ + 1);
+ }
+
+ return control;
+ }
+
+ AutoClimbControl update_auto_climb_dash() {
+ AutoClimbControl control{
+ .front_track_velocity = track_velocity_max_,
+ .back_climber_velocity = climber_back_control_velocity_abs_,
+ .override_chassis_vx = auto_climb_dash_velocity_,
+ };
+
+ double pitch = *chassis_pitch_imu_;
+ bool is_leveled = std::abs(pitch) < kAutoClimbLeveledPitchThreshold
+ && auto_climb_timer_ > kAutoClimbDashMinTicks;
+ bool timeout = auto_climb_timer_ > kAutoClimbDashTimeoutTicks;
+
+ RCLCPP_INFO_THROTTLE(
+ logger_, *get_clock(), 500, "DASH (step %d): pitch=%.3f, timer=%d",
+ auto_climb_stair_index_ + 1, pitch, auto_climb_timer_);
+
+ if (is_leveled || timeout) {
+ enter_auto_climb_state(AutoClimbState::SUPPORT_RETRACT);
+
+ if (timeout) {
+ RCLCPP_WARN(
+ logger_, "Auto climb DASH timeout on step %d. Entering SUPPORT_RETRACT.",
+ auto_climb_stair_index_ + 1);
+ } else {
+ RCLCPP_INFO(
+ logger_, "Auto climb reached platform on step %d.",
+ auto_climb_stair_index_ + 1);
+ }
+ }
+
+ return control;
+ }
+
+ AutoClimbControl update_auto_climb_support_retract() {
+ AutoClimbControl control{
+ .front_track_velocity = track_velocity_max_,
+ .back_climber_velocity = -auto_climb_support_retract_velocity_abs_,
+ .override_chassis_vx = auto_climb_dash_velocity_,
+ };
+
+ RCLCPP_INFO_THROTTLE(
+ logger_, *get_clock(), 500, "SUPPORT_RETRACT (step %d): timer=%d",
+ auto_climb_stair_index_ + 1, auto_climb_timer_);
+
+ if (auto_climb_timer_ > kAutoClimbSupportRetractTicks) {
+ bool has_next_stair =
+ auto_climb_continue_ && (auto_climb_stair_index_ + 1 < kAutoClimbMaxStairs);
+
+ if (has_next_stair) {
+ auto_climb_stair_index_++;
+ enter_auto_climb_state(AutoClimbState::APPROACH);
+ RCLCPP_INFO(
+ logger_, "Auto climb continuing to step %d.", auto_climb_stair_index_ + 1);
+ } else {
+ int finished_steps = auto_climb_stair_index_ + 1;
+ stop_auto_climb();
+ RCLCPP_INFO(logger_, "Auto climb completed (finished %d steps).", finished_steps);
+ }
+ }
+
+ return control;
+ }
+
+ void apply_auto_climb_control(const AutoClimbControl& control) {
+ *climbing_forward_velocity_ = control.override_chassis_vx;
+
+ dual_motor_sync_control(
+ control.front_track_velocity, *climber_front_left_velocity_,
+ *climber_front_right_velocity_, front_velocity_pid_calculator_,
+ *climber_front_left_control_torque_, *climber_front_right_control_torque_);
+
+ dual_motor_sync_control(
+ control.back_climber_velocity, *climber_back_left_velocity_,
+ *climber_back_right_velocity_, back_velocity_pid_calculator_,
+ *climber_back_left_control_torque_, *climber_back_right_control_torque_);
+ }
+
+ void update_manual_control() {
+ *climbing_forward_velocity_ = nan_;
+
+ // if (last_switch_right_ == Switch::MIDDLE && switch_right == Switch::UP) {
+ // front_climber_enable_ = !front_climber_enable_;
+ // } else if (last_switch_right_ == Switch::MIDDLE && switch_right == Switch::DOWN) {
+ // back_climber_dir_ = -1 * back_climber_dir_;
+ // reset_back_safety_counters();
+ // }
+
+ double track_control_velocity =
+ front_climber_enable_ ? joystick_right_->x() * track_velocity_max_ : nan_;
+
+ dual_motor_sync_control(
+ track_control_velocity, *climber_front_left_velocity_, *climber_front_right_velocity_,
+ front_velocity_pid_calculator_, *climber_front_left_control_torque_,
+ *climber_front_right_control_torque_);
+
+ double back_climber_control_velocity = 0.0;
+ back_climber_timer_++;
+ bool force_zero_torque = false;
+
+ if (is_back_climber_blocked()) {
+ back_climber_block_count_++;
+ }
+
+ if (back_climber_dir_ == -1) {
+ if (back_climber_timer_ < burst_duration_) {
+ back_climber_control_velocity = burst_velocity_abs_ * back_climber_dir_;
+ } else {
+ force_zero_torque = true;
+ }
+ } else {
+ back_climber_control_velocity = climber_back_control_velocity_abs_ * back_climber_dir_;
+ }
+
+ if (!force_zero_torque) {
+ if (back_climber_block_count_ >= 500) {
+ RCLCPP_WARN_THROTTLE(logger_, *get_clock(), 1000, "Back climber STALLED.");
+ back_climber_control_velocity = 0.0;
+ } else if (back_climber_timer_ >= climb_timeout_limit_) {
+ RCLCPP_WARN_THROTTLE(logger_, *get_clock(), 1000, "Back climber TIMEOUT.");
+ back_climber_control_velocity = 0.0;
+ }
+
+ dual_motor_sync_control(
+ back_climber_control_velocity, *climber_back_left_velocity_,
+ *climber_back_right_velocity_, back_velocity_pid_calculator_,
+ *climber_back_left_control_torque_, *climber_back_right_control_torque_);
+ } else {
+ *climber_back_left_control_torque_ = 0.0;
+ *climber_back_right_control_torque_ = 0.0;
+ }
+ }
+
+ void reset_all_controls() {
+ *climber_front_left_control_torque_ = 0;
+ *climber_front_right_control_torque_ = 0;
+ *climber_back_left_control_torque_ = 0;
+ *climber_back_right_control_torque_ = 0;
+ front_climber_enable_ = false;
+ *climbing_forward_velocity_ = nan_;
+ stop_auto_climb();
+ reset_back_safety_counters();
+ }
+
+ void stop_auto_climb() {
+ auto_climb_state_ = AutoClimbState::IDLE;
+ auto_climb_timer_ = 0;
+ auto_climb_stair_index_ = 0;
+ auto_climb_continue_ = false;
+ auto_climb_support_block_count_ = 0;
+ }
+
+ void enter_auto_climb_state(AutoClimbState state) {
+ auto_climb_state_ = state;
+ auto_climb_timer_ = 0;
+ auto_climb_support_block_count_ = 0;
+ }
+
+ void reset_back_safety_counters() {
+ back_climber_block_count_ = 0;
+ back_climber_timer_ = 0;
+ }
+
+ bool is_back_climber_blocked() const {
+ return (std::abs(*climber_back_left_torque_) > kBackClimberBlockedTorqueThreshold
+ && std::abs(*climber_back_left_velocity_) < kBackClimberBlockedVelocityThreshold)
+ || (std::abs(*climber_back_right_torque_) > kBackClimberBlockedTorqueThreshold
+ && std::abs(*climber_back_right_velocity_) < kBackClimberBlockedVelocityThreshold);
+ }
+
+ void dual_motor_sync_control(
+ double setpoint, double left_velocity, double right_velocity,
+ pid::MatrixPidCalculator<2>& pid_calculator, double& left_torque_out,
+ double& right_torque_out) {
+
+ if (std::isnan(setpoint)) {
+ left_torque_out = nan_;
+ right_torque_out = nan_;
+ return;
+ }
+
+ Eigen::Vector2d setpoint_error{setpoint - left_velocity, setpoint - right_velocity};
+ Eigen::Vector2d relative_velocity{
+ left_velocity - right_velocity, right_velocity - left_velocity};
+
+ Eigen::Vector2d control_error = setpoint_error - sync_coefficient_ * relative_velocity;
+ auto control_torques = pid_calculator.update(control_error);
+
+ left_torque_out = control_torques[0];
+ right_torque_out = control_torques[1];
+ }
+
+ int back_climber_block_count_;
+ int back_climber_timer_;
+
+ rclcpp::Logger logger_;
+ static constexpr double nan_ = std::numeric_limits::quiet_NaN();
+ static constexpr double kAutoClimbApproachVelocity = 1.0;
+ static constexpr double kAutoClimbLeveledPitchThreshold = 0.1;
+ static constexpr double kBackClimberBlockedTorqueThreshold = 0.1;
+ static constexpr double kBackClimberBlockedVelocityThreshold = 0.1;
+ static constexpr int kAutoClimbSupportConfirmTicks = 50;
+ static constexpr int kAutoClimbDashMinTicks = 500;
+ static constexpr int kAutoClimbDashTimeoutTicks = 3000;
+ static constexpr int kAutoClimbSupportRetractTicks = 1000;
+ static constexpr int kAutoClimbMaxStairs = 2;
+
+ double sync_coefficient_;
+ int64_t climb_timeout_limit_;
+ double first_stair_approach_pitch_;
+ double second_stair_approach_pitch_;
+
+ double burst_velocity_abs_;
+ int64_t burst_duration_;
+
+ bool front_climber_enable_ = false;
+ double back_climber_dir_ = -1;
+
+ double track_velocity_max_;
+ double climber_back_control_velocity_abs_;
+ double auto_climb_dash_velocity_;
+ double auto_climb_support_retract_velocity_abs_;
+
+ AutoClimbState auto_climb_state_ = AutoClimbState::IDLE;
+ int auto_climb_timer_ = 0;
+ int auto_climb_stair_index_ = 0;
+ int auto_climb_support_block_count_ = 0;
+ bool auto_climb_continue_ = false;
+
+ OutputInterface climber_front_left_control_torque_;
+ OutputInterface climber_front_right_control_torque_;
+ OutputInterface climber_back_left_control_torque_;
+ OutputInterface climber_back_right_control_torque_;
+ OutputInterface climbing_forward_velocity_;
+
+ InputInterface climber_front_left_velocity_;
+ InputInterface climber_front_right_velocity_;
+ InputInterface climber_back_left_velocity_;
+ InputInterface climber_back_right_velocity_;
+
+ InputInterface climber_back_left_torque_;
+ InputInterface climber_back_right_torque_;
+
+ InputInterface switch_right_;
+ InputInterface switch_left_;
+ InputInterface joystick_right_;
+ InputInterface keyboard_;
+ InputInterface rotary_knob_switch_;
+
+ InputInterface chassis_pitch_imu_;
+
+ rmcs_msgs::Switch last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Switch last_rotary_knob_switch_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
+
+ pid::MatrixPidCalculator<2> front_velocity_pid_calculator_, back_velocity_pid_calculator_;
+};
+} // namespace rmcs_core::controller::chassis
+
+#include
+
+PLUGINLIB_EXPORT_CLASS(
+ rmcs_core::controller::chassis::ChassisClimberController, rmcs_executor::Component)
diff --git a/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_controller.cpp
index da70a96f..af18ba43 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_controller.cpp
@@ -19,7 +19,7 @@ class ChassisController
: Node(
get_component_name(),
rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true))
- , following_velocity_controller_(7.0, 0.0, 0.0) {
+ , following_velocity_controller_(10.0, 0.0, 1.2) {
following_velocity_controller_.output_max = angular_velocity_max;
following_velocity_controller_.output_min = -angular_velocity_max;
@@ -34,6 +34,7 @@ class ChassisController
register_input("/gimbal/yaw/angle", gimbal_yaw_angle_, false);
register_input("/gimbal/yaw/control_angle_error", gimbal_yaw_angle_error_, false);
+ register_input("/chassis/climbing_forward_velocity", climbing_forward_velocity_, nan);
register_output("/chassis/angle", chassis_angle_, nan);
register_output("/chassis/control_angle", chassis_control_angle_, nan);
@@ -58,8 +59,8 @@ class ChassisController
using namespace rmcs_msgs;
auto switch_right = *switch_right_;
- auto switch_left = *switch_left_;
- auto keyboard = *keyboard_;
+ auto switch_left = *switch_left_;
+ auto keyboard = *keyboard_;
do {
if ((switch_left == Switch::UNKNOWN || switch_right == Switch::UNKNOWN)
@@ -74,14 +75,14 @@ class ChassisController
if (mode == rmcs_msgs::ChassisMode::SPIN) {
mode = rmcs_msgs::ChassisMode::STEP_DOWN;
} else {
- mode = rmcs_msgs::ChassisMode::SPIN;
+ mode = rmcs_msgs::ChassisMode::SPIN;
spinning_forward_ = !spinning_forward_;
}
} else if (!last_keyboard_.c && keyboard.c) {
if (mode == rmcs_msgs::ChassisMode::SPIN) {
mode = rmcs_msgs::ChassisMode::AUTO;
} else {
- mode = rmcs_msgs::ChassisMode::SPIN;
+ mode = rmcs_msgs::ChassisMode::SPIN;
spinning_forward_ = !spinning_forward_;
}
} else if (!last_keyboard_.x && keyboard.x) {
@@ -100,8 +101,8 @@ class ChassisController
} while (false);
last_switch_right_ = switch_right;
- last_switch_left_ = switch_left;
- last_keyboard_ = keyboard;
+ last_switch_left_ = switch_left;
+ last_keyboard_ = keyboard;
}
void reset_all_controls() {
@@ -112,12 +113,16 @@ class ChassisController
void update_velocity_control() {
auto translational_velocity = update_translational_velocity_control();
- auto angular_velocity = update_angular_velocity_control();
+ auto angular_velocity = update_angular_velocity_control();
chassis_control_velocity_->vector << translational_velocity, angular_velocity;
}
Eigen::Vector2d update_translational_velocity_control() {
+ if (!std::isnan(*climbing_forward_velocity_)) {
+ return Eigen::Vector2d{*climbing_forward_velocity_, 0.0};
+ }
+
auto keyboard = *keyboard_;
Eigen::Vector2d keyboard_move{keyboard.w - keyboard.s, keyboard.a - keyboard.d};
@@ -133,7 +138,13 @@ class ChassisController
}
double update_angular_velocity_control() {
- double angular_velocity = 0.0;
+ if (!std::isnan(*climbing_forward_velocity_)) {
+ *chassis_angle_ = 2 * std::numbers::pi - *gimbal_yaw_angle_;
+ *chassis_control_angle_ = nan;
+ return 0.0;
+ }
+
+ double angular_velocity = 0.0;
double chassis_control_angle = nan;
switch (*mode_) {
@@ -171,7 +182,7 @@ class ChassisController
angular_velocity = following_velocity_controller_.update(err);
} break;
}
- *chassis_angle_ = 2 * std::numbers::pi - *gimbal_yaw_angle_;
+ *chassis_angle_ = 2 * std::numbers::pi - *gimbal_yaw_angle_;
*chassis_control_angle_ = chassis_control_angle;
return angular_velocity;
@@ -202,7 +213,7 @@ class ChassisController
// Maximum control velocities
static constexpr double translational_velocity_max = 10.0;
- static constexpr double angular_velocity_max = 16.0;
+ static constexpr double angular_velocity_max = 16.0;
InputInterface joystick_right_;
InputInterface joystick_left_;
@@ -214,10 +225,11 @@ class ChassisController
InputInterface rotary_knob_;
rmcs_msgs::Switch last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
- rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
- rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
+ rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
InputInterface gimbal_yaw_angle_, gimbal_yaw_angle_error_;
+ InputInterface climbing_forward_velocity_;
OutputInterface chassis_angle_, chassis_control_angle_;
OutputInterface mode_;
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/dual_yaw_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/dual_yaw_controller.cpp
index 80d7a72e..20c09236 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/dual_yaw_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/dual_yaw_controller.cpp
@@ -45,9 +45,6 @@ class DualYawController
register_output("/gimbal/top_yaw/control_torque", top_yaw_control_torque_, 0.0);
register_output("/gimbal/bottom_yaw/control_torque", bottom_yaw_control_torque_, 0.0);
- register_output("/gimbal/top_yaw/control_angle", top_yaw_control_torque_, 0.0);
- register_output("/gimbal/bottom_yaw/control_angle_shift", bottom_yaw_control_torque_, 0.0);
-
status_component_ =
create_partner_component(get_component_name() + "_status");
}
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/hero_gimbal_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/hero_gimbal_controller.cpp
index f20bd98f..1c6dde8b 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/hero_gimbal_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/hero_gimbal_controller.cpp
@@ -65,8 +65,9 @@ class HeroGimbalController
else
gimbal_mode_keyboard_ = GimbalMode::IMU;
}
- *gimbal_mode_ =
- *switch_right_ == Switch::UP ? GimbalMode::ENCODER : gimbal_mode_keyboard_;
+ // *gimbal_mode_ =
+ // *switch_right_ == Switch::UP ? GimbalMode::ENCODER : gimbal_mode_keyboard_;
+ *gimbal_mode_ = gimbal_mode_keyboard_;
if (*gimbal_mode_ == GimbalMode::IMU) {
auto angle_error = update_imu_control();
diff --git a/rmcs_ws/src/rmcs_core/src/controller/shooting/bullet_feeder_controller_42mm.cpp b/rmcs_ws/src/rmcs_core/src/controller/shooting/bullet_feeder_controller_42mm.cpp
index bf3076e3..95d75cb9 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/shooting/bullet_feeder_controller_42mm.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/shooting/bullet_feeder_controller_42mm.cpp
@@ -31,14 +31,15 @@ class BulletFeederController42mm
register_input(
"/gimbal/control_bullet_allowance/limited_by_heat",
control_bullet_allowance_limited_by_heat_);
+ register_input("/gimbal/bullet_fired", bullet_fired_);
- bullet_feeder_velocity_pid_.kp = 50.0;
- bullet_feeder_velocity_pid_.ki = 10.0;
- bullet_feeder_velocity_pid_.kd = 0.0;
+ bullet_feeder_velocity_pid_.kp = 50.0;
+ bullet_feeder_velocity_pid_.ki = 10.0;
+ bullet_feeder_velocity_pid_.kd = 0.0;
bullet_feeder_velocity_pid_.integral_max = 60.0;
bullet_feeder_velocity_pid_.integral_min = 0.0;
- bullet_feeder_angle_pid_.kp = 50.0;
+ bullet_feeder_angle_pid_.kp = 60.0;
bullet_feeder_angle_pid_.ki = 0.0;
bullet_feeder_angle_pid_.kd = 2.0;
@@ -51,9 +52,9 @@ class BulletFeederController42mm
void update() override {
const auto switch_right = *switch_right_;
- const auto switch_left = *switch_left_;
- const auto mouse = *mouse_;
- const auto keyboard = *keyboard_;
+ const auto switch_left = *switch_left_;
+ const auto mouse = *mouse_;
+ const auto keyboard = *keyboard_;
using namespace rmcs_msgs;
if ((switch_left == Switch::UNKNOWN || switch_right == Switch::UNKNOWN)
@@ -61,7 +62,6 @@ class BulletFeederController42mm
reset_all_controls();
return;
}
-
overdrive_mode_ = keyboard.f;
if (keyboard.ctrl && !last_keyboard_.r && keyboard.r)
low_latency_mode_ = !low_latency_mode_;
@@ -84,8 +84,8 @@ class BulletFeederController42mm
} else {
if (!*friction_ready_ || std::isnan(bullet_feeder_control_angle_)) {
bullet_feeder_control_angle_ = *bullet_feeder_angle_;
- shoot_stage_ = ShootStage::PRELOADED;
- bullet_fed_count_ = static_cast(
+ shoot_stage_ = ShootStage::PRELOADED;
+ bullet_fed_count_ = static_cast(
(*bullet_feeder_angle_ - bullet_feeder_compressed_zero_point_ - 0.1)
/ bullet_feeder_angle_per_bullet_);
}
@@ -135,24 +135,24 @@ class BulletFeederController42mm
}
last_switch_right_ = switch_right;
- last_switch_left_ = switch_left;
- last_mouse_ = mouse;
- last_keyboard_ = keyboard;
+ last_switch_left_ = switch_left;
+ last_mouse_ = mouse;
+ last_keyboard_ = keyboard;
}
private:
void reset_all_controls() {
last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
- last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
- last_mouse_ = rmcs_msgs::Mouse::zero();
- last_keyboard_ = rmcs_msgs::Keyboard::zero();
+ last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ last_mouse_ = rmcs_msgs::Mouse::zero();
+ last_keyboard_ = rmcs_msgs::Keyboard::zero();
overdrive_mode_ = low_latency_mode_ = false;
- shoot_stage_ = ShootStage::PRELOADED;
+ shoot_stage_ = ShootStage::PRELOADED;
bullet_fed_count_ = std::numeric_limits::min();
- bullet_feeder_control_angle_ = nan_;
+ bullet_feeder_control_angle_ = nan_;
bullet_feeder_angle_pid_.output_max = inf_;
bullet_feeder_velocity_pid_.reset();
@@ -160,13 +160,13 @@ class BulletFeederController42mm
*bullet_feeder_control_torque_ = nan_;
bullet_feeder_faulty_count_ = 0;
- bullet_feeder_cool_down_ = 0;
+ bullet_feeder_cool_down_ = 0;
}
void set_preloading() {
RCLCPP_INFO(get_logger(), "PRELOADING");
bullet_fed_count_++;
- shoot_stage_ = ShootStage::PRELOADING;
+ shoot_stage_ = ShootStage::PRELOADING;
bullet_feeder_control_angle_ = bullet_feeder_compressed_zero_point_
+ (bullet_fed_count_ + 0.5) * bullet_feeder_angle_per_bullet_;
bullet_feeder_angle_pid_.output_max = 1.0;
@@ -179,7 +179,7 @@ class BulletFeederController42mm
void set_compressing() {
RCLCPP_INFO(get_logger(), "COMPRESSING");
- shoot_stage_ = ShootStage::COMPRESSING;
+ shoot_stage_ = ShootStage::COMPRESSING;
bullet_feeder_control_angle_ = bullet_feeder_compressed_zero_point_
+ (bullet_fed_count_ + 1) * bullet_feeder_angle_per_bullet_;
bullet_feeder_angle_pid_.output_max = 0.8;
@@ -192,7 +192,7 @@ class BulletFeederController42mm
void set_shooting() {
RCLCPP_INFO(get_logger(), "SHOOTING");
- shoot_stage_ = ShootStage::SHOOTING;
+ shoot_stage_ = ShootStage::SHOOTING;
bullet_feeder_control_angle_ = bullet_feeder_compressed_zero_point_
+ (bullet_fed_count_ + 1.2) * bullet_feeder_angle_per_bullet_;
bullet_feeder_angle_pid_.output_max = 1.0;
@@ -215,7 +215,7 @@ class BulletFeederController42mm
void enter_jam_protection() {
bullet_feeder_control_angle_ = nan_;
- bullet_feeder_cool_down_ = 1000;
+ bullet_feeder_cool_down_ = 1000;
bullet_feeder_angle_pid_.reset();
bullet_feeder_velocity_pid_.reset();
RCLCPP_INFO(get_logger(), "Jammed!");
@@ -225,9 +225,10 @@ class BulletFeederController42mm
static constexpr double inf_ = std::numeric_limits::infinity();
static constexpr double bullet_feeder_compressed_zero_point_ = 0.58;
- static constexpr double bullet_feeder_angle_per_bullet_ = 2 * std::numbers::pi / 6;
+ static constexpr double bullet_feeder_angle_per_bullet_ = 2 * std::numbers::pi / 6;
InputInterface friction_ready_;
+ InputInterface bullet_fired_;
InputInterface switch_right_;
InputInterface switch_left_;
@@ -235,9 +236,9 @@ class BulletFeederController42mm
InputInterface keyboard_;
rmcs_msgs::Switch last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
- rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
- rmcs_msgs::Mouse last_mouse_ = rmcs_msgs::Mouse::zero();
- rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
+ rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Mouse last_mouse_ = rmcs_msgs::Mouse::zero();
+ rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
bool overdrive_mode_ = false, low_latency_mode_ = false;
@@ -247,8 +248,8 @@ class BulletFeederController42mm
InputInterface control_bullet_allowance_limited_by_heat_;
enum class ShootStage { PRELOADING, PRELOADED, COMPRESSING, COMPRESSED, SHOOTING };
- ShootStage shoot_stage_ = ShootStage::PRELOADED;
- int bullet_fed_count_ = std::numeric_limits::min();
+ ShootStage shoot_stage_ = ShootStage::PRELOADED;
+ int bullet_fed_count_ = std::numeric_limits::min();
double bullet_feeder_control_angle_ = nan_;
pid::PidCalculator bullet_feeder_velocity_pid_;
@@ -256,7 +257,7 @@ class BulletFeederController42mm
OutputInterface bullet_feeder_control_torque_;
int bullet_feeder_faulty_count_ = 0;
- int bullet_feeder_cool_down_ = 0;
+ int bullet_feeder_cool_down_ = 0;
OutputInterface shoot_mode_;
};
diff --git a/rmcs_ws/src/rmcs_core/src/controller/shooting/friction_wheel_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/shooting/friction_wheel_controller.cpp
index a83dc5f4..e38437a4 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/shooting/friction_wheel_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/shooting/friction_wheel_controller.cpp
@@ -150,8 +150,8 @@ class FrictionWheelController
bool detect_friction_faulty() {
for (size_t i = 0; i < friction_count_; i++) {
- if (*friction_velocities_[i] < *friction_control_velocities_[i] * 0.5)
- return true;
+ if (abs(*friction_velocities_[i]) < abs(*friction_control_velocities_[i] * 0.5))
+ return false;
}
return false;
}
diff --git a/rmcs_ws/src/rmcs_core/src/controller/shooting/putter_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/shooting/putter_controller.cpp
new file mode 100644
index 00000000..fbf85761
--- /dev/null
+++ b/rmcs_ws/src/rmcs_core/src/controller/shooting/putter_controller.cpp
@@ -0,0 +1,380 @@
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "controller/pid/pid_calculator.hpp"
+
+namespace rmcs_core::controller::shooting {
+
+/**
+ * @class PutterController
+ * @brief 推弹机构控制器
+ *
+ * 发射机制说明:
+ * 由于光电门放置于弹舱口,经测试,双中先触发推杆向后复位,然后堵转检测复位完毕,
+ * 默认情况下会给一点点的力保证推杆不会滑下去,再然后上弹采用速度环,在光电门被触发时
+ * 记录角度并转为角度环,然后推杆检测发弹根据两部分来检测,一是摩擦轮,二是推杆的行程
+ * 整套方案以于暑假前完成压力测试
+ */
+class PutterController
+ : public rmcs_executor::Component
+ , public rclcpp::Node {
+public:
+ PutterController()
+ : Node(
+ get_component_name(),
+ rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true)) {
+
+ register_input("/remote/switch/right", switch_right_);
+ register_input("/remote/switch/left", switch_left_);
+ register_input("/remote/mouse", mouse_);
+ register_input("/remote/keyboard", keyboard_);
+
+ register_input("/gimbal/friction_ready", friction_ready_);
+
+ register_input("/gimbal/bullet_feeder/angle", bullet_feeder_angle_);
+ register_input("/gimbal/bullet_feeder/velocity", bullet_feeder_velocity_);
+
+ register_input(
+ "/gimbal/control_bullet_allowance/limited_by_heat",
+ control_bullet_allowance_limited_by_heat_);
+
+ register_input("/gimbal/photoelectric_sensor", photoelectric_sensor_status_);
+ register_input("/gimbal/bullet_fired", bullet_fired_);
+
+ register_input("/gimbal/putter/angle", putter_angle_);
+ register_input("/gimbal/putter/velocity", putter_velocity_);
+
+ last_preload_flag_ = false;
+
+ bullet_feeder_velocity_pid_.kp = 50.0;
+ bullet_feeder_velocity_pid_.ki = 10.0;
+ bullet_feeder_velocity_pid_.kd = 0.0;
+ bullet_feeder_velocity_pid_.integral_max = 60.0;
+ bullet_feeder_velocity_pid_.integral_min = 0.0;
+
+ bullet_feeder_angle_pid_.kp = 8.0;
+ bullet_feeder_angle_pid_.ki = 0.0;
+ bullet_feeder_angle_pid_.kd = 2.0;
+
+ putter_return_velocity_pid_.kp = 0.0015;
+ putter_return_velocity_pid_.ki = 0.00005;
+ putter_return_velocity_pid_.kd = 0.;
+ putter_return_velocity_pid_.integral_max = 0.;
+ putter_return_velocity_pid_.integral_min = -0.03;
+
+ putter_velocity_pid_.kp = 0.004;
+ putter_velocity_pid_.ki = 0.0001;
+ putter_velocity_pid_.kd = 0.001;
+ putter_velocity_pid_.integral_max = 0.03;
+ putter_velocity_pid_.integral_min = 0.;
+
+ putter_return_angle_pid.kp = 0.0001;
+ // putter_return_angle_pid.ki = 0.000001;
+ putter_return_angle_pid.kd = 0.;
+
+ register_output(
+ "/gimbal/bullet_feeder/control_torque", bullet_feeder_control_torque_, nan_);
+ register_output("/gimbal/putter/control_torque", putter_control_torque_, nan_);
+
+ register_output("/gimbal/shooter/mode", shoot_mode_, rmcs_msgs::ShootMode::SINGLE);
+ }
+
+ void update() override {
+ const auto switch_right = *switch_right_;
+ const auto switch_left = *switch_left_;
+ const auto mouse = *mouse_;
+ const auto keyboard = *keyboard_;
+
+ using namespace rmcs_msgs;
+
+ if ((switch_left == Switch::UNKNOWN || switch_right == Switch::UNKNOWN)
+ || (switch_left == Switch::DOWN && switch_right == Switch::DOWN)) {
+ reset_all_controls();
+ return;
+ }
+
+ // 推杆已初始化后的正常控制流程
+ if (putter_initialized) {
+ // 供弹轮卡弹保护冷却期间的处理
+ if (bullet_feeder_cool_down_ > 0) {
+ bullet_feeder_cool_down_--;
+
+ // 使用角度环反转到“后退一格”的位置以解除卡弹
+ double velocity_err =
+ bullet_feeder_angle_pid_.update(
+ bullet_feeder_control_angle_ - *bullet_feeder_angle_)
+ - *bullet_feeder_velocity_;
+ *bullet_feeder_control_torque_ = bullet_feeder_velocity_pid_.update(velocity_err);
+
+ if (!bullet_feeder_cool_down_) {
+ RCLCPP_INFO(get_logger(), "Jamming Solved, Retrying...");
+ set_preloading();
+ }
+ } else {
+ // 正常运行模式:摩擦轮就绪时才允许发射
+ if (*friction_ready_) {
+ // 发射触发检测
+ // RCLCPP_INFO(get_logger(), "%.2f", *bullet_feeder_angle_);
+ // RCLCPP_INFO(get_logger(), "%.2f", *bullet_feeder_velocity_);
+ if (switch_right != Switch::DOWN) {
+ if ((!last_mouse_.left && mouse.left)
+ || (last_switch_left_ == rmcs_msgs::Switch::MIDDLE
+ && switch_left == rmcs_msgs::Switch::DOWN)) {
+ if (
+ // *control_bullet_allowance_limited_by_heat_ > 0 &&
+ shoot_stage_ == ShootStage::PRELOADED)
+ set_shooting();
+ }
+ }
+
+ if (shoot_stage_ == ShootStage::PRELOADING) {
+ // 盲拨模式:始终执行角度环定位
+ if (std::isnan(bullet_feeder_control_angle_)) {
+ bullet_feeder_control_angle_ =
+ *bullet_feeder_angle_ + bullet_feeder_angle_per_bullet_;
+ last_preload_flag_ = true;
+ }
+
+ const auto angle_err = bullet_feeder_control_angle_ - *bullet_feeder_angle_;
+ if (angle_err < 0.1) {
+ set_preloaded();
+ }
+ double velocity_err =
+ bullet_feeder_angle_pid_.update(angle_err) - *bullet_feeder_velocity_;
+ *bullet_feeder_control_torque_ =
+ bullet_feeder_velocity_pid_.update(velocity_err);
+
+ update_jam_detection();
+ } else {
+ // 其他状态:角度环保持角度不变防止弹链退弹
+ double velocity_err =
+ bullet_feeder_angle_pid_.update(
+ bullet_feeder_control_angle_ - *bullet_feeder_angle_)
+ - *bullet_feeder_velocity_;
+ *bullet_feeder_control_torque_ =
+ bullet_feeder_velocity_pid_.update(velocity_err);
+ }
+
+ if (shoot_stage_ == ShootStage::SHOOTING) {
+ // 发射状态:检测子弹是否发出
+ if (*bullet_fired_
+ || *putter_angle_ - putter_startpoint >= putter_stroke_) {
+ shooted = true;
+ }
+
+ update_putter_jam_detection();
+
+ if (shooted) {
+ // 子弹已发出:推杆复位
+ const auto angle_err = putter_startpoint - *putter_angle_;
+ if (angle_err > -0.05) {
+ *putter_control_torque_ = 0.;
+ set_preloading();
+ shooted = false;
+ } else {
+ *putter_control_torque_ =
+ putter_return_velocity_pid_.update(-80. - *putter_velocity_);
+ }
+ } else {
+ // 子弹未发出:继续推进
+ *putter_control_torque_ =
+ putter_return_velocity_pid_.update(60. - *putter_velocity_);
+ }
+ }
+ } else {
+ // 摩擦轮未就绪:停止供弹轮
+ *bullet_feeder_control_torque_ = 0.;
+ }
+
+ // 非发射状态:推杆给少许力保持位置
+ if (shoot_stage_ != ShootStage::SHOOTING)
+ *putter_control_torque_ = -0.02;
+ }
+ } else {
+ // 推杆未初始化:执行复位操作
+ *putter_control_torque_ = putter_return_velocity_pid_.update(-80. - *putter_velocity_);
+ update_putter_jam_detection();
+ }
+
+ // 保存当前状态用于下次比较
+ last_switch_right_ = switch_right;
+ last_switch_left_ = switch_left;
+ last_mouse_ = mouse;
+ last_keyboard_ = keyboard;
+ }
+
+private:
+ void reset_all_controls() {
+ last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
+ last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ last_mouse_ = rmcs_msgs::Mouse::zero();
+ last_keyboard_ = rmcs_msgs::Keyboard::zero();
+
+ overdrive_mode_ = false;
+
+ bullet_feeder_control_angle_ = nan_;
+ bullet_feeder_angle_pid_.output_max = inf_;
+ bullet_feeder_velocity_pid_.reset();
+ bullet_feeder_angle_pid_.reset();
+ *bullet_feeder_control_torque_ = nan_;
+
+ // shoot_stage_ = ShootStage::PRELOADING;
+
+ putter_initialized = false;
+ putter_startpoint = nan_;
+ putter_return_velocity_pid_.reset();
+ putter_velocity_pid_.reset();
+ putter_return_angle_pid.reset();
+ *putter_control_torque_ = nan_;
+
+ last_preload_flag_ = false;
+ last_photoelectric_sensor_status_ = false;
+
+ bullet_feeder_faulty_count_ = 0;
+ bullet_feeder_cool_down_ = 0;
+ }
+
+ void set_preloading() {
+ RCLCPP_INFO(get_logger(), "PRELOADING");
+ shoot_stage_ = ShootStage::PRELOADING;
+ // 盲拨方案:直接增加目标角度
+ if (!std::isnan(bullet_feeder_control_angle_)) {
+ bullet_feeder_control_angle_ += bullet_feeder_angle_per_bullet_;
+ }
+ last_preload_flag_ = true;
+ }
+
+ void set_preloaded() {
+ RCLCPP_INFO(get_logger(), "PRELOADED");
+ shoot_stage_ = ShootStage::PRELOADED;
+ last_preload_flag_ = false;
+ bullet_feeder_control_angle_ = *bullet_feeder_angle_ - 0.3;
+ }
+
+ void set_shooting() {
+ RCLCPP_INFO(get_logger(), "SHOOTING");
+ shoot_stage_ = ShootStage::SHOOTING;
+ }
+
+ void update_jam_detection() {
+ // RCLCPP_INFO(get_logger(), "%.2f --", *bullet_feeder_control_torque_);
+ if (*bullet_feeder_control_torque_ < 300.0 || std::isnan(*bullet_feeder_control_torque_)) {
+ bullet_feeder_faulty_count_ = 0;
+ return;
+ }
+
+ // 扭矩持续过大时累计故障计数
+ if (bullet_feeder_faulty_count_ < 1000)
+ bullet_feeder_faulty_count_++;
+ else {
+ bullet_feeder_faulty_count_ = 0;
+ RCLCPP_WARN(get_logger(), "Jam Detected! Reversing 60 degrees...");
+ enter_jam_protection();
+ }
+ }
+
+ void update_putter_jam_detection() {
+ if ((*putter_control_torque_ > -0.03 && shoot_stage_ == ShootStage::PRELOADING)
+ || (*putter_control_torque_ < 0.05 && shoot_stage_ == ShootStage::SHOOTING)
+ || std::isnan(*putter_control_torque_)) {
+ putter_faulty_count_ = 0;
+ return;
+ }
+
+ // 扭矩异常时累计故障计数
+ if (putter_faulty_count_ < 500)
+ ++putter_faulty_count_;
+ else {
+ putter_faulty_count_ = 0;
+ if (shoot_stage_ != ShootStage::SHOOTING) {
+ // 非发射状态下检测到堵转:推杆已到位,设置为已初始化
+ putter_initialized = true;
+ putter_startpoint = *putter_angle_;
+ } else {
+ // 发射状态下检测到堵转:认为子弹已发出
+ shooted = true;
+ }
+ }
+ }
+
+ void enter_jam_protection() {
+ // 设置目标角度为当前角度后退 60 度(一格)
+ bullet_feeder_control_angle_ = *bullet_feeder_angle_ - bullet_feeder_angle_per_bullet_;
+ bullet_feeder_cool_down_ = 1000;
+ bullet_feeder_angle_pid_.reset();
+ bullet_feeder_velocity_pid_.reset();
+ RCLCPP_INFO(get_logger(), "Jammed!");
+ }
+
+ static constexpr double nan_ = std::numeric_limits::quiet_NaN(); ///< 非数值常量
+ static constexpr double inf_ = std::numeric_limits::infinity(); ///< 无穷大常量
+
+ static constexpr double low_latency_velocity_ = 5.0; ///<
+ // 低延迟预装弹速度
+
+ static constexpr double putter_stroke_ = 11.5; ///< 推杆行程长度
+
+ static constexpr double max_bullet_feeder_control_torque_ = 0.1;
+ static constexpr double bullet_feeder_angle_per_bullet_ = 2 * std::numbers::pi / 6;
+
+ InputInterface photoelectric_sensor_status_;
+ bool last_photoelectric_sensor_status_;
+ InputInterface bullet_fired_;
+ bool shooted{false};
+
+ InputInterface friction_ready_;
+
+ InputInterface switch_right_;
+ InputInterface switch_left_;
+ InputInterface mouse_;
+ InputInterface keyboard_;
+
+ rmcs_msgs::Switch last_switch_right_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Switch last_switch_left_ = rmcs_msgs::Switch::UNKNOWN;
+ rmcs_msgs::Mouse last_mouse_ = rmcs_msgs::Mouse::zero();
+ rmcs_msgs::Keyboard last_keyboard_ = rmcs_msgs::Keyboard::zero();
+
+ bool overdrive_mode_ = false;
+
+ InputInterface bullet_feeder_angle_;
+ InputInterface bullet_feeder_velocity_;
+
+ InputInterface control_bullet_allowance_limited_by_heat_;
+
+ bool last_preload_flag_ = false;
+
+ bool putter_initialized = false;
+ int putter_faulty_count_ = 0;
+ double putter_startpoint = nan_;
+ pid::PidCalculator putter_return_velocity_pid_;
+ InputInterface putter_velocity_;
+
+ pid::PidCalculator putter_velocity_pid_;
+
+ enum class ShootStage { PRELOADING, PRELOADED, SHOOTING };
+ ShootStage shoot_stage_ = ShootStage::PRELOADING;
+ double bullet_feeder_control_angle_ = nan_;
+
+ pid::PidCalculator bullet_feeder_velocity_pid_;
+ pid::PidCalculator bullet_feeder_angle_pid_;
+ OutputInterface bullet_feeder_control_torque_;
+
+ InputInterface putter_angle_;
+ pid::PidCalculator putter_return_angle_pid;
+ OutputInterface putter_control_torque_;
+
+ int bullet_feeder_faulty_count_ = 0;
+ int bullet_feeder_cool_down_ = 0;
+
+ OutputInterface shoot_mode_;
+};
+
+} // namespace rmcs_core::controller::shooting
+
+#include
+
+PLUGINLIB_EXPORT_CLASS(rmcs_core::controller::shooting::PutterController, rmcs_executor::Component)
\ No newline at end of file
diff --git a/rmcs_ws/src/rmcs_core/src/controller/shooting/shooting_recorder.cpp b/rmcs_ws/src/rmcs_core/src/controller/shooting/shooting_recorder.cpp
index 5500b15c..4394bb8b 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/shooting/shooting_recorder.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/shooting/shooting_recorder.cpp
@@ -1,7 +1,10 @@
+#include
+#include
#include
#include
#include
#include
+#include
namespace rmcs_core::controller::shooting {
@@ -18,44 +21,71 @@ class ShootingRecorder
log_mode_ = static_cast(get_parameter("log_mode").as_int());
+ aim_velocity = get_parameter("aim_velocity").as_double();
+
register_input("/referee/shooter/initial_speed", initial_speed_);
register_input("/referee/shooter/shoot_timestamp", shoot_timestamp_);
- register_input("/friction_wheels/temperature", fractional_temperature_);
if (friction_wheel_count_ == 2) {
- const auto topic = std::array{
- "/gimbal/left_friction/control_velocity",
- "/gimbal/right_friction/control_velocity",
- };
- for (int i = 0; i < 2; i++)
- register_input(topic[i], friction_wheels_velocity_[i]);
- } else if (friction_wheel_count_ == 4) {
const auto topic = std::array{
"/gimbal/first_left_friction/control_velocity",
"/gimbal/first_right_friction/control_velocity",
- "/gimbal/second_left_friction/control_velocity",
- "/gimbal/second_right_friction/control_velocity",
};
- for (int i = 0; i < 4; i++)
+ for (int i = 0; i < 2; i++)
register_input(topic[i], friction_wheels_velocity_[i]);
+ register_input("/gimbal/first_left_friction/velocity", friction_velocities_[0]);
+ register_input("/gimbal/first_right_friction/velocity", friction_velocities_[1]);
}
using namespace std::chrono;
auto now = high_resolution_clock::now();
- auto ms = duration_cast(now.time_since_epoch()).count();
+ auto ms = duration_cast(now.time_since_epoch()).count();
auto file = fmt::format("/robot_shoot/{}.log", ms);
log_stream_.open(file);
+
+ std::ofstream outFile("shoot_recorder");
+ RCLCPP_INFO(get_logger(), "ShootingRecorder initialized, log file: %s", file.c_str());
}
~ShootingRecorder() { log_stream_.close(); }
void update() override {
+ // if (*friction_velocities_[0] <= 366.0 && *friction_velocities_[1] <= 366.0)
+ // return;
+ // if (start_time_ == 0.0) {
+ // start_time_ = GetTime();
+ // }
+
+ // int flag = 0;
+ // if (GetTime() - start_time_ > 10.0) {
+ // if (flag == 0) {
+ // RCLCPP_INFO(get_logger(), "vv = %f", vv);
+ // flag = 1;
+ // }
+ // return;
+ // }
+
+ // vv = std::max(vv, abs(*friction_velocities_[0] + *friction_velocities_[1]));
+
+ // auto log_text = std::string{};
+ // log_text = fmt::format(
+ // "{:.3f}, {:.3f}, {:.3f}", *friction_velocities_[0], *friction_velocities_[1],
+ // (*friction_velocities_[0] + *friction_velocities_[1]));
+
+ // log_stream_ << log_text << std::endl;
+ // RCLCPP_INFO(get_logger(), "%s", log_text.c_str());
+
+ // std::ofstream outFile("shoot_recorder", std::ios::app);
+ // if (outFile.is_open()) {
+ // outFile << log_text << std::endl;
+ // outFile.close();
+ // }
switch (log_mode_) {
case LogMode::TRIGGER:
// It will be triggered by shooting action
- if (*shoot_timestamp_ == last_shoot_timestamp_)
+ if (*shoot_timestamp_ == last_shoot_timestamp_ || v == *shoot_timestamp_)
return;
break;
case LogMode::TIMING:
@@ -64,38 +94,50 @@ class ShootingRecorder
return;
break;
}
+ v = *shoot_timestamp_;
+
+ static constexpr size_t max_velocities_size = 1000;
+
+ velocities.push_back(*initial_speed_);
+ if (velocities.size() > max_velocities_size) {
+ velocities.erase(velocities.begin());
+ }
- auto log_text = std::string{};
+ analysis3();
+
+ auto log_text = std::string{};
auto timestamp = timestamp_to_string(*shoot_timestamp_);
if (friction_wheel_count_ == 2) {
log_text = fmt::format(
- "{},{},{},{},{}", timestamp, *initial_speed_, //
- *friction_wheels_velocity_[0], *friction_wheels_velocity_[1],
- *fractional_temperature_);
- } else if (friction_wheel_count_ == 4) {
- log_text = fmt::format(
- "{},{},{},{},{},{},{}", timestamp, *initial_speed_, //
- *friction_wheels_velocity_[0], *friction_wheels_velocity_[1],
- *friction_wheels_velocity_[2], *friction_wheels_velocity_[3],
- *fractional_temperature_);
+ "{},{},{:.3f},{:.3f},{:.3f},{:.3f},{:.3f},{:.3f},{:.3f}", *initial_speed_,
+ (int)velocities.size(), //
+ velocity_, excellence_rate_, pass_rate_, range_, range2_, velocity_max,
+ velocity_min);
}
log_stream_ << log_text << std::endl;
RCLCPP_INFO(get_logger(), "%s", log_text.c_str());
+ log_velocity = fmt::format("{:.3f}", *initial_speed_);
+ std::ofstream outFile("shoot_recorder", std::ios::app);
+ if (outFile.is_open()) {
+ outFile << log_velocity << std::endl;
+ outFile.close();
+ }
+
last_shoot_timestamp_ = *shoot_timestamp_;
}
private:
/// @brief Component interface
+ std::array, 2> friction_velocities_;
+
InputInterface initial_speed_;
InputInterface shoot_timestamp_;
- InputInterface fractional_temperature_;
-
std::size_t friction_wheel_count_ = 2;
- std::array, 4> friction_wheels_velocity_;
+ std::array, 2> friction_wheels_velocity_;
/// @brief For log
enum class LogMode { TRIGGER = 1, TIMING = 2 };
@@ -103,25 +145,149 @@ class ShootingRecorder
double last_shoot_timestamp_ = 0;
std::ofstream log_stream_;
+ std::string log_velocity;
std::size_t log_count_ = 0;
+ std::vector velocities;
+
+ double velocity_;
+
+ double excellence_rate_;
+ double pass_rate_;
+
+ double range_;
+ double range2_;
+
+ double velocity_min;
+ double velocity_max;
+
+ double v;
+ double aim_velocity;
+
private:
static std::string timestamp_to_string(double timestamp) {
- auto time = static_cast(timestamp);
+ auto time = static_cast(timestamp);
auto local_time = std::localtime(&time);
char buffer[100];
std::strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", local_time);
double fractional_seconds = timestamp - std::floor(timestamp);
- int milliseconds = static_cast(fractional_seconds * 1000);
+ int milliseconds = static_cast(fractional_seconds * 1000);
char result[150];
std::snprintf(result, sizeof(result), "%s.%03d", buffer, milliseconds);
return result;
}
+ void analysis1() {
+ double sum = 0.0;
+ for (const auto& v : velocities) {
+ sum += v;
+ }
+ velocity_ = sum / double(velocities.size());
+
+ sort(velocities.begin(), velocities.end());
+
+ range_ = velocities.back() - velocities.front();
+
+ if (velocities.size() >= 3) {
+ range2_ = velocities[int(velocities.size() - 2)] - velocities[1];
+ } else {
+ range2_ = range_;
+ }
+
+ velocity_max = velocities.back();
+ velocity_min = velocities.front();
+
+ int excellence_count = 0;
+ int pass_count = 0;
+ for (int i = 0; i < int(velocities.size()); i++) {
+ if (velocities[i] >= velocity_ - 0.1 && velocities[i] <= velocity_ + 0.1) {
+ pass_count += 1;
+ }
+ if (velocities[i] >= velocity_ - 0.05 && velocities[i] <= velocity_ + 0.05) {
+ excellence_count += 1;
+ }
+ }
+ excellence_rate_ = double(excellence_count) / double(velocities.size());
+ pass_rate_ = double(pass_count) / double(velocities.size());
+ }
+
+ void analysis2() {
+ double sum = 0.0;
+ for (const auto& v : velocities) {
+ sum += v;
+ }
+
+ sort(velocities.begin(), velocities.end());
+
+ velocity_max = velocities.back();
+ velocity_min = velocities.front();
+
+ int n_adjust = std::max(1, int((int)velocities.size() * 0.05));
+
+ for (int i = 0; i < n_adjust; i++) {
+ sum -= velocities[i];
+ sum -= velocities[velocities.size() - 1 - i];
+ }
+
+ velocity_ = sum / double(velocities.size() - 2 * n_adjust);
+
+ range_ = velocities.back() - velocities.front();
+ range2_ = velocities[int(velocities.size() - 2)] - velocities[1];
+
+ int excellence_count = 0;
+ int pass_count = 0;
+ for (int i = 0; i < int(velocities.size()); i++) {
+ if (velocities[i] >= velocity_ - 0.1 && velocities[i] <= velocity_ + 0.1) {
+ pass_count += 1;
+ }
+ if (velocities[i] >= velocity_ - 0.05 && velocities[i] <= velocity_ + 0.05) {
+ excellence_count += 1;
+ }
+ }
+ excellence_rate_ = double(excellence_count) / double(velocities.size());
+ pass_rate_ = double(pass_count) / double(velocities.size());
+ }
+
+ void analysis3() {
+ double sum = 0.0;
+ for (const auto& v : velocities) {
+ sum += v;
+ }
+ velocity_ = sum / double(velocities.size());
+
+ int excellence_count = 0;
+ int pass_count = 0;
+
+ for (const auto& v : velocities) {
+ if (v >= aim_velocity - 0.05 && v <= aim_velocity + 0.05) {
+ excellence_count += 1;
+ }
+ if (v >= aim_velocity - 0.1 && v <= aim_velocity + 0.1) {
+ pass_count += 1;
+ }
+ }
+ excellence_rate_ = double(excellence_count) / double(velocities.size());
+ pass_rate_ = double(pass_count) / double(velocities.size());
+
+ sort(velocities.begin(), velocities.end());
+ velocity_max = velocities.back();
+ velocity_min = velocities.front();
+
+ range_ = velocities.back() - velocities.front();
+ range2_ = velocities[int(velocities.size() - 2)] - velocities[1];
+ }
+
+ static double GetTime() {
+ using namespace std::chrono;
+ static auto start = high_resolution_clock::now();
+ auto now = high_resolution_clock::now();
+ duration elapsed = now - start;
+ return elapsed.count();
+ }
};
} // namespace rmcs_core::controller::shooting
diff --git a/rmcs_ws/src/rmcs_core/src/hardware/steering-hero.cpp b/rmcs_ws/src/rmcs_core/src/hardware/steering-hero.cpp
index d30c1ce0..847698c2 100644
--- a/rmcs_ws/src/rmcs_core/src/hardware/steering-hero.cpp
+++ b/rmcs_ws/src/rmcs_core/src/hardware/steering-hero.cpp
@@ -4,11 +4,11 @@
#include
#include
#include
-#include
#include
#include
#include
+#include
#include
#include
#include
@@ -18,10 +18,8 @@
#include
#include
#include
-#include
#include
-#include "hardware/device/benewake.hpp"
#include "hardware/device/bmi088.hpp"
#include "hardware/device/can_packet.hpp"
#include "hardware/device/dji_motor.hpp"
@@ -36,16 +34,14 @@ class SteeringHero
, public rclcpp::Node {
public:
SteeringHero()
- : Node{
+ : Node(
get_component_name(),
- rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true)}
+ rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true))
, command_component_(
create_partner_component(
get_component_name() + "_command", *this)) {
register_output("/tf", tf_);
- tf_->set_transform(
- Eigen::Translation3d{0.16, 0.0, 0.15});
gimbal_calibrate_subscription_ = create_subscription(
"/gimbal/calibrate", rclcpp::QoS{0}, [this](std_msgs::msg::Int32::UniquePtr&& msg) {
@@ -54,10 +50,15 @@ class SteeringHero
top_board_ = std::make_unique(
*this, *command_component_, get_parameter("board_serial_top_board").as_string());
- bottom_board_ = std::make_unique(
- *this, *command_component_, get_parameter("board_serial_bottom_board").as_string());
- temperature_logging_timer_.reset(1000);
+ bottom_board_one_ = std::make_unique(
+ *this, *command_component_, get_parameter("board_serial_bottom_board_one").as_string());
+
+ bottom_board_two_ = std::make_unique(
+ *this, *command_component_, get_parameter("board_serial_bottom_board_two").as_string());
+
+ tf_->set_transform(
+ Eigen::Translation3d{0.06603, 0.0, 0.082});
}
SteeringHero(const SteeringHero&) = delete;
@@ -69,51 +70,39 @@ class SteeringHero
void update() override {
top_board_->update();
- bottom_board_->update();
-
- if (temperature_logging_timer_.tick()) {
- temperature_logging_timer_.reset(1000);
- RCLCPP_INFO(
- get_logger(),
- "Temperature: pitch: %.1f, top_yaw: %.1f, bottom_yaw: %.1f, feeder: %.1f",
- top_board_->gimbal_pitch_motor_.temperature(),
- top_board_->gimbal_top_yaw_motor_.temperature(),
- bottom_board_->gimbal_bottom_yaw_motor_.temperature(),
- top_board_->gimbal_bullet_feeder_.temperature());
- }
+ bottom_board_one_->update();
+ bottom_board_two_->update();
}
void command_update() {
top_board_->command_update();
- bottom_board_->command_update();
+ bottom_board_one_->command_update();
+ bottom_board_two_->command_update();
}
private:
void gimbal_calibrate_subscription_callback(std_msgs::msg::Int32::UniquePtr) {
RCLCPP_INFO(
get_logger(), "[gimbal calibration] New bottom yaw offset: %ld",
- bottom_board_->gimbal_bottom_yaw_motor_.calibrate_zero_point());
+ bottom_board_two_->gimbal_bottom_yaw_motor_.calibrate_zero_point());
RCLCPP_INFO(
get_logger(), "[gimbal calibration] New pitch offset: %ld",
top_board_->gimbal_pitch_motor_.calibrate_zero_point());
RCLCPP_INFO(
get_logger(), "[gimbal calibration] New top yaw offset: %ld",
top_board_->gimbal_top_yaw_motor_.calibrate_zero_point());
- RCLCPP_INFO(
- get_logger(), "[gimbal calibration] New viewer offset: %ld",
- top_board_->gimbal_player_viewer_motor_.calibrate_zero_point());
RCLCPP_INFO(
get_logger(), "[chassis calibration] left front steering offset: %d",
- bottom_board_->chassis_steering_motors_[0].calibrate_zero_point());
+ bottom_board_one_->chassis_steering_motors_[0].calibrate_zero_point());
+ RCLCPP_INFO(
+ get_logger(), "[chassis calibration] right front steering offset: %d",
+ bottom_board_one_->chassis_steering_motors_[1].calibrate_zero_point());
RCLCPP_INFO(
get_logger(), "[chassis calibration] left back steering offset: %d",
- bottom_board_->chassis_steering_motors_[1].calibrate_zero_point());
+ bottom_board_two_->chassis_steering_motors2_[0].calibrate_zero_point());
RCLCPP_INFO(
get_logger(), "[chassis calibration] right back steering offset: %d",
- bottom_board_->chassis_steering_motors_[2].calibrate_zero_point());
- RCLCPP_INFO(
- get_logger(), "[chassis calibration] right front steering offset: %d",
- bottom_board_->chassis_steering_motors_[3].calibrate_zero_point());
+ bottom_board_two_->chassis_steering_motors2_[1].calibrate_zero_point());
}
class SteeringHeroCommand : public rmcs_executor::Component {
@@ -123,7 +112,6 @@ class SteeringHero
void update() override { hero_.command_update(); }
- private:
SteeringHero& hero_;
};
std::shared_ptr command_component_;
@@ -132,68 +120,72 @@ class SteeringHero
public:
friend class SteeringHero;
explicit TopBoard(
- SteeringHero& hero, SteeringHeroCommand& hero_command,
+ SteeringHero& steering_hero, SteeringHeroCommand& steering_hero_command,
std::string_view board_serial = {})
: librmcs::agent::CBoard(board_serial)
- , tf_(hero.tf_)
+ , logger_(steering_hero.get_logger())
+ , tf_(steering_hero.tf_)
, imu_(1000, 0.2, 0.0)
- , benewake_(hero, "/gimbal/auto_aim/laser_distance")
- , gimbal_top_yaw_motor_(
- hero, hero_command, "/gimbal/top_yaw",
- device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}
- .set_encoder_zero_point(
- static_cast(
- hero.get_parameter("top_yaw_motor_zero_point").as_int())))
- , gimbal_pitch_motor_(
- hero, hero_command, "/gimbal/pitch",
- device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("pitch_motor_zero_point").as_int())))
+ , gimbal_top_yaw_motor_(steering_hero, steering_hero_command, "/gimbal/top_yaw")
+ , gimbal_pitch_motor_(steering_hero, steering_hero_command, "/gimbal/pitch")
, gimbal_friction_wheels_(
- {hero, hero_command, "/gimbal/second_left_friction",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}.set_reduction_ratio(
- 1.)},
- {hero, hero_command, "/gimbal/first_left_friction",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}.set_reduction_ratio(
- 1.)},
- {hero, hero_command, "/gimbal/first_right_friction",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reduction_ratio(1.)
- .set_reversed()},
- {hero, hero_command, "/gimbal/second_right_friction",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reduction_ratio(1.)
- .set_reversed()})
- , gimbal_bullet_feeder_(
- hero, hero_command, "/gimbal/bullet_feeder",
- device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}
- .set_reversed()
- .enable_multi_turn_angle())
- , gimbal_scope_motor_(
- hero, hero_command, "/gimbal/scope",
- device::DjiMotor::Config{device::DjiMotor::Type::kM2006})
- , gimbal_player_viewer_motor_(
- hero, hero_command, "/gimbal/player_viewer",
- device::LkMotor::Config{device::LkMotor::Type::kMG4005Ei10}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("viewer_motor_zero_point").as_int()))
- .set_reversed()) {
+ {steering_hero, steering_hero_command, "/gimbal/first_left_friction"},
+ {steering_hero, steering_hero_command, "/gimbal/first_right_friction"},
+ {steering_hero, steering_hero_command, "/gimbal/second_left_friction"},
+ {steering_hero, steering_hero_command, "/gimbal/second_right_friction"})
+ , gimbal_bullet_feeder_(steering_hero, steering_hero_command, "/gimbal/bullet_feeder")
+ , putter_motor_(steering_hero, steering_hero_command, "/gimbal/putter") {
+
+ gimbal_top_yaw_motor_.configure(
+ device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}.set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("top_yaw_motor_zero_point").as_int())));
+ gimbal_pitch_motor_.configure(
+ device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}.set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("pitch_motor_zero_point").as_int())));
+ gimbal_friction_wheels_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}.set_reduction_ratio(1.));
+ gimbal_friction_wheels_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(1.));
+ gimbal_friction_wheels_[2].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}.set_reduction_ratio(1.));
+ gimbal_friction_wheels_[3].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(1.));
+ gimbal_bullet_feeder_.configure(
+ device::LkMotor::Config{device::LkMotor::Type::kMG5010Ei10}
+ .set_reversed()
+ .enable_multi_turn_angle());
+ putter_motor_.configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reduction_ratio(1.)
+ .enable_multi_turn_angle());
+
+ steering_hero.register_output("/gimbal/yaw/velocity_imu", gimbal_yaw_velocity_imu_);
+ steering_hero.register_output("/gimbal/pitch/velocity_imu", gimbal_pitch_velocity_imu_);
+
+ steering_hero.register_output(
+ "/gimbal/photoelectric_sensor", photoelectric_sensor_status_, false);
+ steering_hero.register_output(
+ "/auto_aim/image_capturer/timestamp", camera_capturer_trigger_timestamp_, 0);
+ steering_hero.register_output(
+ "/auto_aim/image_capturer/trigger", camera_capturer_trigger_, 0);
imu_.set_coordinate_mapping([](double x, double y, double z) {
// Get the mapping with the following code.
- // The rotation angle must be an exact multiple of 90 degrees, otherwise use a
- // matrix.
+ // The rotation angle must be an exact multiple of 90 degrees, otherwise
+ // use a matrix.
- // Eigen::AngleAxisd pitch_link_to_imu_link{
- // std::numbers::pi, Eigen::Vector3d::UnitZ()};
- // Eigen::Vector3d mapping = pitch_link_to_imu_link * Eigen::Vector3d{1, 2, 3};
+ // Eigen::AngleAxisd pitch_link_to_bmi088_link{
+ // std::numbers::pi / 2, Eigen::Vector3d::UnitZ()};
+ // Eigen::Vector3d mapping = pitch_link_to_bmi088_link * Eigen::Vector3d{1, 2, 3};
// std::cout << mapping << std::endl;
-
return std::make_tuple(-x, -y, z);
});
-
- hero.register_output("/gimbal/yaw/velocity_imu", gimbal_yaw_velocity_imu_);
- hero.register_output("/gimbal/pitch/velocity_imu", gimbal_pitch_velocity_imu_);
}
TopBoard(const TopBoard&) = delete;
@@ -202,16 +194,13 @@ class SteeringHero
TopBoard& operator=(TopBoard&&) = delete;
~TopBoard() final = default;
-
void update() {
imu_.update_status();
- const Eigen::Quaterniond gimbal_imu_pose{imu_.q0(), imu_.q1(), imu_.q2(), imu_.q3()};
+ Eigen::Quaterniond gimbal_imu_pose{imu_.q0(), imu_.q1(), imu_.q2(), imu_.q3()};
tf_->set_transform(
gimbal_imu_pose.conjugate());
- benewake_.update_status();
-
*gimbal_yaw_velocity_imu_ = imu_.gz();
*gimbal_pitch_velocity_imu_ = imu_.gy();
@@ -221,16 +210,15 @@ class SteeringHero
tf_->set_state(
gimbal_pitch_motor_.angle());
- gimbal_player_viewer_motor_.update_status();
- tf_->set_state(
- gimbal_player_viewer_motor_.angle());
-
- gimbal_scope_motor_.update_status();
-
for (auto& motor : gimbal_friction_wheels_)
motor.update_status();
gimbal_bullet_feeder_.update_status();
+ putter_motor_.update_status();
+
+ if (last_camera_capturer_trigger_timestamp_ != *camera_capturer_trigger_timestamp_)
+ *camera_capturer_trigger_ = true;
+ last_camera_capturer_trigger_timestamp_ = *camera_capturer_trigger_timestamp_;
}
void command_update() {
@@ -240,26 +228,19 @@ class SteeringHero
.can_id = 0x200,
.can_data =
device::CanPacket8{
- gimbal_friction_wheels_[0].generate_command(),
+ gimbal_friction_wheels_[3].generate_command(),
gimbal_friction_wheels_[1].generate_command(),
gimbal_friction_wheels_[2].generate_command(),
- gimbal_friction_wheels_[3].generate_command(),
+ gimbal_friction_wheels_[0].generate_command(),
}
.as_bytes(),
});
builder.can1_transmit({
- .can_id = 0x141,
- .can_data = gimbal_bullet_feeder_
- .generate_torque_command(gimbal_bullet_feeder_.control_torque())
- .as_bytes(),
- });
-
- builder.can2_transmit({
- .can_id = 0x200,
+ .can_id = 0x1FF,
.can_data =
device::CanPacket8{
- gimbal_scope_motor_.generate_command(),
+ putter_motor_.generate_command(),
device::CanPacket8::PaddingQuarter{},
device::CanPacket8::PaddingQuarter{},
device::CanPacket8::PaddingQuarter{},
@@ -267,12 +248,9 @@ class SteeringHero
.as_bytes(),
});
- builder.can2_transmit({
- .can_id = 0x143,
- .can_data =
- gimbal_player_viewer_motor_
- .generate_velocity_command(gimbal_player_viewer_motor_.control_velocity())
- .as_bytes(),
+ builder.can1_transmit({
+ .can_id = 0x141,
+ .can_data = gimbal_bullet_feeder_.generate_torque_command().as_bytes(),
});
builder.can2_transmit({
@@ -290,16 +268,17 @@ class SteeringHero
void can1_receive_callback(const librmcs::data::CanDataView& data) override {
if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
return;
-
auto can_id = data.can_id;
- if (can_id == 0x201) {
+ if (can_id == 0x204) {
gimbal_friction_wheels_[0].store_status(data.can_data);
} else if (can_id == 0x202) {
gimbal_friction_wheels_[1].store_status(data.can_data);
} else if (can_id == 0x203) {
gimbal_friction_wheels_[2].store_status(data.can_data);
- } else if (can_id == 0x204) {
+ } else if (can_id == 0x201) {
gimbal_friction_wheels_[3].store_status(data.can_data);
+ } else if (can_id == 0x205) {
+ putter_motor_.store_status(data.can_data);
} else if (can_id == 0x141) {
gimbal_bullet_feeder_.store_status(data.can_data);
}
@@ -308,23 +287,15 @@ class SteeringHero
void can2_receive_callback(const librmcs::data::CanDataView& data) override {
if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
return;
-
auto can_id = data.can_id;
+
if (can_id == 0x141) {
gimbal_top_yaw_motor_.store_status(data.can_data);
} else if (can_id == 0x142) {
gimbal_pitch_motor_.store_status(data.can_data);
- } else if (can_id == 0x143) {
- gimbal_player_viewer_motor_.store_status(data.can_data);
- } else if (can_id == 0x201) {
- gimbal_scope_motor_.store_status(data.can_data);
}
}
- void uart2_receive_callback(const librmcs::data::UartDataView& data) override {
- benewake_.store_status(data.uart_data.data(), data.uart_data.size());
- }
-
void accelerometer_receive_callback(
const librmcs::data::AccelerometerDataView& data) override {
imu_.store_accelerometer_status(data.x, data.y, data.z);
@@ -334,82 +305,257 @@ class SteeringHero
imu_.store_gyroscope_status(data.x, data.y, data.z);
}
- OutputInterface& tf_;
+ void putter_receive_callback(bool status) { *photoelectric_sensor_status_ = status; }
- device::Bmi088 imu_;
- device::Benewake benewake_;
+ rclcpp::Logger logger_;
+ OutputInterface& tf_;
- OutputInterface gimbal_yaw_velocity_imu_;
- OutputInterface gimbal_pitch_velocity_imu_;
+ std::time_t last_camera_capturer_trigger_timestamp_{0};
+ device::Bmi088 imu_;
device::LkMotor gimbal_top_yaw_motor_;
device::LkMotor gimbal_pitch_motor_;
-
device::DjiMotor gimbal_friction_wheels_[4];
device::LkMotor gimbal_bullet_feeder_;
+ device::DjiMotor putter_motor_;
- device::DjiMotor gimbal_scope_motor_;
- device::LkMotor gimbal_player_viewer_motor_;
+ OutputInterface gimbal_yaw_velocity_imu_;
+ OutputInterface gimbal_pitch_velocity_imu_;
+ OutputInterface photoelectric_sensor_status_;
+ OutputInterface camera_capturer_trigger_;
+ OutputInterface camera_capturer_trigger_timestamp_;
};
- class BottomBoard final : private librmcs::agent::CBoard {
+ class BottomBoard_one final : private librmcs::agent::CBoard {
public:
friend class SteeringHero;
- explicit BottomBoard(
- SteeringHero& hero, SteeringHeroCommand& hero_command,
+ explicit BottomBoard_one(
+ SteeringHero& steering_hero, SteeringHeroCommand& steering_hero_command,
std::string_view board_serial = {})
: librmcs::agent::CBoard(board_serial)
+ , logger_(steering_hero.get_logger())
, imu_(1000, 0.2, 0.0)
- , tf_(hero.tf_)
- , dr16_(hero)
+ , chassis_front_climber_motor_(
+ {steering_hero, steering_hero_command, "/chassis/climber/left_front_motor"},
+ {steering_hero, steering_hero_command, "/chassis/climber/right_front_motor"})
+ , chassis_back_climber_motor_(
+ {steering_hero, steering_hero_command, "/chassis/climber/left_back_motor"},
+ {steering_hero, steering_hero_command, "/chassis/climber/right_back_motor"})
, chassis_steering_motors_(
- {hero, hero_command, "/chassis/left_front_steering",
- device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("left_front_zero_point").as_int()))
- .set_reversed()},
- {hero, hero_command, "/chassis/left_back_steering",
- device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("left_back_zero_point").as_int()))
- .set_reversed()},
- {hero, hero_command, "/chassis/right_back_steering",
- device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("right_back_zero_point").as_int()))
- .set_reversed()},
- {hero, hero_command, "/chassis/right_front_steering",
- device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
- .set_encoder_zero_point(
- static_cast(hero.get_parameter("right_front_zero_point").as_int()))
- .set_reversed()})
+ {steering_hero, steering_hero_command, "/chassis/left_front_steering"},
+ {steering_hero, steering_hero_command, "/chassis/right_front_steering"})
, chassis_wheel_motors_(
- {hero, hero_command, "/chassis/left_front_wheel",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reversed()
- .set_reduction_ratio(2232. / 169.)},
- {hero, hero_command, "/chassis/left_back_wheel",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reversed()
- .set_reduction_ratio(2232. / 169.)},
- {hero, hero_command, "/chassis/right_back_wheel",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reversed()
- .set_reduction_ratio(2232. / 169.)},
- {hero, hero_command, "/chassis/right_front_wheel",
- device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
- .set_reversed()
- .set_reduction_ratio(2232. / 169.)})
- , supercap_(hero, hero_command)
- , gimbal_bottom_yaw_motor_(
- hero, hero_command, "/gimbal/bottom_yaw",
- device::LkMotor::Config{device::LkMotor::Type::kMG6012Ei8}
- .set_reversed()
- .set_encoder_zero_point(
- static_cast(
- hero.get_parameter("bottom_yaw_motor_zero_point").as_int()))) {
-
- hero.register_output("/referee/serial", referee_serial_);
+ {steering_hero, steering_hero_command, "/chassis/left_front_wheel"},
+ {steering_hero, steering_hero_command, "/chassis/right_front_wheel"}) {
+ //
+
+ chassis_steering_motors_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
+ .set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("left_front_zero_point").as_int()))
+ .set_reversed());
+ chassis_steering_motors_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
+ .set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("right_front_zero_point").as_int()))
+ .set_reversed());
+ chassis_wheel_motors_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(2232. / 169.));
+ chassis_wheel_motors_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(2232. / 169.));
+
+ chassis_front_climber_motor_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(19.));
+ chassis_front_climber_motor_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}.set_reduction_ratio(19.));
+ chassis_back_climber_motor_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .enable_multi_turn_angle()
+ .set_reduction_ratio(19.));
+ chassis_back_climber_motor_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .enable_multi_turn_angle()
+ .set_reduction_ratio(19.));
+
+ steering_hero.register_output(
+ "/chassis/yaw/velocity_imu", chassis_yaw_velocity_imu_, 0);
+ steering_hero.register_output(
+ "/chassis/pitch_imu", chassis_pitch_imu_, 0.0);
+ }
+ BottomBoard_one(const BottomBoard_one&) = delete;
+ BottomBoard_one& operator=(const BottomBoard_one&) = delete;
+ BottomBoard_one(BottomBoard_one&&) = delete;
+ BottomBoard_one& operator=(BottomBoard_one&&) = delete;
+
+ ~BottomBoard_one() final = default;
+
+ void update() {
+ imu_.update_status();
+
+ *chassis_yaw_velocity_imu_ = imu_.gz();
+ *chassis_pitch_imu_ = -std::asin(2.0 * (imu_.q0() * imu_.q2() - imu_.q3() * imu_.q1()));
+
+ chassis_front_climber_motor_[0].update_status();
+ chassis_front_climber_motor_[1].update_status();
+ chassis_back_climber_motor_[0].update_status();
+ chassis_back_climber_motor_[1].update_status();
+
+ for (auto& motor : chassis_wheel_motors_)
+ motor.update_status();
+ for (auto& motor : chassis_steering_motors_)
+ motor.update_status();
+ }
+
+ void command_update() {
+ auto builder = start_transmit();
+
+ builder.can1_transmit({
+ .can_id = 0x200,
+ .can_data =
+ device::CanPacket8{
+ chassis_wheel_motors_[1].generate_command(),
+ chassis_wheel_motors_[0].generate_command(),
+ device::CanPacket8::PaddingQuarter{},
+ device::CanPacket8::PaddingQuarter{},
+ }
+ .as_bytes(),
+ });
+
+ builder.can1_transmit({
+ .can_id = 0x1FE,
+ .can_data =
+ device::CanPacket8{
+ device::CanPacket8::PaddingQuarter{},
+ chassis_steering_motors_[0].generate_command(),
+ device::CanPacket8::PaddingQuarter{},
+ chassis_steering_motors_[1].generate_command(),
+ }
+ .as_bytes(),
+ });
+
+ builder.can2_transmit({
+ .can_id = 0x200,
+ .can_data =
+ device::CanPacket8{
+ chassis_back_climber_motor_[0].generate_command(),
+ chassis_back_climber_motor_[1].generate_command(),
+ chassis_front_climber_motor_[0].generate_command(),
+ chassis_front_climber_motor_[1].generate_command(),
+ }
+ .as_bytes(),
+ });
+ }
+
+ private:
+ void can1_receive_callback(const librmcs::data::CanDataView& data) override {
+ if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
+ return;
+ auto can_id = data.can_id;
+ if (can_id == 0x201) {
+ chassis_wheel_motors_[1].store_status(data.can_data);
+ } else if (can_id == 0x202) {
+ chassis_wheel_motors_[0].store_status(data.can_data);
+ } else if (can_id == 0x206) {
+ chassis_steering_motors_[0].store_status(data.can_data);
+ } else if (can_id == 0x208) {
+ chassis_steering_motors_[1].store_status(data.can_data);
+ }
+ }
+
+ void can2_receive_callback(const librmcs::data::CanDataView& data) override {
+ if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
+ return;
+ auto can_id = data.can_id;
+
+ if (can_id == 0x203) {
+ chassis_front_climber_motor_[0].store_status(data.can_data);
+ } else if (can_id == 0x204) {
+ chassis_front_climber_motor_[1].store_status(data.can_data);
+ } else if (can_id == 0x201) {
+ chassis_back_climber_motor_[0].store_status(data.can_data);
+ } else if (can_id == 0x202) {
+ chassis_back_climber_motor_[1].store_status(data.can_data);
+ }
+ }
+
+ void accelerometer_receive_callback(
+ const librmcs::data::AccelerometerDataView& data) override {
+ imu_.store_accelerometer_status(data.x, data.y, data.z);
+ }
+
+ void gyroscope_receive_callback(const librmcs::data::GyroscopeDataView& data) override {
+ imu_.store_gyroscope_status(data.x, data.y, data.z);
+ }
+
+ rclcpp::Logger logger_;
+
+ device::Bmi088 imu_;
+ device::DjiMotor chassis_front_climber_motor_[2];
+ device::DjiMotor chassis_back_climber_motor_[2];
+ device::DjiMotor chassis_steering_motors_[2];
+ device::DjiMotor chassis_wheel_motors_[2];
+
+ OutputInterface chassis_yaw_velocity_imu_;
+ OutputInterface chassis_pitch_imu_;
+ OutputInterface gimbal_yaw_velocity_imu_;
+ OutputInterface gimbal_pitch_velocity_imu_;
+ };
+
+ class BottomBoard_two final : private librmcs::agent::CBoard {
+ public:
+ friend class SteeringHero;
+ explicit BottomBoard_two(
+ SteeringHero& steering_hero, SteeringHeroCommand& steering_hero_command,
+ std::string_view board_serial = {})
+ : librmcs::agent::CBoard(board_serial)
+ , logger_(steering_hero.get_logger())
+ , imu_(1000, 0.2, 0.0)
+ , tf_(steering_hero.tf_)
+ , dr16_(steering_hero)
+ , supercap_(steering_hero, steering_hero_command)
+ , chassis_steering_motors2_(
+ {steering_hero, steering_hero_command, "/chassis/left_back_steering"},
+ {steering_hero, steering_hero_command, "/chassis/right_back_steering"})
+ , chassis_wheel_motors2_(
+ {steering_hero, steering_hero_command, "/chassis/left_back_wheel"},
+ {steering_hero, steering_hero_command, "/chassis/right_back_wheel"})
+ , gimbal_bottom_yaw_motor_(steering_hero, steering_hero_command, "/gimbal/bottom_yaw") {
+ chassis_steering_motors2_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
+ .set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("left_back_zero_point").as_int()))
+ .set_reversed());
+ chassis_steering_motors2_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kGM6020}
+ .set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("right_back_zero_point").as_int()))
+ .set_reversed());
+ chassis_wheel_motors2_[0].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(2232. / 169.));
+ chassis_wheel_motors2_[1].configure(
+ device::DjiMotor::Config{device::DjiMotor::Type::kM3508}
+ .set_reversed()
+ .set_reduction_ratio(2232. / 169.));
+ gimbal_bottom_yaw_motor_.configure(
+ device::LkMotor::Config{device::LkMotor::Type::kMG6012Ei8}
+ .set_reversed()
+ .set_encoder_zero_point(
+ static_cast(
+ steering_hero.get_parameter("bottom_yaw_motor_zero_point").as_int())));
+ steering_hero.register_output("/referee/serial", referee_serial_);
referee_serial_->read = [this](std::byte* buffer, size_t size) {
return referee_ring_buffer_receive_.pop_front_n(
[&buffer](std::byte byte) noexcept { *buffer++ = byte; }, size);
@@ -420,49 +566,47 @@ class SteeringHero
});
return size;
};
-
- hero.register_output("/chassis/yaw/velocity_imu", chassis_yaw_velocity_imu_, 0);
-
- hero.register_output(
+ steering_hero.register_output(
"/chassis/powermeter/control_enable", powermeter_control_enabled_, false);
- hero.register_output(
+ steering_hero.register_output(
"/chassis/powermeter/charge_power_limit", powermeter_charge_power_limit_, 0.);
}
- BottomBoard(const BottomBoard&) = delete;
- BottomBoard& operator=(const BottomBoard&) = delete;
- BottomBoard(BottomBoard&&) = delete;
- BottomBoard& operator=(BottomBoard&&) = delete;
+ BottomBoard_two(const BottomBoard_two&) = delete;
+ BottomBoard_two& operator=(const BottomBoard_two&) = delete;
+ BottomBoard_two(BottomBoard_two&&) = delete;
+ BottomBoard_two& operator=(BottomBoard_two&&) = delete;
- ~BottomBoard() final = default;
+ ~BottomBoard_two() final = default;
void update() {
imu_.update_status();
dr16_.update_status();
supercap_.update_status();
- *chassis_yaw_velocity_imu_ = imu_.gz();
-
- for (auto& motor : chassis_wheel_motors_)
+ for (auto& motor : chassis_wheel_motors2_)
motor.update_status();
- for (auto& motor : chassis_steering_motors_)
+ for (auto& motor : chassis_steering_motors2_)
motor.update_status();
+
gimbal_bottom_yaw_motor_.update_status();
+
tf_->set_state(
gimbal_bottom_yaw_motor_.angle());
}
void command_update() {
+
auto builder = start_transmit();
builder.can1_transmit({
.can_id = 0x200,
.can_data =
device::CanPacket8{
- chassis_wheel_motors_[0].generate_command(),
- chassis_wheel_motors_[1].generate_command(),
- chassis_wheel_motors_[2].generate_command(),
- chassis_wheel_motors_[3].generate_command(),
+ device::CanPacket8::PaddingQuarter{},
+ device::CanPacket8::PaddingQuarter{},
+ chassis_wheel_motors2_[1].generate_command(),
+ chassis_wheel_motors2_[0].generate_command(),
}
.as_bytes(),
});
@@ -471,26 +615,14 @@ class SteeringHero
.can_id = 0x1FE,
.can_data =
device::CanPacket8{
+ chassis_steering_motors2_[0].generate_command(),
device::CanPacket8::PaddingQuarter{},
- device::CanPacket8::PaddingQuarter{},
- device::CanPacket8::PaddingQuarter{},
+ chassis_steering_motors2_[1].generate_command(),
supercap_.generate_command(),
}
.as_bytes(),
});
- builder.can2_transmit({
- .can_id = 0x1FE,
- .can_data =
- device::CanPacket8{
- chassis_steering_motors_[0].generate_command(),
- chassis_steering_motors_[1].generate_command(),
- chassis_steering_motors_[2].generate_command(),
- chassis_steering_motors_[3].generate_command(),
- }
- .as_bytes(),
- });
-
builder.can2_transmit({
.can_id = 0x141,
.can_data = gimbal_bottom_yaw_motor_.generate_command().as_bytes(),
@@ -501,16 +633,16 @@ class SteeringHero
void can1_receive_callback(const librmcs::data::CanDataView& data) override {
if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
return;
-
auto can_id = data.can_id;
- if (can_id == 0x201) {
- chassis_wheel_motors_[0].store_status(data.can_data);
- } else if (can_id == 0x202) {
- chassis_wheel_motors_[1].store_status(data.can_data);
- } else if (can_id == 0x203) {
- chassis_wheel_motors_[2].store_status(data.can_data);
+
+ if (can_id == 0x203) {
+ chassis_wheel_motors2_[1].store_status(data.can_data);
} else if (can_id == 0x204) {
- chassis_wheel_motors_[3].store_status(data.can_data);
+ chassis_wheel_motors2_[0].store_status(data.can_data);
+ } else if (can_id == 0x205) {
+ chassis_steering_motors2_[0].store_status(data.can_data);
+ } else if (can_id == 0x207) {
+ chassis_steering_motors2_[1].store_status(data.can_data);
} else if (can_id == 0x300) {
supercap_.store_status(data.can_data);
}
@@ -519,21 +651,15 @@ class SteeringHero
void can2_receive_callback(const librmcs::data::CanDataView& data) override {
if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]]
return;
-
auto can_id = data.can_id;
- if (can_id == 0x205) {
- chassis_steering_motors_[0].store_status(data.can_data);
- } else if (can_id == 0x206) {
- chassis_steering_motors_[1].store_status(data.can_data);
- } else if (can_id == 0x207) {
- chassis_steering_motors_[2].store_status(data.can_data);
- } else if (can_id == 0x208) {
- chassis_steering_motors_[3].store_status(data.can_data);
- } else if (can_id == 0x141) {
+
+ if (can_id == 0x141) {
gimbal_bottom_yaw_motor_.store_status(data.can_data);
}
}
+ rclcpp::Logger logger_;
+
void uart1_receive_callback(const librmcs::data::UartDataView& data) override {
const auto* uart_data = data.uart_data.data();
referee_ring_buffer_receive_.emplace_back_n(
@@ -557,17 +683,14 @@ class SteeringHero
device::Bmi088 imu_;
OutputInterface& tf_;
- OutputInterface chassis_yaw_velocity_imu_;
-
OutputInterface powermeter_control_enabled_;
OutputInterface powermeter_charge_power_limit_;
device::Dr16 dr16_;
-
- device::DjiMotor chassis_steering_motors_[4];
- device::DjiMotor chassis_wheel_motors_[4];
device::Supercap supercap_;
+ device::DjiMotor chassis_steering_motors2_[2];
+ device::DjiMotor chassis_wheel_motors2_[2];
device::LkMotor gimbal_bottom_yaw_motor_;
rmcs_utility::RingBuffer referee_ring_buffer_receive_{256};
@@ -578,10 +701,9 @@ class SteeringHero
rclcpp::Subscription::SharedPtr gimbal_calibrate_subscription_;
- std::unique_ptr top_board_;
- std::unique_ptr bottom_board_;
-
- rmcs_utility::TickTimer temperature_logging_timer_;
+ std::shared_ptr top_board_;
+ std::shared_ptr bottom_board_one_;
+ std::shared_ptr bottom_board_two_;
};
} // namespace rmcs_core::hardware