mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[commands] Revert SubsystemBase deprecation/removal (#5634)
This commit is contained in:
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.subsystem2;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class ReplaceMeSubsystem extends Subsystem {
|
||||
public class ReplaceMeSubsystem extends SubsystemBase {
|
||||
/** Creates a new ReplaceMeSubsystem. */
|
||||
public ReplaceMeSubsystem() {}
|
||||
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final ExampleSmartMotorController m_leftLeader =
|
||||
new ExampleSmartMotorController(DriveConstants.kLeftMotor1Port);
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -8,13 +8,13 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Constants.ClawConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Victor;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* The claw subsystem is a simple system with a motor for opening and closing. If using stronger
|
||||
* motors, you should probably use a sensor so that the motors don't stall.
|
||||
*/
|
||||
public class Claw extends Subsystem {
|
||||
public class Claw extends SubsystemBase {
|
||||
private final Victor m_motor = new Victor(ClawConstants.kMotorPort);
|
||||
private final DigitalInput m_contact = new DigitalInput(ClawConstants.kContactPort);
|
||||
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
/**
|
||||
* The Drivetrain subsystem incorporates the sensors and actuators attached to the robots chassis.
|
||||
* These include four drive motors, a left and right encoder and a gyro.
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -12,10 +12,10 @@ import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
private final PWMSparkMax m_frontLeft = new PWMSparkMax(DriveConstants.kFrontLeftMotorPort);
|
||||
private final PWMSparkMax m_rearLeft = new PWMSparkMax(DriveConstants.kRearLeftMotorPort);
|
||||
private final PWMSparkMax m_frontRight = new PWMSparkMax(DriveConstants.kFrontRightMotorPort);
|
||||
|
||||
@@ -13,9 +13,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,10 +10,10 @@ import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConsta
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class Drive extends Subsystem {
|
||||
public class Drive extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Intake extends Subsystem {
|
||||
public class Intake extends SubsystemBase {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
|
||||
|
||||
// Double solenoid connected to two channels of a PCM with the default CAN ID
|
||||
|
||||
@@ -9,10 +9,10 @@ import edu.wpi.first.wpilibj.Compressor;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** Subsystem for managing the compressor, pressure sensor, etc. */
|
||||
public class Pneumatics extends Subsystem {
|
||||
public class Pneumatics extends SubsystemBase {
|
||||
// External analog pressure sensor
|
||||
// product-specific voltage->pressure conversion, see product manual
|
||||
// in this case, 250(V/5)-25
|
||||
|
||||
@@ -13,9 +13,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Shooter extends Subsystem {
|
||||
public class Shooter extends SubsystemBase {
|
||||
private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort);
|
||||
private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort);
|
||||
private final Encoder m_shooterEncoder =
|
||||
|
||||
@@ -9,9 +9,9 @@ import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.Stor
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Storage extends Subsystem {
|
||||
public class Storage extends SubsystemBase {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort);
|
||||
private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort);
|
||||
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.romireference.sensors.RomiGyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the Romi reference robot. This includes the pushbuttons
|
||||
@@ -17,7 +17,7 @@ import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
* <p>DIO 0 - Button A (input only) DIO 1 - Button B (input) or Green LED (output) DIO 2 - Button C
|
||||
* (input) or Red LED (output) DIO 3 - Yellow LED (output only)
|
||||
*/
|
||||
public class OnBoardIO extends Subsystem {
|
||||
public class OnBoardIO extends SubsystemBase {
|
||||
private final DigitalInput m_buttonA = new DigitalInput(0);
|
||||
private final DigitalOutput m_yellowLed = new DigitalOutput(3);
|
||||
|
||||
|
||||
@@ -22,9 +22,9 @@ import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -12,9 +12,9 @@ import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// Robot swerve modules
|
||||
private final SwerveModule m_frontLeft =
|
||||
new SwerveModule(
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.xrpreference.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.devices.XRPServo;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Arm extends Subsystem {
|
||||
public class Arm extends SubsystemBase {
|
||||
private final XRPServo m_armServo;
|
||||
|
||||
/** Creates a new Arm. */
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.devices.XRPMotor;
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.sensors.XRPGyro;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
private static final double kGearRatio =
|
||||
(30.0 / 14.0) * (28.0 / 16.0) * (36.0 / 9.0) * (26.0 / 8.0); // 48.75:1
|
||||
private static final double kCountsPerMotorShaftRev = 12.0;
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj.examples.xrpreference.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the XRP Reference Robot. This includes the USER
|
||||
* pushbutton and LED
|
||||
*/
|
||||
public class XRPOnBoardIO extends Subsystem {
|
||||
public class XRPOnBoardIO extends SubsystemBase {
|
||||
private final DigitalInput m_button = new DigitalInput(0);
|
||||
private final DigitalOutput m_led = new DigitalOutput(1);
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.templates.commandbased.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class ExampleSubsystem extends Subsystem {
|
||||
public class ExampleSubsystem extends SubsystemBase {
|
||||
/** Creates a new ExampleSubsystem. */
|
||||
public ExampleSubsystem() {}
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.templates.romicommandbased.subsystems;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class RomiDrivetrain extends Subsystem {
|
||||
public class RomiDrivetrain extends SubsystemBase {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.templates.xrpcommandbased.subsystems;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.templates.xrpcommandbased.devices.XRPMotor;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class XRPDrivetrain extends Subsystem {
|
||||
public class XRPDrivetrain extends SubsystemBase {
|
||||
private static final double kGearRatio =
|
||||
(30.0 / 14.0) * (28.0 / 16.0) * (36.0 / 9.0) * (26.0 / 8.0); // 48.75:1
|
||||
private static final double kCountsPerMotorShaftRev = 12.0;
|
||||
|
||||
Reference in New Issue
Block a user