public class SampleMecanumDrive
extends com.acmerobotics.roadrunner.drive.MecanumDrive
Modifier and Type | Class and Description |
---|---|
static class |
SampleMecanumDrive.Mode |
Modifier and Type | Field and Description |
---|---|
private com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint |
accelConstraint |
private com.qualcomm.robotcore.hardware.VoltageSensor |
batteryVoltageSensor |
private com.acmerobotics.roadrunner.util.NanoClock |
clock |
private com.acmerobotics.dashboard.FtcDashboard |
dashboard |
private com.acmerobotics.roadrunner.followers.TrajectoryFollower |
follower |
static com.acmerobotics.roadrunner.control.PIDCoefficients |
HEADING_PID |
private com.qualcomm.hardware.bosch.BNO055IMU |
imu |
private com.acmerobotics.roadrunner.geometry.Pose2d |
lastPoseOnTurn |
static double |
LATERAL_MULTIPLIER |
private com.qualcomm.robotcore.hardware.DcMotorEx |
leftFront |
private com.qualcomm.robotcore.hardware.DcMotorEx |
leftRear |
private SampleMecanumDrive.Mode |
mode |
private java.util.List<com.qualcomm.robotcore.hardware.DcMotorEx> |
motors |
static double |
OMEGA_WEIGHT |
static int |
POSE_HISTORY_LIMIT |
private java.util.LinkedList<com.acmerobotics.roadrunner.geometry.Pose2d> |
poseHistory |
private com.qualcomm.robotcore.hardware.DcMotorEx |
rightFront |
private com.qualcomm.robotcore.hardware.DcMotorEx |
rightRear |
static com.acmerobotics.roadrunner.control.PIDCoefficients |
TRANSLATIONAL_PID |
private com.acmerobotics.roadrunner.control.PIDFController |
turnController |
private com.acmerobotics.roadrunner.profile.MotionProfile |
turnProfile |
private double |
turnStart |
private com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint |
velConstraint |
static double |
VX_WEIGHT |
static double |
VY_WEIGHT |
Constructor and Description |
---|
SampleMecanumDrive(com.qualcomm.robotcore.hardware.HardwareMap hardwareMap) |
Modifier and Type | Method and Description |
---|---|
void |
followTrajectory(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory) |
void |
followTrajectoryAsync(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory) |
com.acmerobotics.roadrunner.geometry.Pose2d |
getLastError() |
double |
getRawExternalHeading() |
java.util.List<java.lang.Double> |
getWheelPositions() |
java.util.List<java.lang.Double> |
getWheelVelocities() |
boolean |
isBusy() |
void |
setMode(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode) |
void |
setMotorPowers(double v,
double v1,
double v2,
double v3) |
void |
setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode,
com.qualcomm.robotcore.hardware.PIDFCoefficients coefficients) |
void |
setWeightedDrivePower(com.acmerobotics.roadrunner.geometry.Pose2d drivePower) |
void |
setZeroPowerBehavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior zeroPowerBehavior) |
com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder |
trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose) |
com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder |
trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose,
boolean reversed) |
com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder |
trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose,
double startHeading) |
void |
turn(double angle) |
void |
turnAsync(double angle) |
void |
update() |
void |
waitForIdle() |
getLocalizer, setDrivePower, setDriveSignal, setLocalizer
public static com.acmerobotics.roadrunner.control.PIDCoefficients TRANSLATIONAL_PID
public static com.acmerobotics.roadrunner.control.PIDCoefficients HEADING_PID
public static double LATERAL_MULTIPLIER
public static double VX_WEIGHT
public static double VY_WEIGHT
public static double OMEGA_WEIGHT
public static int POSE_HISTORY_LIMIT
private com.acmerobotics.dashboard.FtcDashboard dashboard
private com.acmerobotics.roadrunner.util.NanoClock clock
private SampleMecanumDrive.Mode mode
private com.acmerobotics.roadrunner.control.PIDFController turnController
private com.acmerobotics.roadrunner.profile.MotionProfile turnProfile
private double turnStart
private com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint velConstraint
private com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAccelerationConstraint accelConstraint
private com.acmerobotics.roadrunner.followers.TrajectoryFollower follower
private java.util.LinkedList<com.acmerobotics.roadrunner.geometry.Pose2d> poseHistory
private com.qualcomm.robotcore.hardware.DcMotorEx leftFront
private com.qualcomm.robotcore.hardware.DcMotorEx leftRear
private com.qualcomm.robotcore.hardware.DcMotorEx rightRear
private com.qualcomm.robotcore.hardware.DcMotorEx rightFront
private java.util.List<com.qualcomm.robotcore.hardware.DcMotorEx> motors
private com.qualcomm.hardware.bosch.BNO055IMU imu
private com.qualcomm.robotcore.hardware.VoltageSensor batteryVoltageSensor
private com.acmerobotics.roadrunner.geometry.Pose2d lastPoseOnTurn
public SampleMecanumDrive(com.qualcomm.robotcore.hardware.HardwareMap hardwareMap)
public com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose)
public com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, boolean reversed)
public com.acmerobotics.roadrunner.trajectory.TrajectoryBuilder trajectoryBuilder(com.acmerobotics.roadrunner.geometry.Pose2d startPose, double startHeading)
public void turnAsync(double angle)
public void turn(double angle)
public void followTrajectoryAsync(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
public void followTrajectory(com.acmerobotics.roadrunner.trajectory.Trajectory trajectory)
public com.acmerobotics.roadrunner.geometry.Pose2d getLastError()
public void update()
public void waitForIdle()
public boolean isBusy()
public void setMode(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode)
public void setZeroPowerBehavior(com.qualcomm.robotcore.hardware.DcMotor.ZeroPowerBehavior zeroPowerBehavior)
public void setPIDFCoefficients(com.qualcomm.robotcore.hardware.DcMotor.RunMode runMode, com.qualcomm.robotcore.hardware.PIDFCoefficients coefficients)
public void setWeightedDrivePower(com.acmerobotics.roadrunner.geometry.Pose2d drivePower)
@NonNull public java.util.List<java.lang.Double> getWheelPositions()
getWheelPositions
in class com.acmerobotics.roadrunner.drive.MecanumDrive
public java.util.List<java.lang.Double> getWheelVelocities()
getWheelVelocities
in class com.acmerobotics.roadrunner.drive.MecanumDrive
public void setMotorPowers(double v, double v1, double v2, double v3)
setMotorPowers
in class com.acmerobotics.roadrunner.drive.MecanumDrive
public double getRawExternalHeading()
getRawExternalHeading
in class com.acmerobotics.roadrunner.drive.Drive