diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index 192d21bf01..c6b705a574 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -30,12 +30,12 @@ class SpeedController; * @code{.cpp} * class Robot { * public: - * frc::Spark m_frontLeft{1}; - * frc::Spark m_rearLeft{2}; + * frc::PWMVictorSPX m_frontLeft{1}; + * frc::PWMVictorSPX m_rearLeft{2}; * frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft}; * - * frc::Spark m_frontRight{3}; - * frc::Spark m_rearRight{4}; + * frc::PWMVictorSPX m_frontRight{3}; + * frc::PWMVictorSPX m_rearRight{4}; * frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight}; * * frc::DifferentialDrive m_drive{m_left, m_right}; @@ -46,14 +46,14 @@ class SpeedController; * @code{.cpp} * class Robot { * public: - * frc::Spark m_frontLeft{1}; - * frc::Spark m_midLeft{2}; - * frc::Spark m_rearLeft{3}; + * frc::PWMVictorSPX m_frontLeft{1}; + * frc::PWMVictorSPX m_midLeft{2}; + * frc::PWMVictorSPX m_rearLeft{3}; * frc::SpeedControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft}; * - * frc::Spark m_frontRight{4}; - * frc::Spark m_midRight{5}; - * frc::Spark m_rearRight{6}; + * frc::PWMVictorSPX m_frontRight{4}; + * frc::PWMVictorSPX m_midRight{5}; + * frc::PWMVictorSPX m_rearRight{6}; * frc::SpeedControllerGroup m_right{m_frontRight, m_midRight, m_rearRight}; * * frc::DifferentialDrive m_drive{m_left, m_right}; diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h index 0894ec10e4..38a0376f1c 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -57,10 +57,10 @@ class Drivetrain { static constexpr double kWheelRadius = 0.0508; // meters static constexpr int kEncoderResolution = 4096; - frc::Spark m_leftMaster{1}; - frc::Spark m_leftFollower{2}; - frc::Spark m_rightMaster{3}; - frc::Spark m_rightFollower{4}; + frc::PWMVictorSPX m_leftMaster{1}; + frc::PWMVictorSPX m_leftFollower{2}; + frc::PWMVictorSPX m_rightMaster{3}; + frc::PWMVictorSPX m_rightFollower{4}; frc::SpeedControllerGroup m_leftGroup{m_leftMaster, m_leftFollower}; frc::SpeedControllerGroup m_rightGroup{m_rightMaster, m_rightFollower}; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h index 5c1ef6c26e..6550085880 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -45,10 +45,10 @@ class Drivetrain { wpi::math::pi}; // 1/2 rotation per second private: - frc::Spark m_frontLeftMotor{1}; - frc::Spark m_frontRightMotor{2}; - frc::Spark m_backLeftMotor{3}; - frc::Spark m_backRightMotor{4}; + frc::PWMVictorSPX m_frontLeftMotor{1}; + frc::PWMVictorSPX m_frontRightMotor{2}; + frc::PWMVictorSPX m_backLeftMotor{3}; + frc::PWMVictorSPX m_backRightMotor{4}; frc::Encoder m_frontLeftEncoder{0, 1}; frc::Encoder m_frontRightEncoder{2, 3}; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h index 65324c5e79..eb93d1b69b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.h @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include #include #include @@ -34,8 +34,8 @@ class SwerveModule { kModuleMaxAngularAcceleration = units::meters_per_second_squared_t( wpi::math::pi * 2.0); // radians per second squared - frc::Spark m_driveMotor; - frc::Spark m_turningMotor; + frc::PWMVictorSPX m_driveMotor; + frc::PWMVictorSPX m_turningMotor; frc::Encoder m_driveEncoder{0, 1}; frc::Encoder m_turningEncoder{2, 3}; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java index 13016298c1..11ef39c269 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java @@ -31,12 +31,12 @@ import edu.wpi.first.wpiutil.math.MathUtils; *

Four motor drivetrain: *


  * public class Robot {
- *   Spark m_frontLeft = new Spark(1);
- *   Spark m_rearLeft = new Spark(2);
+ *   SpeedController m_frontLeft = new PWMVictorSPX(1);
+ *   SpeedController m_rearLeft = new PWMVictorSPX(2);
  *   SpeedControllerGroup m_left = new SpeedControllerGroup(m_frontLeft, m_rearLeft);
  *
- *   Spark m_frontRight = new Spark(3);
- *   Spark m_rearRight = new Spark(4);
+ *   SpeedController m_frontRight = new PWMVictorSPX(3);
+ *   SpeedController m_rearRight = new PWMVictorSPX(4);
  *   SpeedControllerGroup m_right = new SpeedControllerGroup(m_frontRight, m_rearRight);
  *
  *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
@@ -46,14 +46,14 @@ import edu.wpi.first.wpiutil.math.MathUtils;
  * 

Six motor drivetrain: *


  * public class Robot {
- *   Spark m_frontLeft = new Spark(1);
- *   Spark m_midLeft = new Spark(2);
- *   Spark m_rearLeft = new Spark(3);
+ *   SpeedController m_frontLeft = new PWMVictorSPX(1);
+ *   SpeedController m_midLeft = new PWMVictorSPX(2);
+ *   SpeedController m_rearLeft = new PWMVictorSPX(3);
  *   SpeedControllerGroup m_left = new SpeedControllerGroup(m_frontLeft, m_midLeft, m_rearLeft);
  *
- *   Spark m_frontRight = new Spark(4);
- *   Spark m_midRight = new Spark(5);
- *   Spark m_rearRight = new Spark(6);
+ *   SpeedController m_frontRight = new PWMVictorSPX(4);
+ *   SpeedController m_midRight = new PWMVictorSPX(5);
+ *   SpeedController m_rearRight = new PWMVictorSPX(6);
  *   SpeedControllerGroup m_right = new SpeedControllerGroup(m_frontRight, m_midRight, m_rearRight);
  *
  *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
index 09df9e3c48..9364105414 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
@@ -9,7 +9,8 @@ package edu.wpi.first.wpilibj.examples.differentialdrivebot;
 
 import edu.wpi.first.wpilibj.AnalogGyro;
 import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.Spark;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
 import edu.wpi.first.wpilibj.SpeedControllerGroup;
 import edu.wpi.first.wpilibj.controller.PIDController;
 import edu.wpi.first.wpilibj.geometry.Rotation2d;
@@ -29,10 +30,10 @@ public class Drivetrain {
   private static final double kWheelRadius = 0.0508; // meters
   private static final int kEncoderResolution = 4096;
 
-  private final Spark m_leftMaster = new Spark(1);
-  private final Spark m_leftFollower = new Spark(2);
-  private final Spark m_rightMaster = new Spark(3);
-  private final Spark m_rightFollower = new Spark(4);
+  private final SpeedController m_leftMaster = new PWMVictorSPX(1);
+  private final SpeedController m_leftFollower = new PWMVictorSPX(2);
+  private final SpeedController m_rightMaster = new PWMVictorSPX(3);
+  private final SpeedController m_rightFollower = new PWMVictorSPX(4);
 
   private final Encoder m_leftEncoder = new Encoder(0, 1);
   private final Encoder m_rightEncoder = new Encoder(2, 3);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java
index 8ea1ed1167..5d3d54676f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java
@@ -9,7 +9,8 @@ package edu.wpi.first.wpilibj.examples.elevatorprofiledpid;
 
 import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Spark;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
 import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
@@ -19,7 +20,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 Spark m_motor = new Spark(1);
+  private final SpeedController m_motor = new PWMVictorSPX(1);
 
   // Create a PID controller whose setpoint's change is subject to maximum
   // velocity and acceleration constraints.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java
index 15f56b9ef3..c6e40c6d9f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java
@@ -9,7 +9,8 @@ package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
 
 import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Spark;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.controller.PIDController;
 import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
@@ -19,7 +20,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 Spark m_motor = new Spark(1);
+  private final SpeedController m_motor = new PWMVictorSPX(1);
   private final PIDController m_controller = new PIDController(1.3, 0.0, 0.7, kDt);
 
   private final TrapezoidProfile.Constraints m_constraints =
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
index 73dfb67f3f..6220807aa0 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
@@ -9,7 +9,8 @@ package edu.wpi.first.wpilibj.examples.mecanumbot;
 
 import edu.wpi.first.wpilibj.AnalogGyro;
 import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.Spark;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
 import edu.wpi.first.wpilibj.controller.PIDController;
 import edu.wpi.first.wpilibj.geometry.Rotation2d;
 import edu.wpi.first.wpilibj.geometry.Translation2d;
@@ -26,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 Spark m_frontLeftMotor = new Spark(1);
-  private final Spark m_frontRightMotor = new Spark(2);
-  private final Spark m_backLeftMotor = new Spark(3);
-  private final Spark m_backRightMotor = new Spark(4);
+  private final SpeedController m_frontLeftMotor = new PWMVictorSPX(1);
+  private final SpeedController m_frontRightMotor = new PWMVictorSPX(2);
+  private final SpeedController m_backLeftMotor = new PWMVictorSPX(3);
+  private final SpeedController m_backRightMotor = new PWMVictorSPX(4);
 
   private final Encoder m_frontLeftEncoder = new Encoder(0, 1);
   private final Encoder m_frontRightEncoder = new Encoder(2, 3);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
index 5e014491ad..2969fd40d0 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/SwerveModule.java
@@ -8,7 +8,8 @@
 package edu.wpi.first.wpilibj.examples.swervebot;
 
 import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.Spark;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+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.geometry.Rotation2d;
@@ -23,8 +24,8 @@ public class SwerveModule {
   private static final double kModuleMaxAngularAcceleration
       = 2 * Math.PI; // radians per second squared
 
-  private final Spark m_driveMotor;
-  private final Spark m_turningMotor;
+  private final SpeedController m_driveMotor;
+  private final SpeedController m_turningMotor;
 
   private final Encoder m_driveEncoder = new Encoder(0, 1);
   private final Encoder m_turningEncoder = new Encoder(2, 3);
@@ -42,8 +43,8 @@ public class SwerveModule {
    * @param turningMotorChannel ID for the turning motor.
    */
   public SwerveModule(int driveMotorChannel, int turningMotorChannel) {
-    m_driveMotor = new Spark(driveMotorChannel);
-    m_turningMotor = new Spark(turningMotorChannel);
+    m_driveMotor = new PWMVictorSPX(driveMotorChannel);
+    m_turningMotor = new PWMVictorSPX(turningMotorChannel);
 
     // Set the distance per pulse for the drive encoder. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder