♻️ full agent refactor

This commit is contained in:
2026-06-10 21:15:34 +02:00
parent a98e86ef66
commit 1e0836e1bc
49 changed files with 1309 additions and 829 deletions

View File

@@ -1,64 +0,0 @@
<?xml version="1.0" encoding="utf-8"?>
<robot name="cartpole">
<!-- World link (fixed base) -->
<link name="world"/>
<!-- Cart (slides along x-axis) -->
<link name="cart">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
</collision>
</link>
<!-- Cart slides along x-axis -->
<joint name="cart_joint" type="prismatic">
<parent link="world"/>
<child link="cart"/>
<axis xyz="1 0 0"/>
<limit lower="-2.4" upper="2.4" effort="100" velocity="10"/>
</joint>
<!-- Pole (rotates around y-axis, attached on top of cart) -->
<link name="pole">
<inertial>
<origin xyz="0 0 0.3"/>
<mass value="0.1"/>
<inertia ixx="0.003" ixy="0" ixz="0" iyy="0.003" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin xyz="0 0 0.3"/>
<geometry>
<cylinder radius="0.02" length="0.6"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.3"/>
<geometry>
<cylinder radius="0.02" length="0.6"/>
</geometry>
</collision>
</link>
<!-- Pole rotates freely (no motor) -->
<joint name="pole_joint" type="revolute">
<parent link="cart"/>
<child link="pole"/>
<origin xyz="0 0 0.05"/>
<axis xyz="0 1 0"/>
<limit lower="-6.28" upper="6.28" effort="0" velocity="100"/>
<dynamics damping="0.0" friction="0.0"/>
</joint>
</robot>

View File

@@ -1,10 +0,0 @@
# Classic cartpole — robot hardware config.
urdf: cartpole.urdf
actuators:
- joint: cart_joint
type: motor
gear: 10.0
ctrl_range: [-1.0, 1.0]
damping: 0.05

View File

@@ -0,0 +1,10 @@
# Motor-only hardware config
# Encoder and motor constants for the motor-only sysid capture.
encoder:
ppr: 11 # pulses per revolution (before quadrature)
gear_ratio: 30.0 # gearbox ratio
# counts_per_rev = ppr × gear_ratio × 4 (quadrature) = 1320
motor:
max_pwm: 255 # maximum PWM command accepted by firmware

40
assets/motor/motor.xml Normal file
View File

@@ -0,0 +1,40 @@
<?xml version="1.0" encoding="utf-8"?>
<mujoco model="motor_sysid">
<compiler angle="radian" autolimits="true"/>
<option timestep="0.002" integrator="Euler"/>
<worldbody>
<light pos="0 0 1" dir="0 0 -1"/>
<!-- Fixed base (gearbox housing) -->
<body name="base" pos="0 0 0.15">
<geom type="cylinder" size="0.04 0.06" mass="0.921"
rgba="0.3 0.3 0.3 1" contype="0" conaffinity="0"/>
<!-- Arm: rotates around motor_joint (z-axis) -->
<body name="arm" pos="0 0 0">
<joint name="motor_joint" type="hinge" axis="0 0 1"
range="-1.5708 1.5708"
damping="0.001" armature="0.0001" frictionloss="0.03"/>
<!-- Rotor disk: mass is tunable by the optimizer -->
<geom name="rotor_disk" type="cylinder" size="0.008 0.004"
mass="0.012" pos="0 0 0" rgba="0.6 0.6 0.6 1"
contype="0" conaffinity="0"/>
<!-- Arm load: lightweight arm attached to motor shaft -->
<geom name="arm_load" type="capsule" size="0.004"
fromto="0 0 0 -0.014 0.002 0.016"
mass="0.021" rgba="0.8 0.3 0.1 1"
contype="0" conaffinity="0"/>
</body>
</body>
</worldbody>
<actuator>
<general name="motor" joint="motor_joint"
gear="0.064"
ctrllimited="true" ctrlrange="-1 1"
dyntype="filter" dynprm="0.03"/>
</actuator>
</mujoco>

View File

