Codificadores#

¿Qué son los codificadores?#

Muy a menudo, en FTC ®, quieres saber dónde está algo. Ya sea cuántas veces ha girado la rueda motriz, en qué ángulo se encuentra el brazo o hasta dónde han llegado las correderas de las cuerdas, los codificadores rotacionales pueden ayudarte. En FTC, un codificador es un sensor que registra el ángulo de rotación de un mecanismo.

Existen dos tipos de encóderes utilizados habitualmente en FTC, los relativos y los absolutos. Los encóderes relativos son los que se tratan aquí, ya que son los más comunes.

Codificadores relativos#

Estos codificadores, que van desde el codificador integrado en todos los motores homologados por FTC hasta codificadores externos comunes como el codificador REV Through Bore, registran la posición relativa del eje o mecanismo al que están conectados. Lo que esto significa es que la posición de salida es relativa a la posición inicial en el encendido del robot, lo que significa que la información de posición se pierde entre los ciclos de alimentación.

Truco

Los encoders relativos no se ponen a cero al principio de los OpModes. Puedes utilizar STOP_AND_RESET_ENCODERS para asegurarte de que tus encoders están siempre a cero al principio de un OpMode (ver más abajo).

Todos los encoders relativos del FTC utilizan el protocolo «cuadratura» para enviar información de posición al expansion hub. Como resultado, los encoders relativos deben conectarse a los puertos de encoder situados cerca de los puertos de motor para poder funcionar.

Terminología#

Recuento: Un «recuento» (a veces denominado «tic») se refiere a un incremento de la posición del encoder. Los encoders relativos informan de su posición como un número igual al número de «ticks» o «recuentos» que el encoder se ha movido desde su ángulo inicial.

Recuentos por revolución: El número de «conteos» que reporta un encoder después de haber dado exactamente una revolución. Este valor se utiliza habitualmente para convertir los «recuentos» del encoder en grados o revoluciones.

Advertencia

La terminología de cuadratura puede ser muy confusa. Algunos encoderes pueden informar de «pulsos por revolución». Un pulso puede equivaler a 1 ó 4 recuentos. Otros encoders pueden informar de «ciclos por revolución», que confusamente tienen el mismo acrónimo que cuentas por revolución. La mejor manera de comprobarlo es enchufar el encoder al REV Hub y girarlo 1 revolución completa, luego comprobar lo que informa.

Programación de codificadores#

Lectura de codificadores#

En el software FTC, se accede a los encoders de cuadratura y a los motores con el mismo objeto motor. Esto significa que podemos acceder a la posición de un codificador de la siguiente manera:

int position = motor.getCurrentPosition();
../../../_images/encoder-opmode-1.png

Aunque es conveniente si se utiliza el codificador del motor incorporado, esto puede llegar a ser confuso si se utilizan codificadores externos. Para utilizar encoders externos, debe utilizar el objeto motor asociado al puerto. Por ejemplo, si hay un motor en el puerto 1 llamado «Arm Motor» y un encoder externo conectado al puerto de encoder 1, debes hacer lo siguiente para obtener la posición del encoder:

DcMotor motor = hardwareMap.dcMotor.get("Arm Motor");
double position = motor.getCurrentPosition();
../../../_images/encoder-opmode-1.png

¡Estupendo! Ahora tenemos la posición relativa de nuestro encoder, informada en el número de «cuentas» que está desde lo que considera cero. Sin embargo, a menudo es conveniente que el codificador comience en cero al principio del OpMode. Aunque técnicamente no cambia nada, puede ayudar con la depuración y simplificar el código futuro. Para ello, podemos añadir una llamada para restablecer los codificadores antes de leerlos.

DcMotor motor = hardwareMap.dcMotor.get("Arm Motor");
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); // Reset the motor encoder
motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); // Turn the motor back on when we are done
int position = motor.getCurrentPosition();
../../../_images/encoder-opmode-2.png

Como nota, RUN_WITHOUT_ENCODER no desactiva el encoder. Le dice al SDK que no use el codificador del motor para el control de velocidad integrado. Repasaremos lo que esto significa en una sección posterior, pero por ahora, sepa que enciende el motor de nuevo para que podamos usarlo después de que el codificador se restablezca.

Ahora tenemos nuestra posición (en cuentas) relativa al ángulo inicial del encoder. Podemos hacer un programa rápido para ver esto en acción. Aquí, usamos un codificador de motor conectado a un puerto llamado «Arm Motor» en la configuración de hardware.

package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
@TeleOp
public class EncoderOpmode extends LinearOpMode {
    @Override
    public void runOpMode() throws InterruptedException {
        // Find a motor in the hardware map named "Arm Motor"
        DcMotor motor = hardwareMap.dcMotor.get("Arm Motor");

        // Reset the motor encoder so that it reads zero ticks
        motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);

        // Turn the motor back on, required if you use STOP_AND_RESET_ENCODER
        motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

        waitForStart();

        while (opModeIsActive()) {
            // Get the current position of the motor
            int position = motor.getCurrentPosition();

            // Show the position of the motor on telemetry
            telemetry.addData("Encoder Position", position);
            telemetry.update();
        }
    }
}
../../../_images/encoder-opmode-3.png

