diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp index bb4672ffa4..3361754b63 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include -#include +#include #include #include @@ -15,8 +15,8 @@ * Runs the motors with arcade steering. */ class Robot : public frc::TimedRobot { - frc::Spark m_leftMotor{0}; - frc::Spark m_rightMotor{1}; + frc::PWMVictorSPX m_leftMotor{0}; + frc::PWMVictorSPX m_rightMotor{1}; frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; frc::Joystick m_stick{0}; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h index 778f406641..96a436a7cb 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include /** @@ -46,6 +46,6 @@ class Claw : public frc::Subsystem { void Log(); private: - frc::Spark m_motor{7}; + frc::PWMVictorSPX m_motor{7}; frc::DigitalInput m_contact{5}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h index bb9ab2d9e9..dce4d9c86b 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include #include @@ -67,12 +67,12 @@ class DriveTrain : public frc::Subsystem { double GetDistanceToObstacle(); private: - 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_robotDrive{m_left, m_right}; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h index c0810207a4..53f60575e5 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include /** @@ -42,7 +42,7 @@ class Elevator : public frc::PIDSubsystem { void UsePIDOutput(double d) override; private: - frc::Spark m_motor{5}; + frc::PWMVictorSPX m_motor{5}; // Conversion value of potentiometer varies between the real world and // simulation diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h index 8c4f0f227e..26fc74b053 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include /** @@ -40,7 +40,7 @@ class Wrist : public frc::PIDSubsystem { void UsePIDOutput(double d) override; private: - frc::Spark m_motor{6}; + frc::PWMVictorSPX m_motor{6}; // Conversion value of potentiometer varies between the real world and // simulation diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index 8aa5022e57..f43cb57113 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include -#include +#include #include #include #include @@ -46,8 +46,8 @@ class Robot : public frc::TimedRobot { private: // Robot drive system - frc::Spark m_left{0}; - frc::Spark m_right{1}; + frc::PWMVictorSPX m_left{0}; + frc::PWMVictorSPX m_right{1}; frc::DifferentialDrive m_robotDrive{m_left, m_right}; frc::Joystick m_stick{0}; diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index 61707dee5c..b0c70d2b11 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include @@ -47,8 +47,8 @@ class Robot : public frc::TimedRobot { static constexpr int kGyroPort = 0; static constexpr int kJoystickPort = 0; - frc::Spark m_left{kLeftMotorPort}; - frc::Spark m_right{kRightMotorPort}; + frc::PWMVictorSPX m_left{kLeftMotorPort}; + frc::PWMVictorSPX m_right{kRightMotorPort}; frc::DifferentialDrive m_robotDrive{m_left, m_right}; frc::AnalogGyro m_gyro{kGyroPort}; diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp index f9618a8c0c..738ff32e06 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include @@ -47,10 +47,10 @@ class Robot : public frc::TimedRobot { static constexpr int kGyroPort = 0; static constexpr int kJoystickPort = 0; - frc::Spark m_frontLeft{kFrontLeftMotorPort}; - frc::Spark m_rearLeft{kRearLeftMotorPort}; - frc::Spark m_frontRight{kFrontRightMotorPort}; - frc::Spark m_rearRight{kRearRightMotorPort}; + frc::PWMVictorSPX m_frontLeft{kFrontLeftMotorPort}; + frc::PWMVictorSPX m_rearLeft{kRearLeftMotorPort}; + frc::PWMVictorSPX m_frontRight{kFrontRightMotorPort}; + frc::PWMVictorSPX m_rearRight{kRearRightMotorPort}; frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight}; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index 6b06b7e806..8b4c98c46c 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include -#include +#include #include #include @@ -38,10 +38,10 @@ class Robot : public frc::TimedRobot { static constexpr int kJoystickChannel = 0; - frc::Spark m_frontLeft{kFrontLeftChannel}; - frc::Spark m_rearLeft{kRearLeftChannel}; - frc::Spark m_frontRight{kFrontRightChannel}; - frc::Spark m_rearRight{kRearRightChannel}; + frc::PWMVictorSPX m_frontLeft{kFrontLeftChannel}; + frc::PWMVictorSPX m_rearLeft{kRearLeftChannel}; + frc::PWMVictorSPX m_frontRight{kFrontRightChannel}; + frc::PWMVictorSPX m_rearRight{kRearRightChannel}; frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight}; diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp index 49a1cfa827..2217ec1393 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include -#include +#include #include /** @@ -23,7 +23,7 @@ class Robot : public frc::TimedRobot { private: frc::Joystick m_stick{0}; - frc::Spark m_motor{0}; + frc::PWMVictorSPX m_motor{0}; }; #ifndef RUNNING_FRC_TESTS diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp index 69a0ddfddb..78e1e96985 100644 --- a/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include @@ -44,7 +44,7 @@ class Robot : public frc::TimedRobot { private: frc::Joystick m_stick{0}; - frc::Spark m_motor{0}; + frc::PWMVictorSPX m_motor{0}; frc::Encoder m_encoder{0, 1}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h index 96fbd4726f..3e237fa3d6 100644 --- a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h +++ b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h @@ -8,8 +8,8 @@ #pragma once #include +#include #include -#include #include /** @@ -69,7 +69,7 @@ class Collector : public frc::Subsystem { private: // Subsystem devices - frc::Spark m_rollerMotor{6}; + frc::PWMVictorSPX m_rollerMotor{6}; frc::DigitalInput m_ballDetector{10}; frc::Solenoid m_piston{1}; frc::DigitalInput m_openDetector{6}; diff --git a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h index b263db81dd..0afa3ebb49 100644 --- a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h +++ b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -63,12 +63,12 @@ class DriveTrain : public frc::Subsystem { private: // Subsystem devices - frc::Spark m_frontLeftCIM{1}; - frc::Spark m_rearLeftCIM{2}; + frc::PWMVictorSPX m_frontLeftCIM{1}; + frc::PWMVictorSPX m_rearLeftCIM{2}; frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM}; - frc::Spark m_frontRightCIM{3}; - frc::Spark m_rearRightCIM{4}; + frc::PWMVictorSPX m_frontRightCIM{3}; + frc::PWMVictorSPX m_rearRightCIM{4}; frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM}; frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs}; diff --git a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h index 953949afe5..f9a3c251f5 100644 --- a/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h +++ b/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h @@ -9,7 +9,7 @@ #include #include -#include +#include #include /** @@ -70,5 +70,5 @@ class Pivot : public frc::PIDSubsystem { frc::AnalogPotentiometer m_pot{1}; // Motor to move the pivot - frc::Spark m_motor{5}; + frc::PWMVictorSPX m_motor{5}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp index e60dfa9e27..e01a04f955 100644 --- a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include /** @@ -62,7 +62,7 @@ class Robot : public frc::TimedRobot { frc::AnalogInput m_potentiometer{kPotChannel}; frc::Joystick m_joystick{kJoystickChannel}; - frc::Spark m_elevatorMotor{kMotorChannel}; + frc::PWMVictorSPX m_elevatorMotor{kMotorChannel}; /* Potentiometer (AnalogInput) and elevatorMotor (Victor) can be used as a * PIDSource and PIDOutput respectively. diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp index cebe8730c9..3447504c46 100644 --- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include #include @@ -64,9 +64,9 @@ class Robot : public frc::TimedRobot { } private: - frc::Spark m_left{0}; - frc::Spark m_right{1}; - frc::Spark m_elevatorMotor{2}; + frc::PWMVictorSPX m_left{0}; + frc::PWMVictorSPX m_right{1}; + frc::PWMVictorSPX m_elevatorMotor{2}; frc::DifferentialDrive m_robotDrive{m_left, m_right}; diff --git a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp index 832bc3027c..2cc21318dc 100644 --- a/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp @@ -6,7 +6,7 @@ /*----------------------------------------------------------------------------*/ #include -#include +#include #include #include @@ -45,8 +45,8 @@ class Robot : public frc::TimedRobot { frc::AnalogInput m_ultrasonic{kUltrasonicPort}; - frc::Spark m_left{kLeftMotorPort}; - frc::Spark m_right{kRightMotorPort}; + frc::PWMVictorSPX m_left{kLeftMotorPort}; + frc::PWMVictorSPX m_right{kRightMotorPort}; frc::DifferentialDrive m_robotDrive{m_left, m_right}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp index d47eef3923..67aec780fd 100644 --- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include @@ -72,8 +72,8 @@ class Robot : public frc::TimedRobot { frc::AnalogInput m_ultrasonic{kUltrasonicPort}; - frc::Spark m_left{kLeftMotorPort}; - frc::Spark m_right{kRightMotorPort}; + frc::PWMVictorSPX m_left{kLeftMotorPort}; + frc::PWMVictorSPX m_right{kRightMotorPort}; frc::DifferentialDrive m_robotDrive{m_left, m_right}; MyPIDOutput m_pidOutput{m_robotDrive}; diff --git a/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h index b2889af3cb..d568111d9e 100644 --- a/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h @@ -10,8 +10,8 @@ #include #include +#include #include -#include #include #include @@ -37,8 +37,8 @@ class Robot : public frc::SampleRobot { private: // Robot drive system - frc::Spark m_leftMotor{0}; - frc::Spark m_rightMotor{1}; + frc::PWMVictorSPX m_leftMotor{0}; + frc::PWMVictorSPX m_rightMotor{1}; frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; frc::Joystick m_stick{0}; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java index 899e3d5352..5c55365762 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java @@ -11,7 +11,7 @@ import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.AnalogInput; 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.SpeedControllerGroup; import edu.wpi.first.wpilibj.command.Subsystem; @@ -28,9 +28,9 @@ import edu.wpi.first.wpilibj.examples.gearsbot.commands.TankDriveWithJoystick; */ public class DriveTrain extends Subsystem { private final SpeedController m_leftMotor - = new SpeedControllerGroup(new Spark(0), new Spark(1)); + = new SpeedControllerGroup(new PWMVictorSPX(0), new PWMVictorSPX(1)); private final SpeedController m_rightMotor - = new SpeedControllerGroup(new Spark(2), new Spark(3)); + = new SpeedControllerGroup(new PWMVictorSPX(2), new PWMVictorSPX(3)); private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotor, m_rightMotor); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java index 2876d2e7ac..8b2f249a68 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java @@ -8,7 +8,7 @@ package edu.wpi.first.wpilibj.examples.gettingstarted; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -22,7 +22,7 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive; */ public class Robot extends TimedRobot { private final DifferentialDrive m_robotDrive - = new DifferentialDrive(new Spark(0), new Spark(1)); + = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1)); private final Joystick m_stick = new Joystick(0); private final Timer m_timer = new Timer(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java index b4acdecd4e..39b2ecbf5e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java @@ -9,7 +9,7 @@ package edu.wpi.first.wpilibj.examples.gyro; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -32,8 +32,8 @@ public class Robot extends TimedRobot { private static final int kJoystickPort = 0; private final DifferentialDrive m_myRobot - = new DifferentialDrive(new Spark(kLeftMotorPort), - new Spark(kRightMotorPort)); + = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort), + new PWMVictorSPX(kRightMotorPort)); private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort); private final Joystick m_joystick = new Joystick(kJoystickPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java index 39b5e1d784..079318a746 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java @@ -9,7 +9,7 @@ package edu.wpi.first.wpilibj.examples.gyromecanum; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.MecanumDrive; @@ -36,10 +36,10 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - Spark frontLeft = new Spark(kFrontLeftChannel); - Spark rearLeft = new Spark(kRearLeftChannel); - Spark frontRight = new Spark(kFrontRightChannel); - Spark rearRight = new Spark(kRearRightChannel); + PWMVictorSPX frontLeft = new PWMVictorSPX(kFrontLeftChannel); + PWMVictorSPX rearLeft = new PWMVictorSPX(kRearLeftChannel); + PWMVictorSPX frontRight = new PWMVictorSPX(kFrontRightChannel); + PWMVictorSPX rearRight = new PWMVictorSPX(kRearRightChannel); // Invert the left side motors. // You may need to change or remove this to match your robot. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java index 70fb351bd9..35c975cb78 100755 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java @@ -8,7 +8,7 @@ package edu.wpi.first.wpilibj.examples.mecanumdrive; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.MecanumDrive; @@ -29,10 +29,10 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - Spark frontLeft = new Spark(kFrontLeftChannel); - Spark rearLeft = new Spark(kRearLeftChannel); - Spark frontRight = new Spark(kFrontRightChannel); - Spark rearRight = new Spark(kRearRightChannel); + PWMVictorSPX frontLeft = new PWMVictorSPX(kFrontLeftChannel); + PWMVictorSPX rearLeft = new PWMVictorSPX(kRearLeftChannel); + PWMVictorSPX frontRight = new PWMVictorSPX(kFrontRightChannel); + PWMVictorSPX rearRight = new PWMVictorSPX(kRearRightChannel); // Invert the left side motors. // You may need to change or remove this to match your robot. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java index 444a63658c..7dfb49bfcd 100755 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java @@ -8,7 +8,7 @@ package edu.wpi.first.wpilibj.examples.motorcontrol; 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; @@ -29,7 +29,7 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - m_motor = new Spark(kMotorPort); + m_motor = new PWMVictorSPX(kMotorPort); m_joystick = new Joystick(kJoystickPort); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java index 095ba454d4..b0cc2177da 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java @@ -9,7 +9,7 @@ package edu.wpi.first.wpilibj.examples.motorcontrolencoder; 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.smartdashboard.SmartDashboard; @@ -37,7 +37,7 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - m_motor = new Spark(kMotorPort); + m_motor = new PWMVictorSPX(kMotorPort); m_joystick = new Joystick(kJoystickPort); m_encoder = new Encoder(kEncoderPortA, kEncoderPortB); // Use SetDistancePerPulse to set the multiplier for GetDistance diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java index 4e844332e0..302ce1674d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java @@ -10,7 +10,7 @@ package edu.wpi.first.wpilibj.examples.potentiometerpid; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.PIDController; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.TimedRobot; @@ -48,7 +48,7 @@ public class Robot extends TimedRobot { @Override public void robotInit() { m_potentiometer = new AnalogInput(kPotChannel); - m_elevatorMotor = new Spark(kMotorChannel); + m_elevatorMotor = new PWMVictorSPX(kMotorChannel); m_joystick = new Joystick(kJoystickChannel); m_pidController = new PIDController(kP, kI, kD, m_potentiometer, m_elevatorMotor); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java index 19da038930..7f59e14c9b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java @@ -10,7 +10,7 @@ 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.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; @@ -18,11 +18,12 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; public class Robot extends TimedRobot { - private final DifferentialDrive m_tankDrive = new DifferentialDrive(new Spark(0), new Spark(1)); + private final DifferentialDrive m_tankDrive = new DifferentialDrive(new PWMVictorSPX(0), + new PWMVictorSPX(1)); private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); - private final Spark m_elevatorMotor = new Spark(2); + private final PWMVictorSPX m_elevatorMotor = new PWMVictorSPX(2); private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0); private NetworkTableEntry m_maxSpeed; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java index 46ff5d8547..b8a9202f05 100755 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java @@ -8,7 +8,7 @@ package edu.wpi.first.wpilibj.examples.tankdrive; import edu.wpi.first.wpilibj.Joystick; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -23,7 +23,7 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - m_myRobot = new DifferentialDrive(new Spark(0), new Spark(1)); + m_myRobot = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1)); m_leftStick = new Joystick(0); m_rightStick = new Joystick(1); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java index b6c9717406..e03c66c2b9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java @@ -8,7 +8,7 @@ package edu.wpi.first.wpilibj.examples.ultrasonic; import edu.wpi.first.wpilibj.AnalogInput; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -33,8 +33,8 @@ public class Robot extends TimedRobot { private final AnalogInput m_ultrasonic = new AnalogInput(kUltrasonicPort); private final DifferentialDrive m_robotDrive - = new DifferentialDrive(new Spark(kLeftMotorPort), - new Spark(kRightMotorPort)); + = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort), + new PWMVictorSPX(kRightMotorPort)); /** * Tells the robot to drive to a set distance (in inches) from an object diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java index 27762a9eec..cc80432477 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java @@ -10,7 +10,7 @@ package edu.wpi.first.wpilibj.examples.ultrasonicpid; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.PIDController; import edu.wpi.first.wpilibj.PIDOutput; -import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -43,8 +43,8 @@ public class Robot extends TimedRobot { private final AnalogInput m_ultrasonic = new AnalogInput(kUltrasonicPort); private final DifferentialDrive m_robotDrive - = new DifferentialDrive(new Spark(kLeftMotorPort), - new Spark(kRightMotorPort)); + = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort), + new PWMVictorSPX(kRightMotorPort)); private final PIDController m_pidController = new PIDController(kP, kI, kD, m_ultrasonic, new MyPidOutput()); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java index c1c8c5132f..9a670f0e44 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java @@ -8,8 +8,8 @@ package edu.wpi.first.wpilibj.templates.sample; import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.PWMVictorSPX; import edu.wpi.first.wpilibj.SampleRobot; -import edu.wpi.first.wpilibj.Spark; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; @@ -37,7 +37,7 @@ public class Robot extends SampleRobot { private static final String kCustomAuto = "My Auto"; private final DifferentialDrive m_robotDrive - = new DifferentialDrive(new Spark(0), new Spark(1)); + = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1)); private final Joystick m_stick = new Joystick(0); private final SendableChooser m_chooser = new SendableChooser<>();