@@ -0,0 +1,42 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Motor-only model WITHOUT arm/pendulum load.
Use for arm-off sysid captures. arm_load mass set to ~0. -->
<mujoco model="motor_sysid_bare">
<compiler angle="radian" autolimits="true"/>
<option timestep="0.002" integrator="Euler"/>
<worldbody>
<light pos="0 0 1" dir="0 0 -1"/>
<!-- Fixed base (gearbox housing) -->
<body name="base" pos="0 0 0.15">
<geom type="cylinder" size="0.04 0.06" mass="0.921"
rgba="0.3 0.3 0.3 1" contype="0" conaffinity="0"/>
<!-- Arm: rotates around motor_joint (z-axis) -->
<body name="arm" pos="0 0 0">
<joint name="motor_joint" type="hinge" axis="0 0 1"
range="-1.5708 1.5708"
damping="0.001" armature="0.0001" frictionloss="0.03"/>
<!-- Rotor disk: mass is tunable by the optimizer -->
<geom name="rotor_disk" type="cylinder" size="0.008 0.004"
mass="0.012" pos="0 0 0" rgba="0.6 0.6 0.6 1"
contype="0" conaffinity="0"/>
<!-- Arm load: near-zero mass for bare-shaft sysid -->
<geom name="arm_load" type="capsule" size="0.004"
fromto="0 0 0 -0.014 0.002 0.016"
mass="0.001" rgba="0.8 0.3 0.1 0.3"
contype="0" conaffinity="0"/>
</body>
</body>
</worldbody>
<actuator>
<general name="motor" joint="motor_joint"
gear="0.064"
ctrllimited="true" ctrlrange="-1 1"
dyntype="filter" dynprm="0.03"/>
</actuator>
</mujoco>

Binary file not shown.

After

Width:  |  Height:  |  Size: 463 KiB

View File

@@ -0,0 +1,67 @@
{
"best_params": {
"actuator_gear_pos": 0.3711939014035462,
"actuator_gear_neg": 0.42814281188601877,
"actuator_filter_tau": 0.022300731564787457,
"motor_damping_pos": 0.0013836218905629106,
"motor_damping_neg": 0.005196351489379768,
"motor_armature": 0.0027534181478216656,
"motor_frictionloss_pos": 0.03674406439012955,
"motor_frictionloss_neg": 0.06908200024786905,
"viscous_quadratic": 0.000958226218765762,
"back_emf_gain": 0.0036492272912788297,
"stribeck_friction_boost": 0.044748043677129666,
"stribeck_vel": 4.0513395945623705,
"rotor_mass": 0.03982640764507874,
"motor_deadzone_pos": 0.14181963932762467,
"motor_deadzone_neg": 0.031454276545010214,
"action_bias": -0.007362969452509152,
"gearbox_backlash": 1.4749880999407965e-09
},
"best_cost": 0.21167928018839952,
"recording": "/Users/victormylle/Library/CloudStorage/SeaDrive-VictorMylle(cloud.optimize-it.be)/My Libraries/Projects/AI/RL-Framework/assets/motor/recordings/motor_from_cartpole_162432.npz",
"param_names": [
"actuator_gear_pos",
"actuator_gear_neg",
"actuator_filter_tau",
"motor_damping_pos",
"motor_damping_neg",
"motor_armature",
"motor_frictionloss_pos",
"motor_frictionloss_neg",
"viscous_quadratic",
"back_emf_gain",
"stribeck_friction_boost",
"stribeck_vel",
"rotor_mass",
"motor_deadzone_pos",
"motor_deadzone_neg",
"action_bias",
"gearbox_backlash"
],
"defaults": {
"actuator_gear_pos": 0.064,
"actuator_gear_neg": 0.064,
"actuator_filter_tau": 0.03,
"motor_damping_pos": 0.003,
"motor_damping_neg": 0.003,
"motor_armature": 0.0001,
"motor_frictionloss_pos": 0.03,
"motor_frictionloss_neg": 0.03,
"viscous_quadratic": 0.0,
"back_emf_gain": 0.0,
"stribeck_friction_boost": 0.0,
"stribeck_vel": 2.0,
"rotor_mass": 0.012,
"motor_deadzone_pos": 0.08,
"motor_deadzone_neg": 0.08,
"action_bias": 0.0,
"gearbox_backlash": 0.0
},
"timestamp": "2026-03-23T20:50:53.648753",
"history_summary": {
"first_cost": 5.105499579419285,
"final_cost": 0.21167928018839952,
"generations": 500
}
}

