Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
50 commits
Select commit Hold shift + click to select a range
7e16876
Pick steering hero resources from branch steering-hero
QingZhuC Mar 15, 2026
a276525
Update to librmcs v3.1.0b0
QingZhuC Mar 15, 2026
5b219ae
Fixed board match, test AC
QingZhuC Mar 15, 2026
cef01f4
Fixed gimbal pitch control error and Update climber controller
floatpigeon Mar 15, 2026
901055a
Fixed friction direction error and Update putter controller without p…
floatpigeon Mar 15, 2026
6bbeed2
Auto Climber Demo!
floatpigeon Mar 17, 2026
040b4c4
AUTO CLIMB STABLE
Mar 17, 2026
7bf9b01
Fixed putter controller : add photoelectric_sensor(demo)
zhzy-star Mar 17, 2026
cf68ff7
Fixed dual_yaw; add new putter_controller.
zhzy-star Mar 18, 2026
eafda5f
dd
zhzy-star Mar 21, 2026
8eb58c3
fixed putter controller
zhzy-star Mar 23, 2026
65e7038
Update putter_controller: demo
zhzy-star Mar 23, 2026
fefdd17
Putter _controller : stable
zhzy-star Mar 24, 2026
c076f80
Fixed supercap, climber
zhzy-star Mar 24, 2026
f15fb2a
Putter_controller : Stable ,stable...
zhzy-star Mar 25, 2026
aa71f6e
Add chassis reserve mode
floatpigeon Mar 26, 2026
afae5ce
Shooting Test
zhzy-star Mar 26, 2026
295c155
Add ui
zhzy-star Mar 27, 2026
6e960be
Fixed : heat_controller, ui
zhzy-star Mar 28, 2026
855a695
Fixed : putter_controller, solve endless circle.
zhzy-star Mar 28, 2026
0be7dc7
Fixed correct parameters for pitch,top yaw and bottom yaw.Blocked enc…
QingZhuC Apr 2, 2026
0dd6722
Fixed ui kaka, friction detect
zhzy-star Apr 5, 2026
37f88c4
auto_aim
dwx5 Apr 9, 2026
1ae9419
update
dwx5 Apr 9, 2026
cbaa182
Fixed putter controller: Use grayscale_sensor to automate.
zhzy-star Apr 11, 2026
335272e
update_stable_planner
dwx5 Apr 16, 2026
f5522fd
Add foreraked detect.
zhzy-star Apr 16, 2026
72202a0
Add new keyboard operation
floatpigeon Apr 17, 2026
4d08d70
Add chassis auto mode slowly return
floatpigeon Apr 17, 2026
1f73861
stable version
dwx5 Apr 21, 2026
02a3955
Add steering chassis status
floatpigeon Apr 21, 2026
8d86d62
Change pitch encode mode to angle shift control
floatpigeon Apr 21, 2026
e12004d
Merge remote-tracking branch 'origin/refactor/merge-steering-hero' in…
dwx5 Apr 22, 2026
2ed481d
parameter change
dwx5 Apr 23, 2026
b3b5c77
Fixed parameter
zhzy-star Apr 24, 2026
bbbafa7
Fixed yaw
zhzy-star Apr 24, 2026
bc6cff9
add identification
zhzy-star Apr 24, 2026
d78057a
Fixed pitch torque logic
zhzy-star Apr 24, 2026
6501c36
mouse
dwx5 Apr 24, 2026
f6fbf89
Merge branch 'steering-hero_sp_vision_25' of https://github.com/Allia…
dwx5 Apr 24, 2026
06d2bf3
Fixed putter_controller
zhzy-star Apr 25, 2026
d619dcc
Merge branch 'steering-hero_sp_vision_25' of https://github.com/Allia…
zhzy-star Apr 25, 2026
b5ffc3b
Bug: add steering-hero_test, but steering not well
zhzy-star May 1, 2026
b052d9a
Fix can id error and update parameters
floatpigeon May 2, 2026
bce59cc
view color
dwx5 May 2, 2026
27f8608
update cmake
dwx5 May 2, 2026
202fa39
clean for RMUC
dwx5 May 2, 2026
395808e
parameter changes and outline check
dwx5 May 4, 2026
d090494
fixed : top_board
zhzy-star May 5, 2026
c65fdf6
Merge remote-tracking branch 'origin/main' into steering-hero_sp_visi…
dwx5 May 7, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
495 changes: 495 additions & 0 deletions .script/identification/fit_gravity_torque.py

Large diffs are not rendered by default.

969 changes: 969 additions & 0 deletions .script/identification/fit_sweep_graybox.py

Large diffs are not rendered by default.

Binary file not shown.
Binary file added librmcs-firmware-c_board-3.1.0.dfu
Binary file not shown.
1 change: 1 addition & 0 deletions rmcs_ws/src/hikcamera
Submodule hikcamera added at 212e11
355 changes: 355 additions & 0 deletions rmcs_ws/src/rmcs_bringup/config/steering-hero-little.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,355 @@
rmcs_executor:
ros__parameters:
update_rate: 1000.0
components:
- rmcs_core::hardware::SteeringHeroLittle -> 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::SteeringWheelStatus -> steering_wheel_status
- 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
- rmcs_core::broadcaster::TfBroadcaster -> tf_broadcaster