Si ejecuta el OpMode anterior y gira el codificador, debería ver que los valores cambian a medida que se mueve. Si gira el eje de vuelta a donde comenzó, verá que el número vuelve a (muy cerca de) cero. Como ejercicio, gire el eje una vuelta completa (360) grados y anote el número.

Hay algo más que podemos hacer con los encoders. Aunque saber el número de cuentas que se ha movido algo es útil, a menudo necesitaremos un número diferente, como el número de revoluciones que ha girado el encoder o el ángulo en el que se encuentra. Para determinarlos, necesitamos una constante, los contadores por revolución del encoder o CPR. En el caso de los encoders externos, este número suele aparecer en la hoja de datos. En el caso de los motores, suele aparecer en la página del producto, aunque algunos motores (sobre todo el Rev Ultraplanetary Gearbox) no lo indican claramente.

Truco

Puedes calcular los contadores por revolución de un motor tomando los contadores por revolución del motor base y multiplicándolos por el ratio de la caja de engranajes. Tenga cuidado de utilizar la relación real de la caja de engranajes cuando haga esto. Por ejemplo, un motor Ultraplanetario 5:1 tendría una cuenta por revolución de 28 * (5.23) = 146.44 porque el motor base tiene 28 Cuentas Por Revolución y la caja de cambios 5:1 en realidad tiene una relación de engranaje 5.23:1. Recuerde, cuando se utilizan dos cajas de engranajes una encima de la otra, se multiplican las relaciones de transmisión entre sí.

En el siguiente ejemplo, dividimos la posición del encoder por sus cuentas por revolución para obtener el número de revoluciones que ha girado el encoder. Tienes que sustituir [Your Counts Per Revolution Here] por los recuentos por revolución de tu motor, encontrados en su página de producto o calculados usando el consejo anterior.

double CPR = [Your Counts Per Revolution Here];

int position = motor.getCurrentPosition();
double revolutions = position/CPR;
../../../_images/encoder-opmode-4.png

Hay un número más que podemos obtener: el ángulo del eje. Calcular este número es muy sencillo. Podemos multiplicar el número de rotaciones por 360 (ya que hay 360 grados en una revolución). Puedes notar que este número puede ir por encima de 360 ya que el eje rota varias veces. Por ello, introducimos angleNormalized, que siempre estará entre 0 y 360.

double CPR = [Your Counts Per Revolution Here];

int position = motor.getCurrentPosition();
double revolutions = position/CPR;

double angle = revolutions * 360;
double angleNormalized = angle % 360;
../../../_images/encoder-opmode-5.png

Juntándolo todo, obtenemos el siguiente programa de pruebas.

package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
@TeleOp
public class EncoderOpmode extends LinearOpMode {
    @Override
    public void runOpMode() throws InterruptedException {
        // Find a motor in the hardware map named "Arm Motor"
        DcMotor motor = hardwareMap.dcMotor.get("Arm Motor");

        // Reset the motor encoder so that it reads zero ticks
        motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);

        // Turn the motor back on, required if you use STOP_AND_RESET_ENCODER
        motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

        waitForStart();

        while (opModeIsActive()) {
            double CPR = [Your Counts Per Revolution Here];

            // Get the current position of the motor
            int position = motor.getCurrentPosition();
            double revolutions = position/CPR;

            double angle = revolutions * 360;
            double angleNormalized = angle % 360;

            // Show the position of the motor on telemetry
            telemetry.addData("Encoder Position", position);
            telemetry.addData("Encoder Revolutions", revolutions);
            telemetry.addData("Encoder Angle (Degrees)", angle);
            telemetry.addData("Encoder Angle - Normalized (Degrees)", angleNormalized);
            telemetry.update();
        }
    }
}

:download:` Archivo de blocks descarga <block-code/encoder-opmode.blk>`

../../../_images/encoder-opmode-complete.png

Ruedas de seguimiento y carretes#

Hasta ahora, hemos trabajado sobre todo con motores que hacen girar algo. Sin embargo, muchos mecanismos en FTC son lineales, y puede ser deseable medirlos también en una unidad lineal. Afortunadamente, esto es muy sencillo. Todo lo que necesitamos saber es el diámetro del objeto que estamos midiendo.

Tenga cuidado al seleccionar el diámetro. Para las ruedas, es el diámetro exterior de la rueda, pero para los carretes, es el diámetro interior del carrete, donde descansa la cuerda. Para cadenas y correas, es el «diámetro de paso» del piñón o la polea.

A partir de aquí, podemos calcular la circunferencia (la longitud del arco del círculo, o la distancia que recorrerá la rueda/carrete en una rotación)

double diameter = 1.0; // Replace with your wheel/spool's diameter
double circumference = Math.PI * diameter;

double distance = circumference * revolutions;
../../../_images/spool-encoder-opmode-1.png

Nota

Las unidades son muy importantes cuando se trata de programación FTC, así que asegúrate de que siempre sean coherentes. Cualesquiera que sean las unidades que utilice para el diámetro serán las unidades para la distancia calculada. Por lo tanto, si mide el diámetro en pulgadas, la distancia calculada también será en pulgadas.

