# KOP控制教學
## [點我看範例程式](https://github.com/plokkolp/KOP_Roookie)
程式:`src/main/java/frc/robot`
## 教學目標
- 了解 **Command-based 架構**的角色分工
- 建立一個最基礎的「坦克控制」
- 學會如何寫出以下架構的程式 **Constants / Subsystem / Command / RobotContainer**
---
## 架構概念
在 Command-based 專案中,程式會分為四層:
1. **Constants** → 集中管理數字常數
2. **Subsystem** → 控制硬體
3. **Command** → 決定要做的動作
4. **RobotContainer** → 把搖桿、子系統、命令綁在一起
---
## 📊 系統流程圖
```mermaid
flowchart LR
A[Xbox 搖桿輸入] --> B[Command: ChassisControl]
B --> C[Subsystem: Chassis]
C --> D[四顆馬達輸出]
```
# Command-based KOP 控制教學
## 🔹 Constants.java
首先,我們需要定義整個專案會用到的數值。
這樣日後要改馬達 ID,只需要改一個地方。
這段程式定義了搖桿連到電腦 USB 的 Port 編號。
`0` 代表第一支搖桿。
```java
public final class Constants {
public static class ControllerPort {
public static final int kDriverControllerPort = 0;
}
```
這一段則定義了四顆馬達的 CAN ID,分別是左前、左後、右前、右後。
之後在 Subsystem 中會直接用這些常數。
```java
public static class ChassisConstants {
public static final int MOTOR_LF_ID = 0;
public static final int MOTOR_LB_ID = 1;
public static final int MOTOR_RF_ID = 2;
public static final int MOTOR_RB_ID = 3;
}
```
## 🔹 Subsystem:Chassis.java
接下來建立 **Chassis 子系統**,它會直接管理馬達。
這裡宣告了四顆馬達物件,分別對應到底盤的四顆輪子。**
這段程式碼在建構子裡,將馬達 ID 與 MotorType 綁定。
```java
private SparkMax leftFront = new SparkMax(ChassisConstants.MOTOR_LF_ID, MotorType.kBrushless);
private SparkMax leftBack = new SparkMax(ChassisConstants.MOTOR_LB_ID, MotorType.kBrushless);
private SparkMax rightFront = new SparkMax(ChassisConstants.MOTOR_RF_ID, MotorType.kBrushless);
private SparkMax rightBack = new SparkMax(ChassisConstants.MOTOR_RB_ID, MotorType.kBrushless);
```
這個方法用來設定左邊兩顆馬達的速度。
輸入 speed 範圍是 -1.0 到 +1.0。
```java
public void setLeftMotorSpeed(double speed) {
leftFront.set(speed);
leftBack.set(speed);
}
```
同理,這個方法設定右邊兩顆馬達的速度。
但因左右兩邊馬達旋轉方向須不一樣才會前進故加負號。
```java
public void setRightMotorSpeed(double speed) {
rightFront.set(-speed);
rightBack.set(-speed);
}
```
最後這個方法同時設定左右速度。
我們之後在 Command 裡會直接呼叫它。
```java
public void setChassisSpeed(double leftSpeed, double rightSpeed){
setLeftMotorSpeed(leftSpeed);
setRightMotorSpeed(rightSpeed);
```
## 🔹 Command:ChassisControl.java
現在建立一個 **Command**,用來把「搖桿輸入」轉換成「馬達輸出」。
這裡宣告了一個 Chassis 物件,以及兩個 Supplier<Double>。
這兩個 Supplier 會在執行時去讀取手把的搖桿值。
```java
public class ChassisControl extends Command {
private Chassis m_Chassis;
private Supplier<Double> leftStickY, rightStickY;
}
```
建構子會接收一個 Chassis 子系統,還有左右搖桿的 Supplier。
addRequirements(chassis) 表示這個 Command 會用到這個 Subsystem。
```java
public ChassisControl(Chassis m_Chassis, Supplier<Double> leftStickY, Supplier<Double> rightStickY) {
this.m_Chassis = m_Chassis;
this.leftStickY = leftStickY;
this.rightStickY = rightStickY;
// Use addRequirements() here to declare subsystem dependencies.命令必須要求控制子系統,命令要併在子系統上面,才不會有命令跟非命令同時控制子系統。建構函式從子系統intrue丟進來
addRequirements(m_Chassis);
}
}
```
在 execute() 裡,我們取得手把左右搖桿的數值,並交給 chassis.setChassisSpeed() 去設定馬達。
```java
Override
public void execute() {
m_Chassis.setChassisSpeed(-leftStickY.get(), -rightStickY.get());
}
```
這個方法永遠回傳 false,代表這個 Command 會持續執行。
它會作為底盤的「預設指令」。
```java
@Override
public boolean isFinished() {
return false;
}
```
## 🔹 RobotContainer.java
`RobotContainer` 是 Command-based 專案的中樞。
這裡我們建立一個 `Chassis` 子系統,以及一個 Xbox Controller 物件,來接收搖桿的輸入。
```java
public class RobotContainer {
private final Chassis m_chassis = new Chassis();
private final CommandXboxController m_driverController =
new CommandXboxController(OperatorConstants.kDriverControllerPort);
}
```
在建構子中,先呼叫 configureBindings()(目前留空)。
接著,把 ChassisControl 設定為 m_chassis 的預設指令。
這樣在 Teleop 階段,底盤會自動跟隨手把輸入移動。
```java
public RobotContainer() {
configureBindings();
m_chassis.setDefaultCommand(new ChassisControl(
m_chassis,
() -> m_driverController.getLeftY(),
() -> m_driverController.getRightY()
));
}
```
這裡先留兩個方法空白:
configureBindings() 之後可以用來綁定按鍵。
getAutonomousCommand() 之後可以回傳自動模式要執行的指令。
```java
private void configureBindings() { }
public Command getAutonomousCommand() {
return null;
}
```
## 課後作業
目前我們完成的程式是 **坦克控制**:
- 左搖桿控制左輪
- 右搖桿控制右輪
### 請思考:
如果我們希望改成 **左搖桿控制前後,右搖桿控制旋轉**,應該要怎麼修改?
### 提示 :
1. 在 `Chassis` 子系統新增方法:
```java
public void arcadeDrive(double forward, double rotation){
} //arcadeDrive可以自己命名
```
公式:
左輪速度 = forward + rotation
右輪速度 = forward - rotation
在這個方法裡呼叫:
```java
setLeftMotorSpeed(...);
setRightMotorSpeed(...);
```
#### 補充:
一顆馬達一次只能被一個方法設定speed