编码器#

什么是编码器(Encoder)?#

在FTC® 中很常见的是,你想知道某物在哪个方位。无论是传动轮旋转了多少次,机械臂处于什么角度,还是滑轨走了多远,旋转编码器都可以帮助你。在FTC中,编码器是指跟踪机械旋转角度的任何传感器。

FTC中常用的编码器有两种,相对编码器和绝对编码器。相对编码器是这里介绍的,因为它们是更常见的类型。

相对编码器#

从每个FTC电机中的内置编码器到常见的外部编码器,如REV通孔编码器,这些编码器记录它们所连接的轴或机构的相对位置。这意味着编码器的位置输出是相对于机器人通电时的初始位置来计算的,这也意味着编码器的位置信息会在不通电时丢失。

小技巧

相对编码器不会在OpMode开始时重置为零!你可以使用STOP_AND_RESET_ENCODERS来确保编码器在OpMode开始时始终为零(见下文)。

FTC中的所有相对编码器都使用“正交(quadrature)”协议向扩展集线器发送位置信息。因此,相对编码器必须插入位于电机端口附近的编码器端口才能运行。

相关术语#

计数(count):一个“count”(有时称为一个“tick”)是指编码器位置的一个增量。相对编码器将其位置输出为一个数字,该数字等于编码器从其起始角度移动的“ticks”或“counts”的数量。

每转计数(counts per revolution):编码器恰好转了一圈后输出的“counts”数。此值通常用于将编码器“counts”转换为度或转数。

警告

正交术语(Quadrature terminology)可能会变得非常混乱!一些编码器可能会报告“每转脉冲(pulses per revolution)”。一个脉冲可以等于1或4个计数。其他编码器可能会报告“每转周期(cycles per revolution)”,这与每转计数具有相同的首字母缩写词。最好的检查方法是将编码器插入REV集线器并将其转1个完整转,然后检查它报告的内容。

编程编码器#

阅读编码器#

在FTC软件中,正交编码器和电机使用相同的电机对象访问。这意味着我们可以像这样访问编码器的位置:

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

使用内置电机编码器很方便,而使用外部编码器就很容易造成混乱。要使用外部编码器,必须使用与端口相关联的电机对象。例如,如果端口1中有一个名为“机械臂电机”的电机,编码器端口1中插入了一个外部编码器,则必须执行以下操作才能获得编码器的位置:

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

太好了!我们现在有了编码器的相对位置,它从相对的零始点开始,以“计数”的数量输出数值。然而,让编码器在OpMode的开头从零开始通常很方便。虽然从技术上讲它不会改变任何东西,但它可以帮助调试和简化未来的代码。为此,我们可以在读取编码器之前添加一个重置编码器的调用。

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

请注意,RUN_WITHOUT_ENCODER不会禁用编码器。它只是会告诉SDK不要使用电机编码器进行内置速度控制。 我们将在后面的部分讨论这意味着什么,但现在,知道它会重新打开电机,以便我们可以在编码器复位后使用它。

现在我们有了相对于编码器起始角度的位置(以计数为单位)。我们可以制作一个快速程序来查看这一点的运行情况。在这里,我们使用插入硬件配置中名为“Arm Motor”的端口的电机编码器。

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

如果你运行上述OpMode并转动编码器,你应该会看到值在你移动时发生变化。如果你将轴旋转回起始位置,你将看到数字返回(非常接近)零。作为练习,将轴旋转一周(360)度并记下数字。

我们还可以用编码器做一件事。虽然知道移动的计数很有用,但通常需要一个不同的数字,比如编码器转动的转数或角度。为了确定这些,我们需要一个常数,编码器每转计数或CPR。对于外部编码器,这个数字通常在数据表中提供。对于电机,它通常会出现在产品页面上,尽管一些电机(最明显的是Rev Ultraplanetary Gearbox)没有明确提供。

小技巧

你可以通过获取基础电机的每转计数并将其乘以齿轮箱比来计算电机的每转计数。执行此操作时请注意使用实际齿轮箱比!例如,5:1的Ultraplanetary电机的每转计数为28*(5.23)=146.44,因为基础电机的每转计数为28,而5:1齿轮箱实际上具有5.23:1的齿轮比。请记住,当使用两个齿轮箱时,你需要将齿轮箱比相乘。

在下面的示例中,我们将编码器位置除以它的每转计数,以获得编码器旋转的转数。你必须将[Your Counts Per Revolution Here]替换为电机的每转计数,可在其产品页面上找到或使用上述提示计算。

double CPR = [Your Counts Per Revolution Here];

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

我们还可以得到一个数字:轴的角度。计算这个数字非常简单。我们可以将旋转次数乘以360(因为一次旋转有360度)。你可能会注意到,当轴多次旋转时,这个数字可以超过360。因此,我们引入angleNormalized,它将始终介于0和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

把它们放在一起,我们得到了以下测试程序。

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

跟踪轮和线轴#

到目前为止,我们主要是使用电机旋转物体。然而,FTC中的许多机制都是线性的,也可以用线性单位来计量它们。幸运的是,这非常简单。我们只需要知道我们正在计量的物体的直径。

选择直径时要小心。对于轮子来说,它是轮子的外径,但对于线轴来说,它是线轴的内径,也就是弦的位置。对于链条和皮带来说,它是链轮或皮带轮的“节距直径(pitch diameter)”。

从这里,我们可以计算周长(圆的弧长,或轮子/线轴在一次旋转中行驶的距离)

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

备注

在处理FTC编程时单位非常重要,所以要确保它们始终一致!无论你用什么单位表示直径,都是你计算距离的单位。所以如果你以英寸为单位测量直径,输出显示的距离数据也将以英寸为单位。

将这些与我们之前的测试程序放在一起,我们得到了

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

带编码器的运行电机#

我们已经学会了如何读取编码器值,但是如何设置要去的地方并告诉电机去那里?

先前,我们了解了电机的RUN_WITHOUT_ENCODER模式。我们可以使用另一种电机模式,RUN_TO_POSITION,以tick告诉电机运行到特定位置,如下所示:

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

小技巧

你可以在 官方REV机器人文档页面 找到更多关于运行模式的信息。

然而,在我们告诉电机去一个位置之前,我们必须告诉电机运行到什么位置。注意,这个值必须是一个整数。 让我们修改上面的代码来做到这一点。

警告

在设置目标位置之前将电机设置为RUN_TO_POSITION模式会提示错误。小心不要这样做!

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

此代码告诉电机移动到1000tick,使用PID回路来控制电机的位置。你可以在 此处 阅读有关PID回路的更多信息。

我们可以使用以下代码限制电机运行的速度:

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

现在,让我们使用此信息来控制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();
      }
   }
}