Si juntamos todo esto con nuestro programa de pruebas anterior, obtenemos

package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
@TeleOp
public class SpoolEncoderOpmode extends LinearOpMode {
   @Override
   public void runOpMode() throws InterruptedException {
      // Find a motor in the hardware map named "Arm Motor"
      DcMotor motor = hardwareMap.dcMotor.get("Arm Motor");

      // Reset the motor encoder so that it reads zero ticks
      motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);

      // Turn the motor back on, required if you use STOP_AND_RESET_ENCODER
      motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

      waitForStart();

      while (opModeIsActive()) {
            double CPR = [Your Counts Per Revolution Here];

            double diameter = 1.0; // Replace with your wheel/spool's diameter
            double circumference = Math.PI * diameter;

            // Get the current position of the motor
            int position = motor.getCurrentPosition();
            double revolutions = position/CPR;

            double angle = revolutions * 360;
            double angleNormalized = angle % 360;

            double distance = circumference * revolutions;

            //Show the position of the motor on telemetry
            telemetry.addData("Encoder Position", position);
            telemetry.addData("Encoder Revolutions", revolutions);
            telemetry.addData("Encoder Angle (Degrees)", angle);
            telemetry.addData("Encoder Angle - Normalized (Degrees)", angleNormalized);
            telemetry.addData("Linear Distance", distance);
            telemetry.update();
      }
   }
}

Funcionamiento de motores con encoderes#

Hemos aprendido a leer los valores del encoder, pero ¿cómo se fija a dónde se quiere ir y se le dice al motor que vaya allí?

Anteriormente, aprendimos sobre el modo RUN_WITHOUT_ENCODER para el motor. Podemos usar otro modo de motor, RUN_TO_POSITION, para decirle al motor que corra a una posición específica en ticks, así:

DcMotor motor = hardwareMap.dcmotor.get("Arm Motor");
motor.setMode(DcMotor.RunMode.RUN_TO_POSITION); // Tells the motor to run to the specific position
../../../_images/arm-opmode-1.png

Truco

Puedes encontrar más información sobre los modos de ejecución en la página oficial de documentación de REV Robotics

Sin embargo, antes de decirle al motor que vaya a una posición, tenemos que decirle a qué posición debe ir. Nótese que este valor debe ser un entero. Vamos a modificar el código anterior para hacer eso.

Advertencia

Poner el motor en modo RUN_TO_POSITION, antes de fijar una posición objetivo arrojará un error. Tenga cuidado de no hacerlo.

DcMotor motor = hardwareMap.dcmotor.get("Arm Motor");
int desiredPosition = 1000; // The position (in ticks) that you want the motor to move to
motor.setTargetPosition(desiredPosition); // Tells the motor that the position it should go to is desiredPosition
motor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
../../../_images/arm-opmode-2.png

Este código le dice al motor que se mueva a 1000 ticks, usando un bucle PID para controlar la posición del motor. Puedes leer más sobre bucles PID aquí.

Podemos limitar la velocidad a la que funciona el motor utilizando el siguiente código:

DcMotor motor = hardwareMap.dcmotor.get("Arm Motor");
int desiredPosition = 1000; // The position (in ticks) that you want the motor to move to
motor.setTargetPosition(desiredPosition); // Tells the motor that the position it should go to is desiredPosition
motor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
motor.setPower(0.5); // Sets the maximum power that the motor can go at
../../../_images/arm-opmode-3.png

Ahora, vamos a utilizar esta información para controlar un brazo en un OpMode.

package org.firstinspires.ftc.teamcode.Tests;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;

@TeleOp
public class ArmOpMode extends LinearOpMode {
   @Override
   public void runOpMode() throws InterruptedException {
      // Position of the arm when it's lifted
      int armUpPosition = 1000;

      // Position of the arm when it's down
      int armDownPosition = 0;

      // Find a motor in the hardware map named "Arm Motor"
      DcMotor armMotor = hardwareMap.dcMotor.get("Arm Motor");

      // Reset the motor encoder so that it reads zero ticks
      armMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);

      // Sets the starting position of the arm to the down position
      armMotor.setTargetPosition(armDownPosition);
      armMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);

      waitForStart();

      while (opModeIsActive()) {
            // If the A button is pressed, raise the arm
            if (gamepad1.a) {
               armMotor.setTargetPosition(armUpPosition);
               armMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
               armMotor.setPower(0.5);
            }

            // If the B button is pressed, lower the arm
            if (gamepad1.b) {
               armMotor.setTargetPosition(armDownPosition);
               armMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
               armMotor.setPower(0.5);
            }

            // Get the current position of the armMotor
            double position = armMotor.getCurrentPosition();

            // Get the target position of the armMotor
            double desiredPosition = armMotor.getTargetPosition();

            // Show the position of the armMotor on telemetry
            telemetry.addData("Encoder Position", position);

            // Show the target position of the armMotor on telemetry
            telemetry.addData("Desired Position", desiredPosition);

            telemetry.update();
      }
   }
}