Skip to content

3. 创建一个遥控命令

在本教程中,我们将学习如何创建机器人命令。命令是WPILib中实现机器人行为的基本单元,它们封装了特定的动作或行为序列。我们将参考ChassisTeleop命令的结构,创建一个新的IntakeTeleop命令。代码下载链接

WPILib的命令框架基于命令模式设计,具有以下关键特性:

  • 组合性:命令可以组合成更复杂的行为序列,支持顺序、并行和条件执行
  • 可中断性:命令可以在任何时候被安全中断,确保机器人状态的一致性
  • 子系统管理:自动处理子系统的占用和释放,防止资源冲突
  • 状态封装:每个命令封装完整的行为逻辑,便于测试和复用

示例程序

让我们分析ChassisTeleop命令的结构,了解命令的关键组成部分:

java
public class ChassisTeleop extends Command {
  // a. 依赖声明

  // b. 构造方法
  public ChassisTeleop(
      Chassis chassis, DoubleSupplier fowardSupplier, DoubleSupplier rotationSupplier) {
  }

  // c. 开始方法 - 命令开始时调用
  @Override
  public void initialize() {
  }

  // d. 执行方法 - 周期性调用
  @Override
  public void execute() {
  }

  // e. 结束方法 - 命令结束时调用
  @Override
  public void end(boolean interrupted) {
  }

  // f. 返回命令是否执行完毕
  @Override
  public boolean isFinished() {
  }
}

a. 依赖声明

java
public class ChassisTeleop extends Command {
  private final Chassis chassis;
  private final DoubleSupplier fowardSupplier;
  private final DoubleSupplier rotationSupplier;
}

命令通过构造函数注入所需的依赖:

  • chassis: 要控制的子系统实例
  • DoubleSupplier: 函数式接口,提供输入值

b. 构造方法

java
public class ChassisTeleop extends Command {
  public ChassisTeleop(
      Chassis chassis, DoubleSupplier fowardSupplier, DoubleSupplier rotationSupplier) {
    this.chassis = chassis;
    this.fowardSupplier = fowardSupplier;
    this.rotationSupplier = rotationSupplier;
    addRequirements(chassis); // 关键:声明命令所需的子系统
  }
}

addRequirements()方法告诉命令调度器这个命令需要独占访问chassis子系统。当该命令运行时,其他需要同一子系统的命令将被阻止。

c. 开始方法

java
public class ChassisTeleop extends Command {
  @Override
  public void initialize() {
  }
}

initialize()会在命令实例化之后、execute()重复运行之前被调用一次,在这个例子中,这里没有需要初始化的内容。

d. 执行方法

java
public class ChassisTeleop extends Command {
  @Override
  public void execute() {
    // 输入处理
    double forward = 5.0 * Math.abs(fowardSupplier.getAsDouble()) * fowardSupplier.getAsDouble();
    double rotation = 3.0 * Math.abs(rotationSupplier.getAsDouble()) * rotationSupplier.getAsDouble();

    // 控制逻辑
    if (forward < 0) {
      double leftSpeed = forward + rotation;
      double rightSpeed = forward - rotation;
      chassis.setWheelsVelocities(leftSpeed, rightSpeed);
    } else {
      double leftSpeed = forward - rotation;
      double rightSpeed = forward + rotation;
      chassis.setWheelsVelocities(leftSpeed, rightSpeed);
    }
  }
}

execute()方法在每个调度周期(约20ms)被调用:

  • 输入处理:对原始输入应用非线性变换,提供更好的操控体验
  • 控制逻辑:根据前进方向调整差速计算,确保直观的控制响应

e. 结束方法

java
public class ChassisTeleop extends Command {
  @Override
  public void end(boolean interrupted) {
    chassis.setWheelsVelocities(0, 0);
  }
}

end()方法在命令结束时被调用:

  • interrupted参数指示命令是被正常结束还是被中断
  • 确保子系统回到安全状态

f. 完成条件

java
public class ChassisTeleop extends Command {
  @Override
  public boolean isFinished() {
    return false; // 持续运行
  }
}

对于遥控操作命令,通常返回false使其持续运行,直到操作员停止或更高级别的命令中断它。

你的回合

现在你需要参考ChassisTeleop的结构,完成IntakeTeleop命令的设计。该命令应该根据四个布尔输入来控制吸取装置的滚筒运动和机械臂角度。

java
public class IntakeTeleop extends Command {
  private final Intake intake;
  private final BooleanSupplier rollerInjectSupplier;
  private final BooleanSupplier rollerEjectSupplier;
  private final BooleanSupplier armUpSupplier;
  private final BooleanSupplier armDownSupplier;

  public IntakeTeleop(
      Intake intake,
      BooleanSupplier rollerInjectSupplier,
      BooleanSupplier rollerEjectSupplier,
      BooleanSupplier armUpSupplier,
      BooleanSupplier armDownSupplier) {
    this.intake = intake;
    this.rollerInjectSupplier = rollerInjectSupplier;
    this.rollerEjectSupplier = rollerEjectSupplier;
    this.armUpSupplier = armUpSupplier;
    this.armDownSupplier = armDownSupplier;
    addRequirements(intake);
  }

  @Override
  public void execute() {
    // TODO: implement intake teleop control

    // when both buttons are pressed, do nothing
    // when inject button is pressed, intake
    // when eject button is pressed, outtake

    // when both buttons are pressed, do nothing
    // when arm up button is pressed, raise the arm
    // when arm down button is pressed, lower the arm
  }

  @Override
  public void end(boolean interrupted) {
    // TODO: stop the rollers and hold the arm position
  }

  @Override
  public boolean isFinished() {
    return false;
  }
}

效果演示

通过左右摇杆分别控制机器人的左、右轮前进。右扳机键用于控制滚筒吸入,左扳机键控制滚筒吐出。左肩键用于抬升吸取装置角度,右肩键用于降低吸取装置角度。