- sp_vision_25::bridge::HeroAutoAimBridge -> hero_auto_aim_bridge

# - rmcs_core::controller::identification::SweptFrequencyController -> pitch_swept_frequency_controller
# - rmcs_core::controller::identification::StaticTorqueTestController -> pitch_static_torque_test_controller
# - rmcs_core::controller::identification::SweptFrequencyController -> top_yaw_swept_frequency_controller
# - rmcs_core::controller::identification::SweptFrequencyController -> bottom_yaw_swept_frequency_controller




hero_hardware:
ros__parameters:
board_serial_top_board: "AF-BFF7-0B6F-46A5-2B4B-AA20-89C2-E180-64B9"
serial_bottom_rmcs_board: "AF-60BB-7484-FA24-F3FC-399B-454D-22FA-1B1D"
bottom_yaw_motor_zero_point: 35833
pitch_motor_zero_point: 47885
top_yaw_motor_zero_point: 49457
viewer_motor_zero_point: 3030
external_imu_port: /dev/ttyUSB0
bullet_feeder_motor_zero_point: 41415
left_front_zero_point: 5814
right_front_zero_point: 3806
left_back_zero_point: 7825
right_back_zero_point: 1767
# 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_front_steering/velocity
- /chassis/left_front_steering/control_torque
- /chassis/left_front_steering/torque
- /chassis/right_front_steering/angle
- /chassis/right_front_steering/velocity
- /chassis/right_front_steering/control_torque
- /chassis/right_front_steering/torque
- /chassis/left_back_steering/angle
- /chassis/left_back_steering/velocity
- /chassis/left_back_steering/control_torque
- /chassis/left_back_steering/torque
- /chassis/right_back_steering/angle
- /chassis/right_back_steering/velocity
- /chassis/right_back_steering/control_torque
- /chassis/right_back_steering/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
first_stair_approach_pitch: 0.458
second_stair_approach_pitch: 0.354
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.753376
lower_limit: 0.257038

dual_yaw_controller:
ros__parameters:
top_yaw_angle_kp: 22.2
top_yaw_angle_ki: 0.0
top_yaw_angle_kd: 0.0
top_yaw_velocity_kp: 8.92
top_yaw_velocity_ki: 0.0026
top_yaw_velocity_kd: 0.0
top_yaw_velocity_integral_min: -2500.0
top_yaw_velocity_integral_max: 2500.0
bottom_yaw_angle_kp: 13.9
bottom_yaw_angle_ki: 0.0
bottom_yaw_angle_kd: 0.0
bottom_yaw_velocity_kp: 3.0
bottom_yaw_velocity_ki: 0.0006
bottom_yaw_velocity_kd: 0.0
bottom_yaw_velocity_integral_min: -2500.0
bottom_yaw_velocity_integral_max: 2500.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: 25.6
ki: 0.0
kd: 0.0

pitch_velocity_pid_controller:
ros__parameters:
measurement: /gimbal/pitch/velocity_imu
setpoint: /gimbal/pitch/control_velocity
control: /gimbal/pitch/control_torque
kp: 14.11
ki: 0.0040
kd: 0.0
integral_min: -2500.0
integral_max: 2500.0

gimbal_player_viewer_controller0:
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:
- 368.00
- 368.00
- 532.00
- 532.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: 4
aim_velocity: 11.8
log_mode: 1 # 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.0008
ki: 0.00
kd: 0.000055

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.0008
ki: 0.00
kd: 0.000055

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.0005
ki: 0.00
kd: 0.00004

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.0005
ki: 0.00
kd: 0.00004

steering_wheel_status:
ros__parameters:
vehicle_radius: 0.286378
wheel_radius: 0.055

steering_wheel_controller:
ros__parameters:
mess: 22.0
moment_of_inertia: 1.08
vehicle_radius: 0.318198
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

hero_auto_aim_bridge:
ros__parameters:
config_file: "configs/standard3.yaml"
bullet_speed_fallback: 11.4
result_timeout: 0.1 # 0.08
debug: false

pitch_swept_frequency_controller:
ros__parameters:
target: /gimbal/pitch

sweep: true
logarithmic: true
start_freq: 0.1
end_freq: 10.0
duration: 60.0
amplitude: 10.0

pid: true
setpoint: 0.0
position_kp: 20.0
position_ki: 0.0
position_kd: 0.0
velocity_kp: 1.65
velocity_ki: 0.0
velocity_kd: 0.0
dc_offset: 0.0

top_yaw_swept_frequency_controller:
ros__parameters:
target: /gimbal/top_yaw

sweep: true
logarithmic: true
start_freq: 0.1
end_freq: 10.0
duration: 60.0
amplitude: 20.0

pid: true
setpoint: 0.0
position_kp: 10.0
position_ki: 0.0
position_kd: 0.0
velocity_kp: 3.0
velocity_ki: 0.0
velocity_kd: 0.0
dc_offset: 0.0

bottom_yaw_swept_frequency_controller:
ros__parameters:
target: /gimbal/bottom_yaw

sweep: true
logarithmic: true
start_freq: 0.1
end_freq: 4.0
duration: 80.0
amplitude: 2.0
Loading