Fix wrist oscillations
Modeled wrist inertia was really low, causing oscillations. Somehow the
comp robot is now different than the practice bot...
Change-Id: I45c38f93d5c3a59d66ca4e65349a1b7a785f1212
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/y2023/control_loops/python/roll.py b/y2023/control_loops/python/roll.py
index ce0fac0..750b34f 100644
--- a/y2023/control_loops/python/roll.py
+++ b/y2023/control_loops/python/roll.py
@@ -24,9 +24,9 @@
motor=control_loop.BAG(),
G=18.0 / 48.0 * 1.0 / 36.0,
# 598.006 in^2 lb
- J=0.175,
+ J=0.175 * 3.0,
q_pos=0.40,
- q_vel=20.0,
+ q_vel=5.0,
kalman_q_pos=0.12,
kalman_q_vel=2.0,
kalman_q_voltage=4.0,