[wpilib] Add functional interface equivalents to MotorController (#6053)

This does not deprecate any current functionality, but prepares the way for future deprecation.

The drive classes now accept void(double) functions, which makes them more flexible.

The C++ API ended up a bit more verbose, but the Java API is really concise with method references, which is >80% of our userbase. For example:

`DifferentialDrive drive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);`

Lambdas can be passed to interoperate with vendor motor controller APIs that don't have e.g., set(double), so CTRE doesn't have to maintain their WPI_ classes anymore.

MotorControllerGroup was replaced with PWMMotorController.addFollower() for PWM motor controllers. Users of CAN motor controllers should use their vendor's follower functionality.
This commit is contained in:
Tyler Veness
2024-01-01 13:37:51 -08:00
committed by GitHub
parent 8aca706217
commit e7c9f27683
132 changed files with 1159 additions and 697 deletions

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.arcadedrive;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -16,9 +17,15 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final Joystick m_stick = new Joystick(0);
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override
public void robotInit() {
// We need to invert one side of the drivetrain so that positive voltages

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.arcadedrivexboxcontroller;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -16,9 +17,15 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final XboxController m_driverController = new XboxController(0);
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override
public void robotInit() {
// We need to invert one side of the drivetrain so that positive voltages

View File

@@ -4,28 +4,25 @@
package edu.wpi.first.wpilibj.examples.armbot.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -43,14 +40,20 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
}
/**

View File

@@ -4,14 +4,12 @@
package edu.wpi.first.wpilibj.examples.armbotoffboard;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A simplified stub class that simulates the API of a common "smart" motor controller.
*
* <p>Has no actual functionality.
*/
public class ExampleSmartMotorController implements MotorController {
public class ExampleSmartMotorController {
public enum PIDMode {
kPosition,
kVelocity,
@@ -72,25 +70,19 @@ public class ExampleSmartMotorController implements MotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
@Override
public void set(double speed) {}
@Override
public double get() {
return 0;
}
@Override
public void setInverted(boolean isInverted) {}
@Override
public boolean getInverted() {
return false;
}
@Override
public void disable() {}
@Override
public void stopMotor() {}
}

View File

@@ -4,10 +4,10 @@
package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants;
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;
@@ -16,19 +16,16 @@ import java.util.function.DoubleSupplier;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -46,14 +43,20 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
}
/**

View File

@@ -12,8 +12,6 @@ import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a differential drive style drivetrain. */
@@ -25,19 +23,14 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final MotorController m_leftLeader = new PWMSparkMax(1);
private final MotorController m_leftFollower = new PWMSparkMax(2);
private final MotorController m_rightLeader = new PWMSparkMax(3);
private final MotorController m_rightFollower = new PWMSparkMax(4);
private final PWMSparkMax m_leftLeader = new PWMSparkMax(1);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(2);
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(4);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final MotorControllerGroup m_leftGroup =
new MotorControllerGroup(m_leftLeader, m_leftFollower);
private final MotorControllerGroup m_rightGroup =
new MotorControllerGroup(m_rightLeader, m_rightFollower);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
@@ -58,10 +51,13 @@ public class Drivetrain {
public Drivetrain() {
m_gyro.reset();
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightGroup.setInverted(true);
m_rightLeader.setInverted(true);
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
@@ -90,8 +86,8 @@ public class Drivetrain {
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
final double rightOutput =
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
/**

View File

@@ -30,8 +30,6 @@ import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.Timer;
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.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
@@ -48,19 +46,14 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final MotorController m_leftLeader = new PWMSparkMax(1);
private final MotorController m_leftFollower = new PWMSparkMax(2);
private final MotorController m_rightLeader = new PWMSparkMax(3);
private final MotorController m_rightFollower = new PWMSparkMax(4);
private final PWMSparkMax m_leftLeader = new PWMSparkMax(1);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(2);
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(4);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final MotorControllerGroup m_leftGroup =
new MotorControllerGroup(m_leftLeader, m_leftFollower);
private final MotorControllerGroup m_rightGroup =
new MotorControllerGroup(m_rightLeader, m_rightFollower);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
@@ -113,10 +106,13 @@ public class Drivetrain {
public Drivetrain(DoubleArrayTopic cameraToObjectTopic) {
m_gyro.reset();
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightGroup.setInverted(true);
m_rightLeader.setInverted(true);
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
@@ -148,8 +144,8 @@ public class Drivetrain {
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
final double rightOutput =
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
/**
@@ -251,8 +247,8 @@ public class Drivetrain {
// simulation, and write the simulated positions and velocities to our
// simulated encoder and gyro.
m_drivetrainSimulator.setInputs(
m_leftGroup.get() * RobotController.getInputVoltage(),
m_rightGroup.get() * RobotController.getInputVoltage());
m_leftLeader.get() * RobotController.getInputVoltage(),
m_rightLeader.get() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());

View File

@@ -4,14 +4,12 @@
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A simplified stub class that simulates the API of a common "smart" motor controller.
*
* <p>Has no actual functionality.
*/
public class ExampleSmartMotorController implements MotorController {
public class ExampleSmartMotorController {
public enum PIDMode {
kPosition,
kVelocity,
@@ -74,27 +72,21 @@ public class ExampleSmartMotorController implements MotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
@Override
public void set(double speed) {
m_value = speed;
}
@Override
public double get() {
return m_value;
}
@Override
public void setInverted(boolean isInverted) {}
@Override
public boolean getInverted() {
return false;
}
@Override
public void disable() {}
@Override
public void stopMotor() {}
}

View File

@@ -6,6 +6,7 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
@@ -34,20 +35,19 @@ public class DriveSubsystem extends SubsystemBase {
DriveConstants.kaVoltSecondsSquaredPerMeter);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftLeader, m_rightLeader);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightLeader.setInverted(true);
// You might need to not do this depending on the specific motor controller
// that you are using -- contact the respective vendor's documentation for
// more details.
m_rightFollower.setInverted(true);
m_leftFollower.follow(m_leftLeader);
m_rightFollower.follow(m_rightLeader);

View File

@@ -4,14 +4,12 @@
package edu.wpi.first.wpilibj.examples.elevatorexponentialprofile;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A simplified stub class that simulates the API of a common "smart" motor controller.
*
* <p>Has no actual functionality.
*/
public class ExampleSmartMotorController implements MotorController {
public class ExampleSmartMotorController {
public enum PIDMode {
kPosition,
kVelocity,
@@ -72,25 +70,19 @@ public class ExampleSmartMotorController implements MotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
@Override
public void set(double speed) {}
@Override
public double get() {
return 0;
}
@Override
public void setInverted(boolean isInverted) {}
@Override
public boolean getInverted() {
return false;
}
@Override
public void disable() {}
@Override
public void stopMotor() {}
}

View File

@@ -10,7 +10,6 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@SuppressWarnings("PMD.RedundantFieldInitializer")
@@ -27,7 +26,7 @@ public class Robot extends TimedRobot {
private final Joystick m_joystick = new Joystick(1);
private final Encoder m_encoder = new Encoder(1, 2);
private final MotorController m_motor = new PWMSparkMax(1);
private final PWMSparkMax m_motor = new PWMSparkMax(1);
// Create a PID controller whose setpoint's change is subject to maximum
// velocity and acceleration constraints.

View File

@@ -4,14 +4,12 @@
package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
/**
* A simplified stub class that simulates the API of a common "smart" motor controller.
*
* <p>Has no actual functionality.
*/
public class ExampleSmartMotorController implements MotorController {
public class ExampleSmartMotorController {
public enum PIDMode {
kPosition,
kVelocity,
@@ -72,25 +70,19 @@ public class ExampleSmartMotorController implements MotorController {
/** Resets the encoder to zero distance. */
public void resetEncoder() {}
@Override
public void set(double speed) {}
@Override
public double get() {
return 0;
}
@Override
public void setInverted(boolean isInverted) {}
@Override
public boolean getInverted() {
return false;
}
@Override
public void disable() {}
@Override
public void stopMotor() {}
}

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Ultrasonic;
import edu.wpi.first.wpilibj.event.BooleanEvent;
import edu.wpi.first.wpilibj.event.EventLoop;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
@@ -20,15 +19,15 @@ public class Robot extends TimedRobot {
public static final int TOLERANCE = 8; // rpm
public static final int KICKER_THRESHOLD = 15; // mm
private final MotorController m_shooter = new PWMSparkMax(0);
private final PWMSparkMax m_shooter = new PWMSparkMax(0);
private final Encoder m_shooterEncoder = new Encoder(0, 1);
private final PIDController m_controller = new PIDController(0.3, 0, 0);
private final SimpleMotorFeedforward m_ff = new SimpleMotorFeedforward(0.1, 0.065);
private final MotorController m_kicker = new PWMSparkMax(1);
private final PWMSparkMax m_kicker = new PWMSparkMax(1);
private final Ultrasonic m_kickerSensor = new Ultrasonic(2, 3);
private final MotorController m_intake = new PWMSparkMax(2);
private final PWMSparkMax m_intake = new PWMSparkMax(2);
private final EventLoop m_loop = new EventLoop();
private final Joystick m_joystick = new Joystick(0);

View File

@@ -4,28 +4,25 @@
package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -43,10 +40,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -4,34 +4,27 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.gearsbot.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
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.SubsystemBase;
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.
*/
private final MotorController m_leftMotor =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotorPort1),
new PWMSparkMax(DriveConstants.kLeftMotorPort1));
// 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.
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotorPort1);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotorPort2);
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotorPort1);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotorPort2);
private final MotorController m_rightMotor =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotorPort2),
new PWMSparkMax(DriveConstants.kLeftMotorPort2));
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
private final Encoder m_leftEncoder =
new Encoder(
@@ -50,10 +43,16 @@ public class Drivetrain extends SubsystemBase {
public Drivetrain() {
super();
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotor.setInverted(true);
m_rightLeader.setInverted(true);
// Encoders may measure differently in the real world and in
// simulation. In this example the robot moves 0.042 barleycorns

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.gettingstarted;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
@@ -19,10 +20,16 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
}
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.gyro;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
@@ -30,10 +31,16 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort);
private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort);
private final DifferentialDrive m_myRobot = new DifferentialDrive(m_leftDrive, m_rightDrive);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftDrive::set, m_rightDrive::set);
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
private final Joystick m_joystick = new Joystick(kJoystickPort);
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
}
@Override
public void robotInit() {
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
@@ -50,6 +57,6 @@ public class Robot extends TimedRobot {
@Override
public void teleopPeriodic() {
double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP;
m_myRobot.arcadeDrive(-m_joystick.getY(), -turningValue);
m_robotDrive.arcadeDrive(-m_joystick.getY(), -turningValue);
}
}

View File

@@ -4,29 +4,26 @@
package edu.wpi.first.wpilibj.examples.gyrodrivecommands.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -47,10 +44,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.gyromecanum;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
@@ -37,12 +38,17 @@ public class Robot extends TimedRobot {
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
// Invert the right side motors.
// You may need to change or remove this to match your robot.
frontRight.setInverted(true);
rearRight.setInverted(true);
m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set);
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
}

View File

@@ -5,28 +5,25 @@
package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -44,10 +41,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -5,28 +5,25 @@
package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -44,10 +41,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -14,7 +14,6 @@ import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a mecanum drive style drivetrain. */
@@ -22,10 +21,10 @@ public class Drivetrain {
public static final double kMaxSpeed = 3.0; // 3 meters per second
public static final double kMaxAngularSpeed = Math.PI; // 1/2 rotation per second
private final MotorController m_frontLeftMotor = new PWMSparkMax(1);
private final MotorController m_frontRightMotor = new PWMSparkMax(2);
private final MotorController m_backLeftMotor = new PWMSparkMax(3);
private final MotorController m_backRightMotor = new PWMSparkMax(4);
private final PWMSparkMax m_frontLeftMotor = new PWMSparkMax(1);
private final PWMSparkMax m_frontRightMotor = new PWMSparkMax(2);
private final PWMSparkMax m_backLeftMotor = new PWMSparkMax(3);
private final PWMSparkMax m_backRightMotor = new PWMSparkMax(4);
private final Encoder m_frontLeftEncoder = new Encoder(0, 1);
private final Encoder m_frontRightEncoder = new Encoder(2, 3);

View File

@@ -9,6 +9,7 @@ import edu.wpi.first.math.kinematics.MecanumDriveMotorVoltages;
import edu.wpi.first.math.kinematics.MecanumDriveOdometry;
import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions;
import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
@@ -23,7 +24,7 @@ public class DriveSubsystem extends SubsystemBase {
private final PWMSparkMax m_rearRight = new PWMSparkMax(DriveConstants.kRearRightMotorPort);
private final MecanumDrive m_drive =
new MecanumDrive(m_frontLeft, m_rearLeft, m_frontRight, m_rearRight);
new MecanumDrive(m_frontLeft::set, m_rearLeft::set, m_frontRight::set, m_rearRight::set);
// The front-left-side drive encoder
private final Encoder m_frontLeftEncoder =
@@ -65,6 +66,11 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_frontLeft);
SendableRegistry.addChild(m_drive, m_rearLeft);
SendableRegistry.addChild(m_drive, m_frontRight);
SendableRegistry.addChild(m_drive, m_rearRight);
// Sets the distance per pulse for the encoders
m_frontLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
m_rearLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.mecanumdrive;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
@@ -28,12 +29,17 @@ public class Robot extends TimedRobot {
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
// Invert the right side motors.
// You may need to change or remove this to match your robot.
frontRight.setInverted(true);
rearRight.setInverted(true);
m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set);
m_stick = new Joystick(kJoystickChannel);
}

View File

@@ -18,7 +18,6 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a mecanum drive style drivetrain. */
@@ -26,10 +25,10 @@ public class Drivetrain {
public static final double kMaxSpeed = 3.0; // 3 meters per second
public static final double kMaxAngularSpeed = Math.PI; // 1/2 rotation per second
private final MotorController m_frontLeftMotor = new PWMSparkMax(1);
private final MotorController m_frontRightMotor = new PWMSparkMax(2);
private final MotorController m_backLeftMotor = new PWMSparkMax(3);
private final MotorController m_backRightMotor = new PWMSparkMax(4);
private final PWMSparkMax m_frontLeftMotor = new PWMSparkMax(1);
private final PWMSparkMax m_frontRightMotor = new PWMSparkMax(2);
private final PWMSparkMax m_backLeftMotor = new PWMSparkMax(3);
private final PWMSparkMax m_backRightMotor = new PWMSparkMax(4);
private final Encoder m_frontLeftEncoder = new Encoder(0, 1);
private final Encoder m_frontRightEncoder = new Encoder(2, 3);

View File

@@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj.examples.motorcontrol;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
@@ -27,7 +26,7 @@ public class Robot extends TimedRobot {
private static final int kEncoderPortA = 0;
private static final int kEncoderPortB = 1;
private MotorController m_motor;
private PWMSparkMax m_motor;
private Joystick m_joystick;
private Encoder m_encoder;

View File

@@ -7,29 +7,26 @@ package edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -53,10 +50,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
@@ -121,8 +124,8 @@ public class DriveSubsystem extends SubsystemBase {
* @param rightVolts the commanded right output
*/
public void tankDriveVolts(double leftVolts, double rightVolts) {
m_leftMotors.setVoltage(leftVolts);
m_rightMotors.setVoltage(rightVolts);
m_leftLeader.setVoltage(leftVolts);
m_rightLeader.setVoltage(rightVolts);
m_drive.feed();
}

View File

@@ -13,8 +13,6 @@ import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a differential drive style drivetrain. */
@@ -26,19 +24,14 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final MotorController m_leftLeader = new PWMSparkMax(1);
private final MotorController m_leftFollower = new PWMSparkMax(2);
private final MotorController m_rightLeader = new PWMSparkMax(3);
private final MotorController m_rightFollower = new PWMSparkMax(4);
private final PWMSparkMax m_leftLeader = new PWMSparkMax(1);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(2);
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(4);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final MotorControllerGroup m_leftGroup =
new MotorControllerGroup(m_leftLeader, m_leftFollower);
private final MotorControllerGroup m_rightGroup =
new MotorControllerGroup(m_rightLeader, m_rightFollower);
private final AnalogGyro m_gyro = new AnalogGyro(0);
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
@@ -59,10 +52,13 @@ public class Drivetrain {
public Drivetrain() {
m_gyro.reset();
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightGroup.setInverted(true);
m_rightLeader.setInverted(true);
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
@@ -91,8 +87,8 @@ public class Drivetrain {
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
final double rightOutput =
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
/**

View File

@@ -4,10 +4,10 @@
package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants;
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.SubsystemBase;
@@ -15,19 +15,16 @@ import java.util.function.DoubleSupplier;
public class Drive extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -45,10 +42,16 @@ public class Drive extends SubsystemBase {
/** Creates a new Drive subsystem. */
public Drive() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.romireference.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.BuiltInAccelerometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -26,7 +27,8 @@ public class Drivetrain extends SubsystemBase {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
// Set up the RomiGyro
private final RomiGyro m_gyro = new RomiGyro();
@@ -36,6 +38,9 @@ public class Drivetrain extends SubsystemBase {
/** Creates a new Drivetrain. */
public Drivetrain() {
SendableRegistry.addChild(m_diffDrive, m_leftMotor);
SendableRegistry.addChild(m_diffDrive, m_rightMotor);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj.examples.shuffleboard;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.TimedRobot;
@@ -16,8 +17,10 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftDriveMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightDriveMotor = new PWMSparkMax(1);
private final DifferentialDrive m_tankDrive =
new DifferentialDrive(new PWMSparkMax(0), new PWMSparkMax(1));
new DifferentialDrive(m_leftDriveMotor::set, m_rightDriveMotor::set);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
@@ -27,6 +30,9 @@ public class Robot extends TimedRobot {
@Override
public void robotInit() {
SendableRegistry.addChild(m_tankDrive, m_leftDriveMotor);
SendableRegistry.addChild(m_tankDrive, m_rightDriveMotor);
// Add a 'max speed' widget to a tab named 'Configuration', using a number slider
// The widget will be placed in the second column and row and will be TWO columns wide
m_maxSpeed =

View File

@@ -18,7 +18,6 @@ import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
@@ -41,11 +40,6 @@ public class Drivetrain {
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(4);
private final MotorControllerGroup m_leftGroup =
new MotorControllerGroup(m_leftLeader, m_leftFollower);
private final MotorControllerGroup m_rightGroup =
new MotorControllerGroup(m_rightLeader, m_rightFollower);
private final Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
@@ -77,10 +71,13 @@ public class Drivetrain {
/** Subsystem constructor. */
public Drivetrain() {
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightGroup.setInverted(true);
m_rightLeader.setInverted(true);
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
@@ -91,7 +88,7 @@ public class Drivetrain {
m_leftEncoder.reset();
m_rightEncoder.reset();
m_rightGroup.setInverted(true);
m_rightLeader.setInverted(true);
SmartDashboard.putData("Field", m_fieldSim);
}
@@ -104,8 +101,8 @@ public class Drivetrain {
double rightOutput =
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
m_leftLeader.setVoltage(leftOutput + leftFeedforward);
m_rightLeader.setVoltage(rightOutput + rightFeedforward);
}
/**
@@ -145,8 +142,8 @@ public class Drivetrain {
// simulated encoder and gyro. We negate the right side so that positive
// voltages make the right side move forward.
m_drivetrainSimulator.setInputs(
m_leftGroup.get() * RobotController.getInputVoltage(),
m_rightGroup.get() * RobotController.getInputVoltage());
m_leftLeader.get() * RobotController.getInputVoltage(),
m_rightLeader.get() * RobotController.getInputVoltage());
m_drivetrainSimulator.update(0.02);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());

View File

@@ -19,7 +19,6 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
@@ -92,7 +91,7 @@ public class Robot extends TimedRobot {
// An encoder set up to measure arm position in radians.
private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -9,13 +9,13 @@ import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.Constants.DriveConstants;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
@@ -26,19 +26,16 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
// The motors on the right side of the drive.
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));
private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port);
// The robot's drive
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
private final DifferentialDrive m_drive =
new DifferentialDrive(m_leftLeader::set, m_rightLeader::set);
// The left-side drive encoder
private final Encoder m_leftEncoder =
@@ -70,10 +67,16 @@ public class DriveSubsystem extends SubsystemBase {
/** Creates a new DriveSubsystem. */
public DriveSubsystem() {
SendableRegistry.addChild(m_drive, m_leftLeader);
SendableRegistry.addChild(m_drive, m_rightLeader);
m_leftLeader.addFollower(m_leftFollower);
m_rightLeader.addFollower(m_rightFollower);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotors.setInverted(true);
m_rightLeader.setInverted(true);
// Sets the distance per pulse for the encoders
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
@@ -131,8 +134,8 @@ public class DriveSubsystem extends SubsystemBase {
// We negate the right side so that positive voltages make the right side
// move forward.
m_drivetrainSimulator.setInputs(
m_leftMotors.get() * RobotController.getBatteryVoltage(),
m_rightMotors.get() * RobotController.getBatteryVoltage());
m_leftLeader.get() * RobotController.getBatteryVoltage(),
m_rightLeader.get() * RobotController.getBatteryVoltage());
m_drivetrainSimulator.update(0.020);
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
@@ -202,8 +205,8 @@ public class DriveSubsystem extends SubsystemBase {
* @param rightVolts the commanded right output
*/
public void tankDriveVolts(double leftVolts, double rightVolts) {
m_leftMotors.setVoltage(leftVolts);
m_rightMotors.setVoltage(rightVolts);
m_leftLeader.setVoltage(leftVolts);
m_rightLeader.setVoltage(rightVolts);
m_drive.feed();
}

View File

@@ -19,7 +19,6 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
@@ -96,7 +95,7 @@ public class Robot extends TimedRobot {
// An encoder set up to measure elevator height in meters.
private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -17,7 +17,6 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
@@ -77,7 +76,7 @@ public class Robot extends TimedRobot {
// An encoder set up to measure flywheel velocity in radians per second.
private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -16,7 +16,6 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
@@ -72,7 +71,7 @@ public class Robot extends TimedRobot {
// An encoder set up to measure flywheel velocity in radians per second.
private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class SwerveModule {
@@ -23,8 +22,8 @@ public class SwerveModule {
private static final double kModuleMaxAngularAcceleration =
2 * Math.PI; // radians per second squared
private final MotorController m_driveMotor;
private final MotorController m_turningMotor;
private final PWMSparkMax m_driveMotor;
private final PWMSparkMax m_turningMotor;
private final Encoder m_driveEncoder;
private final Encoder m_turningEncoder;

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class SwerveModule {
@@ -23,8 +22,8 @@ public class SwerveModule {
private static final double kModuleMaxAngularAcceleration =
2 * Math.PI; // radians per second squared
private final MotorController m_driveMotor;
private final MotorController m_turningMotor;
private final PWMSparkMax m_driveMotor;
private final PWMSparkMax m_turningMotor;
private final Encoder m_driveEncoder;
private final Encoder m_turningEncoder;

View File

@@ -4,10 +4,10 @@
package edu.wpi.first.wpilibj.examples.tankdrive;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
@@ -15,27 +15,30 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
* the code necessary to operate a robot with tank drive.
*/
public class Robot extends TimedRobot {
private DifferentialDrive m_myRobot;
private DifferentialDrive m_robotDrive;
private Joystick m_leftStick;
private Joystick m_rightStick;
private final MotorController m_leftMotor = new PWMSparkMax(0);
private final MotorController m_rightMotor = new PWMSparkMax(1);
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
@Override
public void robotInit() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_rightMotor.setInverted(true);
m_myRobot = new DifferentialDrive(m_leftMotor, m_rightMotor);
m_robotDrive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
m_leftStick = new Joystick(0);
m_rightStick = new Joystick(1);
}
@Override
public void teleopPeriodic() {
m_myRobot.tankDrive(-m_leftStick.getY(), -m_rightStick.getY());
m_robotDrive.tankDrive(-m_leftStick.getY(), -m_rightStick.getY());
}
}

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.tankdrivexboxcontroller;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -16,11 +17,15 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
public class Robot extends TimedRobot {
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final XboxController m_driverController = new XboxController(0);
@Override
public void robotInit() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -6,6 +6,7 @@ package edu.wpi.first.wpilibj.examples.ultrasonicpid;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.filter.MedianFilter;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Ultrasonic;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -40,9 +41,15 @@ public class Robot extends TimedRobot {
private final Ultrasonic m_ultrasonic = new Ultrasonic(kUltrasonicPingPort, kUltrasonicEchoPort);
private final PWMSparkMax m_leftMotor = new PWMSparkMax(kLeftMotorPort);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(kRightMotorPort);
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_robotDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final PIDController m_pidController = new PIDController(kP, kI, kD);
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override
public void autonomousInit() {
// Set setpoint of the pid controller

View File

@@ -4,6 +4,7 @@
package edu.wpi.first.wpilibj.examples.xrpreference.subsystems;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.BuiltInAccelerometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -29,7 +30,8 @@ public class Drivetrain extends SubsystemBase {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
// Set up the XRPGyro
private final XRPGyro m_gyro = new XRPGyro();
@@ -39,6 +41,9 @@ public class Drivetrain extends SubsystemBase {
/** Creates a new Drivetrain. */
public Drivetrain() {
SendableRegistry.addChild(m_diffDrive, m_leftMotor);
SendableRegistry.addChild(m_diffDrive, m_rightMotor);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -24,7 +24,8 @@ public class RomiDrivetrain extends SubsystemBase {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -23,7 +23,8 @@ public class RomiDrivetrain {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -23,7 +23,8 @@ public class RomiDrivetrain {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new RomiDrivetrain. */
public RomiDrivetrain() {

View File

@@ -27,7 +27,8 @@ public class XRPDrivetrain extends SubsystemBase {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {

View File

@@ -26,7 +26,8 @@ public class XRPDrivetrain {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {

View File

@@ -26,7 +26,8 @@ public class XRPDrivetrain {
private final Encoder m_rightEncoder = new Encoder(6, 7);
// Set up the differential drive controller
private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
private final DifferentialDrive m_diffDrive =
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
/** Creates a new XRPDrivetrain. */
public XRPDrivetrain() {