有限状态机#

有限状态机(FSM)通常用于编程,以实现更复杂的一系列操作。当需要多个任务同时运行时,这一点尤其有用,因为它允许任务以非线性方式相互依赖执行。

什么是有限状态机?#

有限状态机的名称非常具有描述性;它是一种状态机,具有有限个状态。它一次只能处于一种状态,一旦有事情发生,就可以过渡到另一种状态。维基百科 旋转门的例子很好地解释了这个概念。

具体实现#

简单实现#

初学 FSM 时,程序员尝试使用 FSM 的情况很常见。很多时候,他们试图将 FSM 应用到自主程序中,将自主程序分割成一个巨大的 switch 语句,通常看起来是这样的:

while (opModeIsActive()) {
    switch (state) {
        case DETECT_SKYSTONE:
            // skystone detection code here
            int position = detectSkystone();

            if (position == 0) {
                state = SKYSTONE_POS_0;
            }
            else if (position == 1) {
                state = SKYSTONE_POS_1;
            }
            else {
                state = SKYSTONE_POS_2;
            }
            break;
        case SKYSTONE_POS_0:
            // skystone position 0 here
            doSkystone(0);
            state = MOVE_FOUNDATION;
            break;
        case SKYSTONE_POS_1:
        case SKYSTONE_POS_2:
            // etc etc
            break;
        case MOVE_FOUNDATION:
            // foundation move code
            state = PARK;
            break;
        case PARK:
            // park the bot
            break;
     }
}

然而,与程序员简单地将每段代码放入函数并按顺序执行相比,这样做并没有任何好处。事实上,很多时候,程序员都会这样编排代码,而不是将代码分割成函数。这样做的结果是,自动阶段代码更难调试,最终也更难在比赛或其他时间紧迫的情况下临时修复。

如果画出每种状态的状态转换图,对于上面的自动程序来说,它将是非常线性的,而且状态转换总是因为该段代码完成而发生:

digraph {
   detect[label="Detect Skystone"];
   posZero[label="Skystone Position 0"];
   posOne[label="Skystone Position 1"];
   posTwo[label="Skystone Position 2"];
   move[label="Foundation Move"];
   park[label="Park"];

   detect->posZero;
   detect->posOne;
   detect->posTwo;

   posZero->move;
   posOne->move;
   posTwo->move;

   move->park;
}

事实上,在许多实现中,由于代码是线性执行的,只需在循环中重新运行 switch 语句,因此出于任何其他原因进行状态转换通常都很困难。(很多时候,这意味着代码很难对自动运行中的停止请求做出反应)。

警告

这样写代码是不可取的。如果你的自动运行程序是同步的,最好将代码分割成多个函数并按顺序运行,因为这样更易于理解和即时编辑。

有用的实现#

当机器人需要同时完成多项任务时,FSM 就是最合适的工具;一个常见的例子是,机器人需要在远程操作中实现自动化,但仍能控制传动系统。

很多时候,团队会遇到一些问题,因为他们的远程操作是在循环中执行的,而且他们的舵机逻辑中存在 sleep 函数。但是,如果我们以 异步 的方式编写代码,就可以避免这种情况的发生–在这种方式下,任务不是等一个任务完成后再执行下一个任务,而是同时执行,并且在不停止其他任务执行的情况下检查每个任务的状态。

举个例子,如果我们有一个类似于 Gluten Free’s Rover Ruckus Robot 的机器人,而我们想自动完成升降机的工作,这样驾驶员就不必在机器人堆放矿石时思考。在本练习中,机器人有两个与我们相关的部分:倾斜的得分升降机和倒出矿物的舵机。我们的目标是按下按钮,机器人就会开始工作:

  • 延长升降机,

  • 在升降机完全伸出的时候,调整矿斗舵机的角度,倒出矿物,

  • 等着矿石掉出来、

  • 将舵机复位到初始位置

  • 缩回升降机

如果驾驶员按下其他特定按钮,我们将停止执行上述操作,以防万一–万一机器人发生故障,驾驶员需要手动控制。与此同时,驾驶员仍能控制我们的传动系统,以便我们进行调整。当然,这有点简化了(可能也不完全是 GF 所做的那样),但目前还是可以做到的。

在编写任何程序之前,不妨绘制出相关的状态图,以便更好地了解机器人实际应该做些什么。这也可以为提交的控制奖增色不少。

