diff --git a/cpp/SwerveWithPathPlanner/src/main/cpp/Robot.cpp b/cpp/SwerveWithPathPlanner/src/main/cpp/Robot.cpp index a8980db6..2afe3c52 100644 --- a/cpp/SwerveWithPathPlanner/src/main/cpp/Robot.cpp +++ b/cpp/SwerveWithPathPlanner/src/main/cpp/Robot.cpp @@ -12,7 +12,6 @@ Robot::Robot() {} void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); - /** * This example of adding Limelight is very simple and may not be sufficient for on-field use. * Users typically need to provide a standard deviation that scales with the distance to target diff --git a/python/SwerveWithPathPlanner/generated/tuner_constants.py b/python/SwerveWithPathPlanner/generated/tuner_constants.py index 87d7f781..341fed6d 100644 --- a/python/SwerveWithPathPlanner/generated/tuner_constants.py +++ b/python/SwerveWithPathPlanner/generated/tuner_constants.py @@ -63,20 +63,20 @@ class TunerConstants: # Theoretical free speed (m/s) at 12 V applied output; # This needs to be tuned to your individual robot - speed_at_12_volts: units.meters_per_second = 4.73 + speed_at_12_volts: units.meters_per_second = 4.70 # Every 1 rotation of the azimuth results in _couple_ratio drive motor turns; # This may need to be tuned to your individual robot - _couple_ratio = 3.5714285714285716 + _couple_ratio = 3.5 - _drive_gear_ratio = 6.746031746031747 + _drive_gear_ratio = 7.363636364 _steer_gear_ratio = 12.8 _wheel_radius: units.meter = inchesToMeters(2.167) _invert_left_side = False _invert_right_side = True - _canbus = CANBus("*", "./logs/example.hoot") + _canbus = CANBus("rio", "./logs/example.hoot") _pigeon_id = 1 # These are only used for simulation @@ -116,44 +116,44 @@ class TunerConstants: ) # Front Left - _front_left_drive_motor_id = 4 - _front_left_steer_motor_id = 3 - _front_left_encoder_id = 3 - _front_left_encoder_offset: units.rotation = -0.470458984375 - _front_left_steer_motor_inverted = False + _front_left_drive_motor_id = 5 + _front_left_steer_motor_id = 4 + _front_left_encoder_id = 2 + _front_left_encoder_offset: units.rotation = -0.83544921875 + _front_left_steer_motor_inverted = True - _front_left_x_pos: units.meter = inchesToMeters(10) - _front_left_y_pos: units.meter = inchesToMeters(10) + _front_left_x_pos: units.meter = inchesToMeters(10.5) + _front_left_y_pos: units.meter = inchesToMeters(10.5) # Front Right - _front_right_drive_motor_id = 2 - _front_right_steer_motor_id = 1 - _front_right_encoder_id = 0 - _front_right_encoder_offset: units.rotation = -0.051025390625 - _front_right_steer_motor_inverted = False + _front_right_drive_motor_id = 7 + _front_right_steer_motor_id = 6 + _front_right_encoder_id = 3 + _front_right_encoder_offset: units.rotation = -0.15234375 + _front_right_steer_motor_inverted = True - _front_right_x_pos: units.meter = inchesToMeters(10) - _front_right_y_pos: units.meter = inchesToMeters(-10) + _front_right_x_pos: units.meter = inchesToMeters(10.5) + _front_right_y_pos: units.meter = inchesToMeters(-10.5) # Back Left - _back_left_drive_motor_id = 0 - _back_left_steer_motor_id = 7 - _back_left_encoder_id = 2 - _back_left_encoder_offset: units.rotation = 0.237548828125 - _back_left_steer_motor_inverted = False + _back_left_drive_motor_id = 1 + _back_left_steer_motor_id = 0 + _back_left_encoder_id = 0 + _back_left_encoder_offset: units.rotation = -0.4794921875 + _back_left_steer_motor_inverted = True - _back_left_x_pos: units.meter = inchesToMeters(-10) - _back_left_y_pos: units.meter = inchesToMeters(10) + _back_left_x_pos: units.meter = inchesToMeters(-10.5) + _back_left_y_pos: units.meter = inchesToMeters(10.5) # Back Right - _back_right_drive_motor_id = 6 - _back_right_steer_motor_id = 5 + _back_right_drive_motor_id = 3 + _back_right_steer_motor_id = 2 _back_right_encoder_id = 1 - _back_right_encoder_offset: units.rotation = -0.438720703125 - _back_right_steer_motor_inverted = False + _back_right_encoder_offset: units.rotation = -0.84130859375 + _back_right_steer_motor_inverted = True - _back_right_x_pos: units.meter = inchesToMeters(-10) - _back_right_y_pos: units.meter = inchesToMeters(-10) + _back_right_x_pos: units.meter = inchesToMeters(-10.5) + _back_right_y_pos: units.meter = inchesToMeters(-10.5) front_left = _constants_creator.create_module_constants( _front_left_steer_motor_id,