All Known Implementing Classes:
ArmBlank, DoubleArmBlank, DoubleArmImpl

public interface DoubleArm
ATTENTION: New for 2024:
New parameters:
  • elevatorLimitBuffer
  • elevatorOffsetLength
These, as well as elevator upper and lower limits, are now in inches, measured from the back of the robot. This change was made because of:
  • The new game rule this year - our robot cannot be more than 42 inches long in that direction
  • How the new extension limit code works


Represents the combination pivot and elevator mechanism and allows both to be controlled by setting their powers independently or by setting a pivot angle (degrees) and extension distance (inches - see above). The "setPower()" methods do not actually set power. They set a percentage of the max. velocity.



To work around an unknown bug (presumably in AccelLimiter?), when passing an AccelLimiter into this subsystem (or creating one anywhere), multiply the maxAccel and maxDeltaVEachLoop arguments by 10.
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Interface
    Description
    static class 
     
  • Method Summary

    Modifier and Type
    Method
    Description
    int
    Get the current average position of the elevator motors.
    double
    Get the current average power of the elevator motors.
    double
    Get the current average velocity of the elevator motors.
    int
    Get the current average position of the pivot motors.
    double
    Get the current average power of the pivot motors.
    double
    Get the current average velocity of the pivot motors.
    void
    setElevatorDistance(double distance)
    Set the target position of the elevator motors to a distance from the back of the robot.
    void
    setElevatorPower(double power)
    Set the power of the elevator motors.
    void
    setElevatorVelocity(int velocity)
    Set the velocity of the elevator motors in ticks per second.
    void
    setPivotAngle(org.firstinspires.ftc.robotcore.external.navigation.AngleUnit unit, double angle)
    Set the target position of the pivot motors to an angle.
    void
    setPivotPower(double power)
    Set the power of the pivot motors.
    void
    setPivotVelocity(int velocity)
    Set the velocity of the pivot motors in ticks per second.
    void
    Called by robot.update().
  • Method Details

    • setPivotAngle

      void setPivotAngle(org.firstinspires.ftc.robotcore.external.navigation.AngleUnit unit, double angle)
      Set the target position of the pivot motors to an angle. Safety limits apply.
      Parameters:
      unit - See AngleUnit.
      angle - in the AngleUnit you set
    • setPivotPower

      void setPivotPower(double power)
      Set the power of the pivot motors. Important when setting an angle - this works like setPower() does on a normal motor in RUN_TO_POSITION mode. This does not actually set power anymore - this sets the velocity to the max. velocity multiplied by your requested power.
      Parameters:
      power - from -1 to 1 just like setPower() on a normal motor
    • getPivotPower

      double getPivotPower()
      Get the current average power of the pivot motors.
    • setPivotVelocity

      void setPivotVelocity(int velocity)
      Set the velocity of the pivot motors in ticks per second.
      Parameters:
      velocity - The velocity to set, in ticks per second
    • getPivotVelocity

      double getPivotVelocity()
      Get the current average velocity of the pivot motors.
    • getPivotPosition

      int getPivotPosition()
      Get the current average position of the pivot motors.
    • setElevatorDistance

      void setElevatorDistance(double distance)
      Set the target position of the elevator motors to a distance from the back of the robot.
      Parameters:
      distance - in inches
    • setElevatorPower

      void setElevatorPower(double power)
      Set the power of the elevator motors. Important when setting a distance - this works like setPower() does on a normal motor in RUN_TO_POSITION mode.
      Parameters:
      power - from -1 to 1, just like setPower() on a normal motor
    • getElevatorPower

      double getElevatorPower()
      Get the current average power of the elevator motors.
    • setElevatorVelocity

      void setElevatorVelocity(int velocity)
      Set the velocity of the elevator motors in ticks per second.
      Parameters:
      velocity - The velocity to set, in ticks per second
    • getElevatorVelocity

      double getElevatorVelocity()
      Get the current average velocity of the elevator motors.
    • getElevatorPosition

      int getElevatorPosition()
      Get the current average position of the elevator motors.
    • update

      void update()
      Called by robot.update(). You do not need to call this method.