digraph {
   start[label="Start"];
   extend[label="Extend Lift"];
   dump[label="Set Servo Dump"];
   reset[label="Reset Servo, Retract Lift"];

   start->extend[label="X Pressed"];
   extend->dump[label="Lift Fully Extended"];
   extend->start[label="Y Pressed"];
   dump->start[label="Y Pressed"];
   dump->reset[label="Minerals be Dumped"];
   reset->start[label="Lift Fully Retracted/Y Pressed"];
}

请注意,重置倾卸舵机和缩回移位机是共用一个状态的。这是因为机器人在向下移动移位机之前不需要等待舵机复位,它们可以同时进行。

现在,让我们来实际执行相关代码。在传统的 OpMode (通常用于远程操作)中,代码会在一个 loop() 函数中重复运行,因此代码不会直接等待状态转换的发生,而是会在每次 loop() 调用时重复检查是否应该执行状态转换。这种 “更新状态” 模式可以防止代码阻塞其他 loop() 代码的运行,例如传动系统。

/*
 * Some declarations that are boilerplate are
 * skipped for the sake of brevity.
 * Since there are no real values to use, named constants will be used.
 */

@TeleOp(name="FSM Example")
public class FSMExample extends OpMode {
    // An Enum is used to represent lift states.
    // (This is one thing enums are designed to do)
    public enum LiftState {
        LIFT_START,
        LIFT_EXTEND,
        LIFT_DUMP,
        LIFT_RETRACT
    };

    // The liftState variable is declared out here
    // so its value persists between loop() calls
    LiftState liftState = LiftState.LIFT_START;

    // Some hardware access boilerplate; these would be initialized in init()
    // the lift motor, it's in RUN_TO_POSITION mode
    public DcMotorEx liftMotor;

    // the dump servo
    public Servo liftDump;
    // used with the dump servo, this will get covered in a bit
    ElapsedTime liftTimer = new ElapsedTime();

    final double DUMP_IDLE; // the idle position for the dump servo
    final double DUMP_DEPOSIT; // the dumping position for the dump servo

    // the amount of time the dump servo takes to activate in seconds
    final double DUMP_TIME;

    final int LIFT_LOW; // the low encoder position for the lift
    final int LIFT_HIGH; // the high encoder position for the lift

    public void init() {
        liftTimer.reset();

        // hardware initialization code goes here
        // this needs to correspond with the configuration used
        liftMotor = hardwareMap.get(DcMotorEx.class, "liftMotor");
        liftDump = hardwareMap.get(Servo.class, "liftDump");

        liftMotor.setTargetPosition(LIFT_LOW);
        liftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
    }

    public void loop() {
        liftMotor.setPower(1.0);

        switch (liftState) {
            case LIFT_START:
                // Waiting for some input
                if (gamepad1.x) {
                    // x is pressed, start extending
                    liftMotor.setTargetPosition(LIFT_HIGH);
                    liftState = LiftState.LIFT_EXTEND;
                }
                break;
            case LIFT_EXTEND:
                 // check if the lift has finished extending,
                 // otherwise do nothing.
                if (Math.abs(liftMotor.getCurrentPosition() - LIFT_HIGH) < 10) {
                    // our threshold is within
                    // 10 encoder ticks of our target.
                    // this is pretty arbitrary, and would have to be
                    // tweaked for each robot.

                    // set the lift dump to dump
                    liftDump.setTargetPosition(DUMP_DEPOSIT);

                    liftTimer.reset();
                    liftState = LiftState.LIFT_DUMP;
                }
                break;
            case LIFT_DUMP:
                if (liftTimer.seconds() >= DUMP_TIME) {
                    // The robot waited long enough, time to start
                    // retracting the lift
                    liftDump.setTargetPosition(DUMP_IDLE);
                    liftMotor.setTargetPosition(LIFT_LOW);
                    liftState = LiftState.LIFT_RETRACT;
                }
                break;
            case LIFT_RETRACT:
                if (Math.abs(liftMotor.getCurrentPosition() - LIFT_LOW) < 10) {
                    liftState = LiftState.LIFT_START;
                }
                break;
            default:
                 // should never be reached, as liftState should never be null
                 liftState = LiftState.LIFT_START;
        }

        // small optimization, instead of repeating ourselves in each
        // lift state case besides LIFT_START for the cancel action,
        // it's just handled here
        if (gamepad1.y && liftState != LiftState.LIFT_START) {
            liftState = LiftState.LIFT_START;
        }

        // mecanum drive code goes here
        // But since none of the stuff in the switch case stops
        // the robot, this will always run!
        updateDrive(gamepad1, gamepad2);
   }
}