SwerveModule Class
The SwerveModule class initializes the swerve module on the robot. The method
getState
returns a new object of the SwerveModuleState
class, allowing us to
know the current state according to the linear speed of the throttle in meters
per second and the degrees the encoder has rotated. The method setState
gets
the current heading of the drive and takes a SwerveModuleState
object. The
method will use a PID controller to turn the drive to the desired heading at a desired
speed.
備註
For API specific issues, please see the WPILib API , CTRE API, and the REV Robotics API.
Constructor
1// 初始化 rotor & throttle 馬達
2private WPI_TalonFX mRotor;
3private WPI_TalonFX mThrottle;
4
5// 初始化 rotor encoder
6private WPI_CANCoder mRotorEncoder;
7
8// 初始化 rotor PID controller
9private PIDController mRotorPID;
10
11/**
12 * 構建新的 SwerveModule
13 *
14 * @param throttleID CAN ID of throttle 馬達
15 * @param rotorID CAN ID of rotor 馬達
16 * @param rotorEncoderID CAN ID of rotor encoder
17 * @param rotorOffsetAngleDeg rotor encoder 偏移量
18 */
19public SwerveModule(int throttleID, int rotorID, int rotorEncoderID, double rotorOffsetAngleDeg)
20{
21 // 實例化 throttle 馬達
22 mThrottle = new WPI_TalonFX(throttleID);
23
24 // 實例化 rotor 馬達
25 mRotor = new WPI_TalonFX(rotorID);
26
27 // 實例化 rotor absolute encoder
28 mRotorEncoder = new WPI_CANCoder(rotorEncoderID);
29
30 // 重置所有配置(保險起見以免有舊的配置)
31 mThrottle.configFactoryDefault();
32 mRotor.configFactoryDefault();
33 mRotorEncoder.configFactoryDefault();
34
35 // 根據之前的常數配置 rotor 馬達
36 mRotor.setInverted(SwerveConstants.kRotorMotorInversion);
37 mRotor.configVoltageCompSaturation(Constants.kVoltageCompensation);
38 mRotor.enableVoltageCompensation(true);
39 mRotor.setNeutralMode(NeutralMode.Brake);
40
41 // 根據之前的常數配置轉向 rotor encoder
42 mRotorEncoder.configAbsoluteSensorRange(AbsoluteSensorRange.Signed_PlusMinus180);
43 mRotorEncoder.configMagnetOffset(rotorOffsetAngleDeg);
44 mRotorEncoder.configSensorDirection(SwerveConstants.kRotorEncoderDirection);
45 mRotorEncoder.configSensorInitializationStrategy(
46 SensorInitializationStrategy.BootToAbsolutePosition
47 );
48
49 // 根據之前的常數配置 rotor 馬達的PID控制器
50 mRotorPID = new PIDController(
51 SwerveConstants.kRotor_kP,
52 SwerveConstants.kRotor_kI,
53 SwerveConstants.kRotor_kD
54 );
55
56 // ContinuousInput 認為 min 和 max 是同一點並且自動計算到設定點的最短路線
57 mRotorPID.enableContinuousInput(-180, 180);
58
59 // 根據之前的常數配置 throttle 馬達
60 mThrottle.configSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor);
61 mThrottle.configVoltageCompSaturation(Constants.kVoltageCompensation);
62 mThrottle.enableVoltageCompensation(true);
63 mThrottle.setNeutralMode(NeutralMode.Brake);
64}
1// 初始化 rotor & throttle 馬達
2private CANSparkMax mRotor;
3private CANSparkMax mThrottle;
4
5// 初始化 throttle encoder
6private RelativeEncoder mThrottleEncoder;
7
8// 初始化 rotor encoder
9private WPI_CANCoder mRotorEncoder;
10
11// 初始化 rotor PID controller
12private PIDController mRotorPID;
13
14/**
15 * 構建新的 SwerveModule
16 *
17 * @param throttleID CAN ID of throttle 馬達
18 * @param rotorID CAN ID of rotor 馬達
19 * @param rotorEncoderID CAN ID of rotor encoder
20 * @param rotorOffsetAngleDeg rotor encoder 偏移量
21 */
22public SwerveModule(int throttleID, int rotorID, int rotorEncoderID, double rotorOffsetAngleDeg)
23{
24 // 實例化 throttle 馬達 & encoder
25 mThrottle = new CANSparkMax(throttleID, MotorType.kBrushless);
26 mThrottleEncoder = mThrottle.getEncoder();
27
28 // 實例化 rotor 馬達
29 mRotor = new CANSparkMax(rotorID, MotorType.kBrushless);
30
31 // 實例化 rotor absolute encoder
32 mRotorEncoder = new WPI_CANCoder(rotorEncoderID);
33
34 // 重置所有配置(保險起見以免有舊的配置)
35 mThrottle.restoreFactoryDefaults();
36 mRotor.restoreFactoryDefaults();
37 mRotorEncoder.configFactoryDefault();
38
39 // 根據之前的常數配置 rotor 馬達
40 mRotor.setInverted(SwerveConstants.kRotorMotorInversion);
41 mRotor.enableVoltageCompensation(Constants.kVoltageCompensation);
42 mRotor.setIdleMode(IdleMode.kBrake);
43
44 // 根據之前的常數配置轉向 rotor encoder
45 mRotorEncoder.configAbsoluteSensorRange(AbsoluteSensorRange.Signed_PlusMinus180);
46 mRotorEncoder.configMagnetOffset(rotorOffsetAngleDeg);
47 mRotorEncoder.configSensorDirection(SwerveConstants.kRotorEncoderDirection);
48 mRotorEncoder.configSensorInitializationStrategy(
49 SensorInitializationStrategy.BootToAbsolutePosition
50 );
51
52 // 根據之前的常數配置 rotor 馬達的PID控制器
53 mRotorPID = new PIDController(
54 SwerveConstants.kRotor_kP,
55 SwerveConstants.kRotor_kI,
56 SwerveConstants.kRotor_kD
57 );
58
59 // ContinuousInput 認為 min 和 max 是同一點並且自動計算到設定點的最短路線
60 mRotorPID.enableContinuousInput(-180, 180);
61
62 // 根據之前的常數配置 throttle 馬達
63 mThrottle.enableVoltageCompensation(Constants.kVoltageCompensation);
64 mThrottle.setIdleMode(IdleMode.kBrake);
65
66 // 給與 throttle encoder 轉換係數以便它以米每秒而不是 RPM 為單位讀取速度
67 mThrottleEncoder.setVelocityConversionFactor(
68 SwerveConstants.kThrottleVelocityConversionFactor
69 );
70 mThrottleEncoder.setPositionConversionFactor(
71 SwerveConstants.kThrottlePositionConversionFactor
72 );
73}
1// 初始化 rotor & throttle 馬達
2private CANSparkMax mRotor;
3private CANSparkMax mThrottle;
4
5// 初始化 throttle encoder
6private RelativeEncoder mThrottleEncoder;
7
8// 初始化 rotor encoder
9private AnalogPotentiometer mRotorEncoder;
10
11// 初始化 rotor PID controller
12private PIDController mRotorPID;
13
14/**
15 * 構建新的 SwerveModule
16 *
17 * @param throttleID CAN ID of throttle 馬達
18 * @param rotorID CAN ID of rotor 馬達
19 * @param rotorEncoderID analog ID of rotor encoder
20 * @param rotorOffsetAngleDeg rotor encoder 偏移量
21 */
22public SwerveModule(int throttleID, int rotorID, int rotorEncoderID, double rotorOffsetAngleDeg)
23{
24 // 實例化 throttle 馬達 & encoder
25 mThrottle = new CANSparkMax(throttleID, MotorType.kBrushless);
26 mThrottleEncoder = mThrottle.getEncoder();
27
28 // 實例化 rotor 馬達
29 mRotor = new CANSparkMax(rotorID, MotorType.kBrushless);
30
31 // 實例化 rotor absolute encoder
32 // - 完整範圍 = 360,因為這是編碼器能返回的最大值
33 mRotorEncoder = new AnalogPotentiometer(rotorEncoderID, 360, rotorOffsetAngleDeg);
34
35 // 重置所有配置(保險起見以免有舊的配置)
36 mThrottle.restoreFactoryDefaults();
37 mRotor.restoreFactoryDefaults();
38
39 // 根據之前的常數配置 rotor 馬達
40 mRotor.setInverted(SwerveConstants.kRotorMotorInversion);
41 mRotor.enableVoltageCompensation(Constants.kVoltageCompensation);
42 mRotor.setIdleMode(IdleMode.kBrake);
43
44 // 根據之前的常數配置 rotor 馬達的PID控制器
45 mRotorPID = new PIDController(
46 SwerveConstants.kRotor_kP,
47 SwerveConstants.kRotor_kI,
48 SwerveConstants.kRotor_kD
49 );
50
51 // ContinuousInput 認為 min 和 max 是同一點並且自動計算到設定點的最短路線
52 mRotorPID.enableContinuousInput(-180, 180);
53
54 // 根據之前的常數配置 throttle 馬達
55 mThrottle.enableVoltageCompensation(Constants.kVoltageCompensation);
56 mThrottle.setIdleMode(IdleMode.kBrake);
57
58 // 給與 throttle encoder 轉換係數以便它以米每秒而不是 RPM 為單位讀取速度
59 mThrottleEncoder.setVelocityConversionFactor(
60 SwerveConstants.kThrottleVelocityConversionFactor
61 );
62 mThrottleEncoder.setPositionConversionFactor(
63 SwerveConstants.kThrottlePositionConversionFactor
64 );
65}
Methods
getState
輸出 swerve module 的當前狀態。
1public SwerveModuleState getState() {
2 double throttleVelocity =
3 mThrottle.getSelectedSensorVelocity() * SwerveConstants.kThrottleVelocityConversionFactor;
4
5 return new SwerveModuleState(
6 throttleVelocity,
7 Rotation2d.fromDegrees(mRotorEncoder.getAbsolutePosition())
8 );
9}
1public SwerveModuleState getState() {
2 return new SwerveModuleState(
3 mThrottleEncoder.getVelocity(),
4 Rotation2d.fromDegrees(mRotorEncoder.getAbsolutePosition())
5 );
6}
Return:
新的 SwerveModuleState 代表著目前的前進速度和面相角度。
getPosition
Outputs the current position of the swerve module.
1public SwerveModulePosition getPosition() {
2 double throttlePosition = mThrottle.getSelectedSensorPosition() * SwerveConstants.kThrottlePositionConversionFactor;
3
4 return new SwerveModulePosition(
5 throttlePosition,
6 Rotation2d.fromDegrees(mRotorEncoder.getAbsolutePosition())
7 );
8}
1public SwerveModulePosition getPosition() {
2 return new SwerveModulePosition(
3 mThrottleEncoder.getPosition(),
4 Rotation2d.fromDegrees(mRotorEncoder.get())
5 );
6}
Return:
New SwerveModulePosition representing the current throttle position and rotor angle.
setState
設置 swerve module 的狀態。
1public void setState(SwerveModuleState state) {
2 // 優化狀態,使轉向馬達不必旋轉超過 90 度來獲得目標的角度
3 SwerveModuleState optimizedState = SwerveModuleState.optimize(state, getState().angle);
4
5 // 通過比較目前角度與目標角度來用 PID 控制器計算轉向馬達所需的輸出
6 double rotorOutput = mRotorPID.calculate(
7 getState().angle.getDegrees(),
8 optimizedState.angle.getDegrees()
9 );
10
11 mRotor.set(rotorOutput);
12 mThrottle.set(optimizedState.speedMetersPerSecond);
13}
Parameters:
state
- 理想的 SwerveModuleState (angle & speed) of SwerveModule
備註
在我們的 Github 上查看我們在這些文檔中使用的代碼!