Interface RRMecanumDrive

All Known Implementing Classes:
MecanumDriveBlank, RRMecanumDriveImpl

public interface RRMecanumDrive
A port of RoadRunner Quickstart's SampleMecanumDrive to our new architecture. Learn more at learnroadrunner.com.
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Interface
    Description
    static class 
    See the RoadRunner Quickstart's DriveConstants class.
    static class 
    Contains motor names and settings - usually part of a set of Robot parameters.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint
     
    static final com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint
     
  • Method Summary

    Modifier and Type
    Method
    Description
    void
    Apply motor powers from a DTS (Drive-Turn-Strafe).
    void
    followTrajectory(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
    Blocking method to follow a trajectory created by TrajectoryBuilder (NOT TrajectorySequenceBuilder).
    void
    followTrajectoryAsync(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
    Asynchronously follows a trajectory created by TrajectoryBuilder (NOT TrajectorySequenceBuilder).
    void
    Blocking method to follow a trajectory created by TrajectorySequenceBuilder.
    void
    Asynchronously follows a trajectory created by TrajectorySequenceBuilder.
    com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint
    getAccelerationConstraint(double maxAccel)
     
    Use your robot's FriendlyIMU instead.
    com.acmerobotics.roadrunner.geometry.Pose2d
     
    com.qualcomm.robotcore.hardware.DcMotorEx
    Get the leftBack motor, if direct access is needed
    com.qualcomm.robotcore.hardware.DcMotorEx
    Get the leftFront motor, if direct access is needed
    com.acmerobotics.roadrunner.geometry.Pose2d
     
    double
    Use your robot's FriendlyIMU instead.
    com.qualcomm.robotcore.hardware.DcMotorEx
    Get the rightBack motor, if direct access is needed
    com.qualcomm.robotcore.hardware.DcMotorEx
    Get the rightFront motor, if direct access is needed
    com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint
    getVelocityConstraint(double maxVel, double maxAngularVel, double trackWidth)
     
     
     
    boolean
    Is RoadRunner doing something right now?
    void
    Please use applyDTS() instead.
    void
     
    void
    setMode(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode)
    The usual DcMotor method, but applied to all four motors.
    void
    setMotorPowers(double v, double v1, double v2, double v3)
    Please use applyDTS() instead.
    void
    setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode, com.qualcomm.robotcore.hardware.PIDFCoefficients coefficients)
     
    void
    setPoseEstimate(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
     
    void
    setWeightedDrivePower(com.acmerobotics.roadrunner.geometry.Pose2d drivePower)
    Please use applyDTS() instead.
    void
    setZeroPowerBehavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior behavior)
    The usual DcMotor method, but applied to all four motors.
    com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
    trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
    We'll usually use TrajectorySequenceBuilder.
    com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
    trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, boolean reversed)
    We'll usually use TrajectorySequenceBuilder.
    com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder
    trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, double startHeading)
    We'll usually use TrajectorySequenceBuilder.
    trajectorySequenceBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
    Learn more at https://learnroadrunner.com/trajectory-sequence.html.
    void
    turn(double angle)
     
    void
    turnAsync(double angle)
     
    void
    Called by robot.update().
    void
     
    void
    A poorly named RoadRunner update method that only updates RR stuff (like async(?) trajectory following) when the OpMode thread is active.
  • Field Details

    • VEL_CONSTRAINT

      static final com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint VEL_CONSTRAINT
    • ACCEL_CONSTRAINT

      static final com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint ACCEL_CONSTRAINT
  • Method Details

    • getLeftFrontMotor

      com.qualcomm.robotcore.hardware.DcMotorEx getLeftFrontMotor()
      Get the leftFront motor, if direct access is needed
    • getRightFrontMotor

      com.qualcomm.robotcore.hardware.DcMotorEx getRightFrontMotor()
      Get the rightFront motor, if direct access is needed
    • getLeftBackMotor

      com.qualcomm.robotcore.hardware.DcMotorEx getLeftBackMotor()
      Get the leftBack motor, if direct access is needed
    • getRightBackMotor

      com.qualcomm.robotcore.hardware.DcMotorEx getRightBackMotor()
      Get the rightBack motor, if direct access is needed
    • applyDTS

      void applyDTS(DTS dts)
      Apply motor powers from a DTS (Drive-Turn-Strafe).
      Parameters:
      dts - The DTS to apply. Normalize it before passing it in for desirable behavior.
    • setMode

      void setMode(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode)
      The usual DcMotor method, but applied to all four motors.
      Parameters:
      runMode - The RunMode to set
    • setZeroPowerBehavior

      void setZeroPowerBehavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior behavior)
      The usual DcMotor method, but applied to all four motors.
      Parameters:
      behavior - The ZeroPowerBehavior to set
    • update

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

      com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
      We'll usually use TrajectorySequenceBuilder. Learn more about TrajectoryBuilder at https://learnroadrunner.com/trajectories.html#building-a-trajectory.
    • trajectoryBuilder

      com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, boolean reversed)
      We'll usually use TrajectorySequenceBuilder. Learn more about TrajectoryBuilder at https://learnroadrunner.com/trajectories.html#building-a-trajectory.
    • trajectoryBuilder

      com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, double startHeading)
      We'll usually use TrajectorySequenceBuilder. Learn more about TrajectoryBuilder at https://learnroadrunner.com/trajectories.html#building-a-trajectory.
    • trajectorySequenceBuilder

      TrajectorySequenceBuilder trajectorySequenceBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
      Learn more at https://learnroadrunner.com/trajectory-sequence.html.
    • turnAsync

      void turnAsync(double angle)
    • turn

      void turn(double angle)
    • followTrajectoryAsync

      void followTrajectoryAsync(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
      Asynchronously follows a trajectory created by TrajectoryBuilder (NOT TrajectorySequenceBuilder).
    • followTrajectory

      void followTrajectory(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
      Blocking method to follow a trajectory created by TrajectoryBuilder (NOT TrajectorySequenceBuilder).
    • followTrajectorySequenceAsync

      void followTrajectorySequenceAsync(TrajectorySequence trajectorySequence)
      Asynchronously follows a trajectory created by TrajectorySequenceBuilder.
    • followTrajectorySequence

      void followTrajectorySequence(TrajectorySequence trajectorySequence)
      Blocking method to follow a trajectory created by TrajectorySequenceBuilder.
    • getLastError

      com.acmerobotics.roadrunner.geometry.Pose2d getLastError()
    • waitForIdle

      void waitForIdle()
      A poorly named RoadRunner update method that only updates RR stuff (like async(?) trajectory following) when the OpMode thread is active.
    • isBusy

      boolean isBusy()
      Is RoadRunner doing something right now?
    • setPIDFCoefficients

      void setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode, com.qualcomm.robotcore.hardware.PIDFCoefficients coefficients)
    • setWeightedDrivePower

      void setWeightedDrivePower(com.acmerobotics.roadrunner.geometry.Pose2d drivePower)
      Please use applyDTS() instead. This only exists for compatibility with stuff written for SampleMecanumDrive.
    • getWheelPositions

      @NonNull List<Double> getWheelPositions()
    • getWheelVelocities

      List<Double> getWheelVelocities()
    • setMotorPowers

      void setMotorPowers(double v, double v1, double v2, double v3)
      Please use applyDTS() instead. This only exists for compatibility with stuff written for SampleMecanumDrive.
    • getRawExternalHeading

      double getRawExternalHeading()
      Use your robot's FriendlyIMU instead. This exists only to match SampleMecanumDrive.
    • getExternalHeadingVelocity

      Double getExternalHeadingVelocity()
      Use your robot's FriendlyIMU instead. This exists only to match SampleMecanumDrive.
    • getVelocityConstraint

      com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint getVelocityConstraint(double maxVel, double maxAngularVel, double trackWidth)
    • getAccelerationConstraint

      com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint getAccelerationConstraint(double maxAccel)
    • setDrivePower

      void setDrivePower()
      Please use applyDTS() instead. This only exists for compatibility with stuff written for RoadRunner's MecanumDrive.
    • setDriveSignal

      void setDriveSignal()
    • updatePoseEstimate

      void updatePoseEstimate()
    • getPoseEstimate

      com.acmerobotics.roadrunner.geometry.Pose2d getPoseEstimate()
    • setPoseEstimate

      void setPoseEstimate(com.acmerobotics.roadrunner.geometry.Pose2d startPose)