View File

@@ -0,0 +1,19 @@
<?xml version='1.0' encoding='utf-8'?>
<mujoco model="motor_sysid">
<compiler angle="radian" autolimits="true" />
<option timestep="0.002" integrator="Euler" />
<worldbody>
<light pos="0 0 1" dir="0 0 -1" />
<body name="base" pos="0 0 0.15">
<geom type="cylinder" size="0.04 0.06" mass="0.921" rgba="0.3 0.3 0.3 1" contype="0" conaffinity="0" />
<body name="arm" pos="0 0 0">
<joint name="motor_joint" type="hinge" axis="0 0 1" range="-1.5708 1.5708" damping="0" armature="0.0027534181478216656" frictionloss="0" />
<geom name="rotor_disk" type="cylinder" size="0.008 0.004" mass="0.03982640764507874" pos="0 0 0" rgba="0.6 0.6 0.6 1" contype="0" conaffinity="0" />
<geom name="arm_load" type="capsule" size="0.004" fromto="0 0 0 -0.014 0.002 0.016" mass="0.021" rgba="0.8 0.3 0.1 1" contype="0" conaffinity="0" />
</body>
</body>
</worldbody>
<actuator>
<general name="motor" joint="motor_joint" gear="0.3996683566447825" ctrllimited="true" ctrlrange="-1 1" dyntype="filter" dynprm="0.022300731564787457" />
</actuator>
</mujoco>

6
assets/motor/robot.yaml Normal file
View File

@@ -0,0 +1,6 @@
# Motor-only sysid config
# Minimal config for the motor-only identification pipeline.
# The optimizer patches motor.xml in-memory; this file tells it
# which MJCF to load and provides encoder/hardware constants.
mjcf: motor.xml

View File

@@ -0,0 +1,4 @@
# Motor-only sysid config — bare shaft (no arm/pendulum load)
# Use with arm-off captures to identify pure motor dynamics.
mjcf: motor_bare.xml

View File

@@ -0,0 +1,23 @@
# Tuned motor config — generated by src.sysid.motor.optimize
# Original: robot.yaml
mjcf: motor_tuned.xml
joints:
motor_joint:
armature: 0.002753
frictionloss: 0.052913
hardware_realism:
actuator_gear_pos: 0.371194
actuator_gear_neg: 0.428143
motor_damping_pos: 0.001384
motor_damping_neg: 0.005196
motor_frictionloss_pos: 0.036744
motor_frictionloss_neg: 0.069082
motor_deadzone_pos: 0.14182
motor_deadzone_neg: 0.031454
action_bias: -0.007363
viscous_quadratic: 0.000958
back_emf_gain: 0.003649
stribeck_friction_boost: 0.044748
stribeck_vel: 4.05134
gearbox_backlash: 0.0

View File

@@ -1,21 +1,30 @@
# Tuned robot config — generated by src.sysid.optimize
# Canonical training model — unified sysid (cost 0.925, 475 generations).
# Source: sysid_result.json → exported via src.sysid.export.
# Key physics: ~96 ms motor lag (filter_tau), Stribeck friction, driver bias.
# Regenerate with:
# python -m src.sysid.optimize --robot-path assets/rotary_cartpole --recording <capture>.npz
# then copy robot_tuned.yaml over this file once validated
# (python -m src.sysid.visualize to compare real vs sim).
urdf: rotary_cartpole_tuned.urdf
urdf: rotary_cartpole.urdf
actuators:
- joint: motor_joint
type: motor
gear: [0.424182, 0.425031] # torque constant [pos, neg] (motor sysid)
ctrl_range: [-0.592, 0.592] # effective control bound (sysid-tuned)
deadzone: [0.141291, 0.078015] # L298N min |ctrl| for torque [pos, neg]
damping: [0.002027, 0.014665] # viscous damping [pos, neg]
frictionloss: [0.057328, 0.053355] # Coulomb friction [pos, neg]
filter_tau: 0.005035 # 1st-order actuator filter (motor sysid)
viscous_quadratic: 0.000285 # velocity² drag
back_emf_gain: 0.006758 # back-EMF torque reduction
- joint: motor_joint
type: motor
gear: [0.846499, 1.183733] # torque constant [pos, neg]
ctrl_range: [-0.686251, 0.686251] # PWM saturation (MAX_MOTOR_SPEED / 255)
deadzone: [0.181097, 0.202072] # L298N min |ctrl| for torque [pos, neg]
damping: [0.013165, 0.015452] # viscous damping [pos, neg]
frictionloss: [0.014244, 0.001005] # Coulomb friction [pos, neg]
filter_tau: 0.096263 # 1st-order actuator lag (s) — dominant!
stribeck_friction_boost: 0.068594 # extra static friction near standstill
stribeck_vel: 5.279594 # Stribeck decay velocity (rad/s)
action_bias: 0.056566 # additive ctrl bias (driver asymmetry)
joints:
motor_joint:
armature: 0.002773 # reflected rotor inertia (motor sysid)
frictionloss: 0.0 # handled by motor model via qfrc_applied
armature: 0.001676 # reflected rotor inertia (kg·m²)
frictionloss: 0.0 # handled by motor model via qfrc_applied
pendulum_joint:
damping: 0.000119
frictionloss: 1.0e-05
damping: 1.2e-05
frictionloss: 7.2e-05

