Máquinas de Estados Finitos#

Las máquinas de estados finitos (FSM) se utilizan a menudo en programación para permitir series de acciones más complejas. Esto es especialmente útil cuando se necesita que varias tareas se ejecuten al mismo tiempo, ya que permite que las tareas dependan de la ejecución de las demás de forma no lineal.

¿Qué es una máquina de estados finitos?#

The name of a finite state machine is very descriptive; it’s a state machine, with a finite number of states. It can be in one state at a time, and can transition to a different state once something happens. The Wikipedia example of a turnstile explains the concept very well.

Aplicación#

Aplicación ingenua#

Cuando se aprende por primera vez sobre los FSM, es bastante común que los programadores intenten utilizarlos. A menudo, intentan aplicar un FSM a sus programas autónomos segmentando sus autónomos en una declaración switch gigante, y a menudo se parece a esto:

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;
     }
}

Esto, sin embargo, no tiene realmente ningún beneficio en comparación con si el programador simplemente hubiera puesto cada uno de los segmentos del código en funciones, y los hubiera ejecutado en orden. De hecho, muchas veces, los programadores estructuran su código así en lugar de dividirlo en funciones. El resultado es un código autónomo que es más difícil de depurar y, en última instancia, más difícil de arreglar sobre la marcha durante una competencia o en otro momento de apuro.

Si uno dibujara el diagrama de transición de estado para cada uno de los estados, para el autónomo de arriba sería muy lineal, y las transiciones de estado siempre ocurren porque la sección del código terminó:

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;
}

De hecho, en muchas implementaciones, hacer transiciones de estado por cualquier otra razón es a menudo difícil porque el código se ejecuta linealmente y sólo está en un bucle para volver a ejecutar las sentencias switch. (A menudo, esto significa que el código tiene dificultades para reaccionar ante una petición de parada en medio de la ejecución autónoma).

Advertencia

No es aconsejable escribir código así. Si tu autónomo es síncrono, es preferible dividir tu código en funciones y ejecutarlas en orden, ya que así será más fácil de entender y editar sobre la marcha.

Aplicación útil#

Los FSM son la herramienta adecuada cuando un robot debe realizar varias tareas a la vez; un ejemplo habitual es cuando un robot debe automatizarse en teleoperación, pero sigue teniendo control sobre el chasis.

A menudo, los equipos tienen problemas porque su teleoperación se ejecuta en bucle y su lógica de servos tiene tiempos de espera. Pero podemos evitarlo si escribimos el código de forma asíncrona, es decir, en lugar de esperar a que se complete una tarea para realizar la siguiente, las tareas se ejecutan al mismo tiempo y se comprueba el estado de cada tarea sin detener la ejecución de las demás.

Un ejemplo de esto sería que si uno tuviera un robot similar al Gluten Free’s Rover Ruckus Robot, y uno quisiera automatizar el elevador de puntuación para que los conductores no tengan que pensar mientras el bot deposita los minerales. Hay dos partes del robot que son relevantes para nosotros en este ejercicio: el elevador de puntuación en ángulo, y el servo que inclina el volquete para que los minerales caigan. El objetivo es poder pulsar un botón y que el bot lo haga:

  • extender el ascensor,

  • en la extensión de elevación completa, incline el servo del cucharón de minerales para depositar los minerales,

  • esperar a que se caigan los minerales,

  • restablecer el servo a la posición original

  • retraer el ascensor

Si los conductores pulsan otro botón específico, dejaremos de ejecutar las acciones anteriores como medida de seguridad, por si el robot se rompe de algún modo y los conductores tienen que tomar el control manual. Mientras tanto, los conductores deberían poder seguir controlando nuestro chasis para que podamos hacer ajustes. Ahora, por supuesto, esto es un poco simplificado (y probablemente no del todo lo que hizo GF), pero servirá por ahora.

Antes de programar nada, puede ser útil dibujar el diagrama de estados para obtener una mejor comprensión de lo que el robot debería estar haciendo. Esto también puede contribuir a la presentación de un Premio de Control.

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"];
}

Observa cómo el restablecimiento del servo de descarga y la retracción del elevador comparten un estado. Esto se debe a que el robot no necesita esperar a que el servo se restablezca antes de mover el ascensor hacia abajo; ambos pueden ocurrir a la vez.

Ahora, pasemos a implementar el código para esto. En un OpMode tradicional, que se utiliza comúnmente para teleoperación, el código se ejecuta repetidamente en una función loop(), por lo que en lugar de esperar a que una transición de estado suceda directamente, el código comprobará repetidamente en cada llamada loop() si debe realizar una transición de estado. Este tipo de patrón «actualiza nuestro estado» evita que el código bloquee la ejecución del resto del código del loop(), como el chasis.

/*
 * 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);
   }
}