Swerve Class
Swerve Class 結合了 4 個 swerve module 來控制整個 swerve。
備註
有關 API 的特定問題,請參閱 WPILib API , CTRE API,和 REV Robotics API。
Constructor
1// 初始化 IMU
2private final WPI_Pigeon2 mImu = new WPI_Pigeon2(SwerveConstants.kImuID);
3
4private final SwerveModule mLeftFrontModule, mRightFrontModule, mLeftRearModule, mRightRearModule;
5private SwerveDriveOdometry mOdometry;
6
7public Swerve() {
8 // 實例化(instantiate)swerve module - 個代表機器上四個其一
9 mLeftFrontModule = new SwerveModule(
10 SwerveConstants.kLeftFrontThrottleID,
11 SwerveConstants.kLeftFrontRotorID,
12 SwerveConstants.kLeftFrontCANCoderID,
13 SwerveConstants.kLeftFrontRotorOffset
14 );
15
16 mRightFrontModule = new SwerveModule(
17 SwerveConstants.kRightFrontThrottleID,
18 SwerveConstants.kRightFrontRotorID,
19 SwerveConstants.kRightFrontCANCoderID,
20 SwerveConstants.kRightFrontRotorOffset
21 );
22
23 mLeftRearModule = new SwerveModule(
24 SwerveConstants.kLeftRearThrottleID,
25 SwerveConstants.kLeftRearRotorID,
26 SwerveConstants.kLeftRearCANCoderID,
27 SwerveConstants.kLeftRearRotorOffset
28 );
29
30 mRightRearModule = new SwerveModule(
31 SwerveConstants.kRightRearThrottleID,
32 SwerveConstants.kRightRearRotorID,
33 SwerveConstants.kRightRearCANCoderID,
34 SwerveConstants.kRightRearRotorOffset
35 );
36
37 // 實例化(instantiate)測程法(odometry) - 用於追踪位置
38 mOdometry = new SwerveDriveOdometry(
39 SwerveConstants.kSwerveKinematics,
40 mImu.getRotation2d(),
41 getModulePositions()
42 );
43}
Methods
使用當前 Swerve module 狀態更新測程法(odometry)。
periodic
1@Override
2public void periodic() {
3 // 使用當前Swerve module狀態更新測程法(odometry)。
4 mOdometry.update(mImu.getRotation2d(), getModulePositions());
5}
drive
移動底盤到想要的方向 / 地方與轉向。
1public void drive(double xSpeed, double ySpeed, double zSpeed, boolean fieldOriented) {
2 SwerveModuleState[] states = null;
3 if(fieldOriented) {
4 states = SwerveConstants.kSwerveKinematics.toSwerveModuleStates(
5 // IMU 用於 Field Oriented Control
6 ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, zSpeed, mImu.getRotation2d())
7 );
8 } else {
9 states = SwerveConstants.kSwerveKinematics.toSwerveModuleStates(
10 new ChassisSpeeds(xSpeed, ySpeed, zSpeed)
11 );
12 }
13 setModuleStates(states);
14}
Parameters:
xSpeed
- X 方向的功率百分比
ySpeed
- Y 方向的功率百分比
zSpeed
- 旋轉的功率百分比
fieldOriented
- 設置機器運動方式(Field or Robot Oriented)
getModuleStates
輸出 4 個 Swerve Module 的當前狀態 modules。
1public SwerveModuleState[] getModuleStates() {
2 return new SwerveModuleState[]{
3 mLeftFrontModule.getState(),
4 mRightFrontModule.getState(),
5 mLeftRearModule.getState(),
6 mRightRearModule.getState()
7 };
8}
Return:
返回 SwerveModuleState 數組中所有Swerve的狀態(順序:[左前、右前、左後、右後])。
getModulePositions
Outputs the current positions of the 4 drive swerve modules.
1public SwerveModulePosition[] getModulePositions() {
2 return new SwerveModulePosition[] {
3 mLeftFrontModule.getPosition(),
4 mRightFrontModule.getPosition(),
5 mLeftRearModule.getPosition(),
6 mRightRearModule.getPosition()
7 };
8}
Return:
返回 SwerveModulePosition 數組中所有Swerve的狀態(順序:[左前、右前、左後、右後])。
setModuleStates
設置 4 個 Swerve module 的狀態。
1// Swerve module 順序:[左前、右前、左後、右後]
2public void setModuleStates(SwerveModuleState[] desiredStates) {
3 SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, 1);
4 mLeftFrontModule.setState(desiredStates[0]);
5 mRightFrontModule.setState(desiredStates[1]);
6 mLeftRearModule.setState(desiredStates[2]);
7 mRightRearModule.setState(desiredStates[3]);
8}
Parameters:
desiredStates
- 理想 SwerveModuleState 數組。