View File

@@ -0,0 +1,34 @@
# Tuned robot config — generated by src.sysid.optimize
# Original: robot.yaml
# Run `python -m src.sysid.visualize` to compare real vs sim.
urdf: rotary_cartpole_tuned.urdf
actuators:
- joint: motor_joint
type: motor
gear:
- 0.846499
- 1.183733
ctrl_range:
- -0.686251
- 0.686251
deadzone:
- 0.181097
- 0.202072
damping:
- 0.013165
- 0.015452
frictionloss:
- 0.014244
- 0.001005
filter_tau: 0.096263
stribeck_friction_boost: 0.068594
stribeck_vel: 5.279594
action_bias: 0.056566
joints:
motor_joint:
armature: 0.001676
frictionloss: 0.0
pendulum_joint:
damping: 1.2e-05
frictionloss: 7.2e-05

View File

@@ -0,0 +1,80 @@
<?xml version='1.0' encoding='utf-8'?>
<robot name="rotary_cartpole">
<link name="world" />
<link name="base_link">
<inertial>
<origin xyz="-0.00011 0.00117 0.06055" rpy="0 0 0" />
<mass value="0.921" />
<inertia ixx="0.002385" iyy="0.002484" izz="0.000559" ixy="0.0" iyz="-0.000149" ixz="6e-06" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/base_link.stl" scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<joint name="base_joint" type="fixed">
<parent link="world" />
<child link="base_link" />
</joint>
<link name="arm">
<inertial>
<origin xyz="0.02679980831009001 -0.015110803875962989 -0.005337417994989926" rpy="0 0 0" />
<mass value="0.04052645463607292" />
<inertia ixx="2.70e-06" iyy="7.80e-07" izz="2.44e-06" ixy="0.0" iyz="7.20e-08" ixz="0.0" />
</inertial>
<visual>
<origin xyz="0.006947 -0.00395 -0.14796" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/arm_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0.006947 -0.00395 -0.14796" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/arm_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<joint name="motor_joint" type="revolute">
<origin xyz="-0.006947 0.00395 0.14796" rpy="0 0 0" />
<parent link="base_link" />
<child link="arm" />
<axis xyz="0 0 1" />
<limit lower="-1.5708" upper="1.5708" effort="10.0" velocity="200.0" />
<dynamics damping="0.001" />
</joint>
<link name="pendulum">
<inertial>
<origin xyz="0.04237886229290564 -0.05762212306183831 -0.0006039324398328591" rpy="0 0 0" />
<mass value="0.056793277126969105" />
<inertia ixx="0.0005956997356690322" iyy="8.986080748758447e-05" izz="0.0006855370063143978" ixy="-1.074983574165622e-05" iyz="0.0" ixz="0.0" />
</inertial>
<visual>
<origin xyz="0.006895 -0.023224 -0.162953" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/pendulum_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0.006895 -0.023224 -0.162953" rpy="0 0 0" />
<geometry>
<mesh filename="meshes/pendulum_1.stl" scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<joint name="pendulum_joint" type="continuous">
<origin xyz="0.000052 0.019274 0.014993" rpy="0 1.5708 0" />
<parent link="arm" />
<child link="pendulum" />
<axis xyz="0 -1 0" />
<dynamics damping="0.0001" />
</joint>
</robot>

Binary file not shown.

After

Width:  |  Height:  |  Size: 845 KiB

View File

@@ -0,0 +1,101 @@
{
"best_params": {
"actuator_gear_pos": 0.8464986357922419,
"actuator_gear_neg": 1.1837332515116656,
"actuator_filter_tau": 0.09626340711982824,
"motor_damping_pos": 0.013165358841570964,
"motor_damping_neg": 0.015451769431035585,
"motor_armature": 0.0016762295220909746,
"motor_frictionloss_pos": 0.014244285616762612,
"motor_frictionloss_neg": 0.0010053574956085138,
"stribeck_friction_boost": 0.06859381652654695,
"stribeck_vel": 5.279593819777324,
"motor_deadzone_pos": 0.1810971675049997,
"motor_deadzone_neg": 0.20207167371643614,
"action_bias": 0.05656632270757292,
"arm_mass": 0.04052645463607292,
"arm_com_x": 0.02679980831009001,
"arm_com_y": -0.015110803875962989,
"arm_com_z": -0.005337417994989926,
"pendulum_mass": 0.056793277126969105,
"pendulum_com_x": 0.04237886229290564,
"pendulum_com_y": -0.05762212306183831,
"pendulum_com_z": -0.0006039324398328591,
"pendulum_ixx": 0.0005956997356690322,
"pendulum_iyy": 8.986080748758447e-05,
"pendulum_izz": 0.0006855370063143978,
"pendulum_ixy": -1.074983574165622e-05,
"pendulum_damping": 1.1718327130851149e-05,
"pendulum_frictionloss": 7.204244487092445e-05,
"ctrl_limit": 0.6862506602999546
},
"best_cost": 0.9250391788859942,
"recording": "/Users/victormylle/Library/CloudStorage/SeaDrive-VictorMylle(cloud.optimize-it.be)/My Libraries/Projects/AI/RL-Framework/assets/rotary_cartpole/recordings/capture_20260328_153749.npz",
"param_names": [
"actuator_gear_pos",
"actuator_gear_neg",
"actuator_filter_tau",
"motor_damping_pos",
"motor_damping_neg",
"motor_armature",
"motor_frictionloss_pos",
"motor_frictionloss_neg",
"stribeck_friction_boost",
"stribeck_vel",
"motor_deadzone_pos",
"motor_deadzone_neg",
"action_bias",
"arm_mass",
"arm_com_x",
"arm_com_y",
"arm_com_z",
"pendulum_mass",
"pendulum_com_x",
"pendulum_com_y",
"pendulum_com_z",
"pendulum_ixx",
"pendulum_iyy",
"pendulum_izz",
"pendulum_ixy",
"pendulum_damping",
"pendulum_frictionloss",
"ctrl_limit"
],
"defaults": {
"actuator_gear_pos": 0.371194,
"actuator_gear_neg": 0.428143,
"actuator_filter_tau": 0.022301,
"motor_damping_pos": 0.001384,
"motor_damping_neg": 0.005196,
"motor_armature": 0.002753,
"motor_frictionloss_pos": 0.036744,
"motor_frictionloss_neg": 0.069082,
"stribeck_friction_boost": 0.0,
"stribeck_vel": 2.0,
"motor_deadzone_pos": 0.14182,
"motor_deadzone_neg": 0.031454,
"action_bias": 0.0,
"arm_mass": 0.0211,
"arm_com_x": -0.0071,
"arm_com_y": 0.00085,
"arm_com_z": 0.00795,
"pendulum_mass": 0.03937,
"pendulum_com_x": 0.06025,
"pendulum_com_y": -0.07602,
"pendulum_com_z": -0.00346,
"pendulum_ixx": 6.2e-05,
"pendulum_iyy": 3.7e-05,
"pendulum_izz": 7.83e-05,
"pendulum_ixy": -6.93e-06,
"pendulum_damping": 0.0001,
"pendulum_frictionloss": 0.0001,
"ctrl_limit": 0.588
},
"preprocess_vel": true,
"timestamp": "2026-03-28T17:09:39.241413",
"history_summary": {
"first_cost": 13.490216059926947,
"final_cost": 0.9250391788859942,
"generations": 475
}
}