[wpilib] Move motor controllers to motorcontrol package (#3302)

Also deprecate SpeedController in favor of motorcontrol.MotorController and
SpeedControllerGroup in favor of motorcontrol.MotorControllerGroup.

The MotorController interface is derived from the SpeedController interface
so that code such as SpeedController x = new VictorSP(1) continues to
compile (just with a warning).

SpeedControllerGroup and MotorControllerGroup are independent classes;
both implement the MotorController interface.
This commit is contained in:
Peter Johnson
2021-04-17 11:27:16 -07:00
committed by GitHub
parent b7b178f49c
commit 0abf6c9045
194 changed files with 1096 additions and 696 deletions

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.arcadedrive;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with

View File

@@ -5,10 +5,10 @@
package edu.wpi.first.wpilibj.examples.arcadedrivexboxcontroller;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with split

View File

@@ -5,10 +5,10 @@
package edu.wpi.first.wpilibj.examples.armbot.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.controller.ArmFeedforward;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.examples.armbot.Constants.ArmConstants;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;

View File

@@ -5,22 +5,22 @@
package edu.wpi.first.wpilibj.examples.armbot.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -4,14 +4,14 @@
package edu.wpi.first.wpilibj.examples.armbotoffboard;
import edu.wpi.first.wpilibj.SpeedController;
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 SpeedController {
public class ExampleSmartMotorController implements MotorController {
public enum PIDMode {
kPosition,
kVelocity,

View File

@@ -5,22 +5,22 @@
package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
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.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.armsimulation;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.BatterySim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.simulation.RoboRioSim;

View File

@@ -6,15 +6,15 @@ package edu.wpi.first.wpilibj.examples.differentialdrivebot;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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. */
public class Drivetrain {
@@ -25,18 +25,18 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final SpeedController m_leftLeader = new PWMSparkMax(1);
private final SpeedController m_leftFollower = new PWMSparkMax(2);
private final SpeedController m_rightLeader = new PWMSparkMax(3);
private final SpeedController m_rightFollower = new PWMSparkMax(4);
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 Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final SpeedControllerGroup m_leftGroup =
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
private final SpeedControllerGroup m_rightGroup =
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
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);

View File

@@ -6,9 +6,6 @@ package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
@@ -18,6 +15,9 @@ import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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.util.Units;
import edu.wpi.first.wpiutil.math.VecBuilder;
@@ -30,18 +30,18 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final SpeedController m_leftLeader = new PWMSparkMax(1);
private final SpeedController m_leftFollower = new PWMSparkMax(2);
private final SpeedController m_rightLeader = new PWMSparkMax(3);
private final SpeedController m_rightFollower = new PWMSparkMax(4);
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 Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final SpeedControllerGroup m_leftGroup =
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
private final SpeedControllerGroup m_rightGroup =
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
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);

View File

@@ -4,14 +4,14 @@
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
import edu.wpi.first.wpilibj.SpeedController;
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 SpeedController {
public class ExampleSmartMotorController implements MotorController {
public enum PIDMode {
kPosition,
kVelocity,

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.elevatorprofiledpid;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
public class Robot extends TimedRobot {
@@ -17,7 +17,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 SpeedController m_motor = new PWMSparkMax(1);
private final MotorController m_motor = new PWMSparkMax(1);
// Create a PID controller whose setpoint's change is subject to maximum
// velocity and acceleration constraints.

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.elevatorsimulation;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.BatterySim;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;

View File

@@ -4,14 +4,14 @@
package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
import edu.wpi.first.wpilibj.SpeedController;
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 SpeedController {
public class ExampleSmartMotorController implements MotorController {
public enum PIDMode {
kPosition,
kVelocity,

View File

@@ -5,22 +5,22 @@
package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -5,10 +5,10 @@
package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
public class ShooterSubsystem extends PIDSubsystem {

View File

@@ -5,7 +5,7 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

View File

@@ -7,11 +7,11 @@ package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
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;
@@ -20,11 +20,11 @@ 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 SpeedController m_leftMotor =
new SpeedControllerGroup(new PWMSparkMax(0), new PWMSparkMax(1));
private final MotorController m_leftMotor =
new MotorControllerGroup(new PWMSparkMax(0), new PWMSparkMax(1));
private final SpeedController m_rightMotor =
new SpeedControllerGroup(new PWMSparkMax(2), new PWMSparkMax(3));
private final MotorController m_rightMotor =
new MotorControllerGroup(new PWMSparkMax(2), new PWMSparkMax(3));
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotor, m_rightMotor);

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.PIDSubsystem;

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.PIDSubsystem;

View File

@@ -5,10 +5,10 @@
package edu.wpi.first.wpilibj.examples.gettingstarted;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* The VM is configured to automatically run this class, and to call the functions corresponding to

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.gyro;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a sample program to demonstrate how to use a gyro sensor to make a robot drive straight.

View File

@@ -6,23 +6,23 @@ package edu.wpi.first.wpilibj.examples.gyrodrivecommands.subsystems;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
import edu.wpi.first.wpilibj.interfaces.Gyro;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.gyromecanum;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation

View File

@@ -5,22 +5,22 @@
package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -5,22 +5,22 @@
package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -6,8 +6,6 @@ package edu.wpi.first.wpilibj.examples.mecanumbot;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Translation2d;
@@ -15,6 +13,8 @@ import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** Represents a mecanum drive style drivetrain. */
@SuppressWarnings("PMD.TooManyFields")
@@ -22,10 +22,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 SpeedController m_frontLeftMotor = new PWMSparkMax(1);
private final SpeedController m_frontRightMotor = new PWMSparkMax(2);
private final SpeedController m_backLeftMotor = new PWMSparkMax(3);
private final SpeedController m_backRightMotor = new PWMSparkMax(4);
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 Encoder m_frontLeftEncoder = new Encoder(0, 1);
private final Encoder m_frontRightEncoder = new Encoder(2, 3);

View File

@@ -118,7 +118,7 @@ public class RobotContainer {
new PIDController(DriveConstants.kPFrontRightVel, 0, 0),
new PIDController(DriveConstants.kPRearRightVel, 0, 0),
m_robotDrive::getCurrentWheelSpeeds,
m_robotDrive::setDriveSpeedControllersVolts, // Consumer for the output motor voltages
m_robotDrive::setDriveMotorControllersVolts, // Consumer for the output motor voltages
m_robotDrive);
// Reset odometry to the starting pose of the trajectory.

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.subsystems;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.geometry.Pose2d;
@@ -14,6 +13,7 @@ import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveMotorVoltages;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class DriveSubsystem extends SubsystemBase {
@@ -117,8 +117,8 @@ public class DriveSubsystem extends SubsystemBase {
}
}
/** Sets the front left drive SpeedController to a voltage. */
public void setDriveSpeedControllersVolts(MecanumDriveMotorVoltages volts) {
/** Sets the front left drive MotorController to a voltage. */
public void setDriveMotorControllersVolts(MecanumDriveMotorVoltages volts) {
m_frontLeft.setVoltage(volts.frontLeftVoltage);
m_rearLeft.setVoltage(volts.rearLeftVoltage);
m_frontRight.setVoltage(volts.frontRightVoltage);

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.mecanumdrive;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.MecanumDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/** This is a demo program showing how to use Mecanum control with the MecanumDrive class. */
public class Robot extends TimedRobot {

View File

@@ -6,8 +6,6 @@ package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
@@ -18,6 +16,8 @@ import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.MecanumDriveWheelSpeeds;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpiutil.math.VecBuilder;
@@ -27,10 +27,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 SpeedController m_frontLeftMotor = new PWMSparkMax(1);
private final SpeedController m_frontRightMotor = new PWMSparkMax(2);
private final SpeedController m_backLeftMotor = new PWMSparkMax(3);
private final SpeedController m_backRightMotor = new PWMSparkMax(4);
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 Encoder m_frontLeftEncoder = new Encoder(0, 1);
private final Encoder m_frontRightEncoder = new Encoder(2, 3);

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.motorcontrol;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This sample program shows how to control a motor using a joystick. In the operator control part
@@ -20,7 +20,7 @@ public class Robot extends TimedRobot {
private static final int kMotorPort = 0;
private static final int kJoystickPort = 0;
private SpeedController m_motor;
private MotorController m_motor;
private Joystick m_joystick;
@Override

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.motorcontrolencoder;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
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 +27,7 @@ public class Robot extends TimedRobot {
private static final int kEncoderPortA = 0;
private static final int kEncoderPortB = 1;
private SpeedController m_motor;
private MotorController m_motor;
private Joystick m_joystick;
private Encoder m_encoder;

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
/**
* The Collector subsystem has one motor for the rollers, a limit switch for ball detection, a
@@ -21,7 +21,7 @@ public class Collector extends Subsystem {
public static final double kReverse = -1;
// Subsystem devices
private final SpeedController m_rollerMotor = new Victor(6);
private final MotorController m_rollerMotor = new Victor(6);
private final DigitalInput m_ballDetector = new DigitalInput(10);
private final DigitalInput m_openDetector = new DigitalInput(6);
private final Solenoid m_piston = new Solenoid(1, 1);

View File

@@ -8,13 +8,13 @@ import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.CounterBase.EncodingType;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveWithJoystick;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
/**
* The DriveTrain subsystem controls the robot's chassis and reads in information about it's speed
@@ -22,14 +22,14 @@ import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveWithJoystick;
*/
public class DriveTrain extends Subsystem {
// Subsystem devices
private final SpeedController m_frontLeftCIM = new Victor(1);
private final SpeedController m_frontRightCIM = new Victor(2);
private final SpeedController m_rearLeftCIM = new Victor(3);
private final SpeedController m_rearRightCIM = new Victor(4);
private final SpeedControllerGroup m_leftCIMs =
new SpeedControllerGroup(m_frontLeftCIM, m_rearLeftCIM);
private final SpeedControllerGroup m_rightCIMs =
new SpeedControllerGroup(m_frontRightCIM, m_rearRightCIM);
private final MotorController m_frontLeftCIM = new Victor(1);
private final MotorController m_frontRightCIM = new Victor(2);
private final MotorController m_rearLeftCIM = new Victor(3);
private final MotorController m_rearRightCIM = new Victor(4);
private final MotorControllerGroup m_leftCIMs =
new MotorControllerGroup(m_frontLeftCIM, m_rearLeftCIM);
private final MotorControllerGroup m_rightCIMs =
new MotorControllerGroup(m_frontRightCIM, m_rearRightCIM);
private final DifferentialDrive m_drive;
private final Encoder m_rightEncoder = new Encoder(1, 2, true, EncodingType.k4X);
private final Encoder m_leftEncoder = new Encoder(3, 4, false, EncodingType.k4X);

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.Victor;
import edu.wpi.first.wpilibj.command.PIDSubsystem;
import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.Victor;
/**
* The Pivot subsystem contains the Van-door motor and the pot for PID control of angle of the pivot
@@ -31,7 +31,7 @@ public class Pivot extends PIDSubsystem {
private final AnalogPotentiometer m_pot = new AnalogPotentiometer(1);
// Motor to move the pivot.
private final SpeedController m_motor = new Victor(5);
private final MotorController m_motor = new Victor(5);
/** Create a new pivot subsystem. */
public Pivot() {

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.potentiometerpid;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a sample program to demonstrate how to use a soft potentiometer and a PID controller to
@@ -33,7 +33,7 @@ public class Robot extends TimedRobot {
private PIDController m_pidController;
private AnalogInput m_potentiometer;
private SpeedController m_elevatorMotor;
private MotorController m_elevatorMotor;
private Joystick m_joystick;
private int m_index;

View File

@@ -6,26 +6,26 @@ package edu.wpi.first.wpilibj.examples.ramsetecommand.subsystems;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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 SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -6,9 +6,6 @@ package edu.wpi.first.wpilibj.examples.ramsetecontroller;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Pose2d;
@@ -16,6 +13,9 @@ import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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. */
public class Drivetrain {
@@ -26,18 +26,18 @@ public class Drivetrain {
private static final double kWheelRadius = 0.0508; // meters
private static final int kEncoderResolution = 4096;
private final SpeedController m_leftLeader = new PWMSparkMax(1);
private final SpeedController m_leftFollower = new PWMSparkMax(2);
private final SpeedController m_rightLeader = new PWMSparkMax(3);
private final SpeedController m_rightFollower = new PWMSparkMax(4);
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 Encoder m_leftEncoder = new Encoder(0, 1);
private final Encoder m_rightEncoder = new Encoder(2, 3);
private final SpeedControllerGroup m_leftGroup =
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
private final SpeedControllerGroup m_rightGroup =
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
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);

View File

@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.romireference.subsystems;
import edu.wpi.first.wpilibj.BuiltInAccelerometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj.romi.RomiGyro;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

View File

@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.examples.shuffleboard;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;

View File

@@ -6,9 +6,7 @@ package edu.wpi.first.wpilibj.examples.simpledifferentialdrivesimulation;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Pose2d;
@@ -16,6 +14,8 @@ import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
@@ -42,10 +42,10 @@ public class Drivetrain {
private final PWMSparkMax m_rightLeader = new PWMSparkMax(3);
private final PWMSparkMax m_rightFollower = new PWMSparkMax(4);
private final SpeedControllerGroup m_leftGroup =
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
private final SpeedControllerGroup m_rightGroup =
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
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);

View File

@@ -6,11 +6,11 @@ package edu.wpi.first.wpilibj.examples.statespacearm;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
import edu.wpi.first.wpilibj.system.plant.DCMotor;
@@ -91,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 SpeedController m_motor = new PWMSparkMax(kMotorPort);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -6,16 +6,16 @@ package edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.sub
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.Constants.DriveConstants;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
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;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
@@ -26,14 +26,14 @@ import edu.wpi.first.wpiutil.math.VecBuilder;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
private final SpeedControllerGroup m_leftMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_leftMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kLeftMotor1Port),
new PWMSparkMax(DriveConstants.kLeftMotor2Port));
// The motors on the right side of the drive.
private final SpeedControllerGroup m_rightMotors =
new SpeedControllerGroup(
private final MotorControllerGroup m_rightMotors =
new MotorControllerGroup(
new PWMSparkMax(DriveConstants.kRightMotor1Port),
new PWMSparkMax(DriveConstants.kRightMotor2Port));

View File

@@ -6,11 +6,11 @@ package edu.wpi.first.wpilibj.examples.statespaceelevator;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
import edu.wpi.first.wpilibj.system.plant.DCMotor;
@@ -94,7 +94,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 SpeedController m_motor = new PWMSparkMax(kMotorPort);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -6,11 +6,11 @@ package edu.wpi.first.wpilibj.examples.statespaceflywheel;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
import edu.wpi.first.wpilibj.system.plant.DCMotor;
@@ -77,7 +77,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 SpeedController m_motor = new PWMSparkMax(kMotorPort);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -6,11 +6,11 @@ package edu.wpi.first.wpilibj.examples.statespaceflywheelsysid;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.LinearQuadraticRegulator;
import edu.wpi.first.wpilibj.estimator.KalmanFilter;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.LinearSystemLoop;
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
@@ -72,7 +72,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 SpeedController m_motor = new PWMSparkMax(kMotorPort);
private final MotorController m_motor = new PWMSparkMax(kMotorPort);
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);

View File

@@ -5,13 +5,13 @@
package edu.wpi.first.wpilibj.examples.swervebot;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
public class SwerveModule {
@@ -22,8 +22,8 @@ public class SwerveModule {
private static final double kModuleMaxAngularAcceleration =
2 * Math.PI; // radians per second squared
private final SpeedController m_driveMotor;
private final SpeedController m_turningMotor;
private final MotorController m_driveMotor;
private final MotorController m_turningMotor;
private final Encoder m_driveEncoder = new Encoder(0, 1);
private final Encoder m_turningEncoder = new Encoder(2, 3);

View File

@@ -5,12 +5,12 @@
package edu.wpi.first.wpilibj.examples.swervecontrollercommand.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.ModuleConstants;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
public class SwerveModule {

View File

@@ -5,13 +5,13 @@
package edu.wpi.first.wpilibj.examples.swervesdriveposeestimator;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
public class SwerveModule {
@@ -22,8 +22,8 @@ public class SwerveModule {
private static final double kModuleMaxAngularAcceleration =
2 * Math.PI; // radians per second squared
private final SpeedController m_driveMotor;
private final SpeedController m_turningMotor;
private final MotorController m_driveMotor;
private final MotorController m_turningMotor;
private final Encoder m_driveEncoder = new Encoder(0, 1);
private final Encoder m_turningEncoder = new Encoder(2, 3);

View File

@@ -5,9 +5,9 @@
package edu.wpi.first.wpilibj.examples.tankdrive;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a demo program showing the use of the DifferentialDrive class, specifically it contains

View File

@@ -5,10 +5,10 @@
package edu.wpi.first.wpilibj.examples.tankdrivexboxcontroller;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with tank

View File

@@ -6,9 +6,9 @@ package edu.wpi.first.wpilibj.examples.ultrasonic;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.MedianFilter;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a sample program demonstrating how to use an ultrasonic sensor and proportional control

View File

@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.ultrasonicpid;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.MedianFilter;
import edu.wpi.first.wpilibj.PWMSparkMax;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
/**
* This is a sample program to demonstrate the use of a PIDController with an ultrasonic sensor to

View File

@@ -5,8 +5,8 @@
package edu.wpi.first.wpilibj.templates.romicommandbased.subsystems;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class RomiDrivetrain extends SubsystemBase {

View File

@@ -5,8 +5,8 @@
package edu.wpi.first.wpilibj.templates.romitimed;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
public class RomiDrivetrain {
private static final double kCountsPerRevolution = 1440.0;