Tune drivetrain for 2019
Change-Id: I6b011fa13b622738fa1c17e66af412587f396d8e
diff --git a/y2019/control_loops/drivetrain/drivetrain_base.cc b/y2019/control_loops/drivetrain/drivetrain_base.cc
index 71f7cb9..26ca861 100644
--- a/y2019/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2019/control_loops/drivetrain/drivetrain_base.cc
@@ -24,12 +24,11 @@
const DrivetrainConfig<double> &GetDrivetrainConfig() {
static DrivetrainConfig<double> kDrivetrainConfig{
::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
- ::frc971::control_loops::drivetrain::LoopType::OPEN_LOOP,
+ ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
::frc971::control_loops::drivetrain::GyroType::IMU_Z_GYRO,
::frc971::control_loops::drivetrain::IMUType::IMU_X,
- drivetrain::MakeDrivetrainLoop,
- drivetrain::MakeVelocityDrivetrainLoop,
+ drivetrain::MakeDrivetrainLoop, drivetrain::MakeVelocityDrivetrainLoop,
drivetrain::MakeKFDrivetrainLoop,
drivetrain::MakeHybridVelocityDrivetrainLoop,
@@ -37,10 +36,8 @@
chrono::duration<double>(drivetrain::kDt)),
drivetrain::kRobotRadius, drivetrain::kWheelRadius, drivetrain::kV,
- drivetrain::kHighGearRatio, drivetrain::kLowGearRatio,
- drivetrain::kJ,
- drivetrain::kMass,
- kThreeStateDriveShifter, kThreeStateDriveShifter,
+ drivetrain::kHighGearRatio, drivetrain::kLowGearRatio, drivetrain::kJ,
+ drivetrain::kMass, kThreeStateDriveShifter, kThreeStateDriveShifter,
true /* default_high_gear */, 0 /* down_offset if using constants use
constants::GetValues().down_error */,
0.8 /* wheel_non_linearity */, 1.2 /* quickturn_wheel_multiplier */,
diff --git a/y2019/control_loops/python/drivetrain.py b/y2019/control_loops/python/drivetrain.py
index b0a213b..e2d6eec 100644
--- a/y2019/control_loops/python/drivetrain.py
+++ b/y2019/control_loops/python/drivetrain.py
@@ -18,10 +18,10 @@
# Encoder is on a 24 tooth gear attached to the output gear.
kDrivetrain = drivetrain.DrivetrainParams(
- J=4.0,
- mass=40.0,
+ J=1.5,
+ mass=38.5,
# TODO(austin): Measure.
- robot_radius=0.616 / 2.0,
+ robot_radius=0.45 / 2.0,
wheel_radius=4.0 * 0.0254 / 2.0,
G=9.0 / 52.0,
q_pos=0.14,