[examples] Use PWMSparkMax instead of PWMVictorSPX (#3156)

This accurately reflects the motor controllers that are distributed in
the Kit of Parts.
This commit is contained in:
Prateek Machiraju
2021-02-13 01:14:56 -05:00
committed by GitHub
parent 69e8d0b65d
commit be0ce99007
89 changed files with 304 additions and 304 deletions

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/DifferentialDrive.h>
@@ -12,8 +12,8 @@
* Runs the motors with arcade steering.
*/
class Robot : public frc::TimedRobot {
frc::PWMVictorSPX m_leftMotor{0};
frc::PWMVictorSPX m_rightMotor{1};
frc::PWMSparkMax m_leftMotor{0};
frc::PWMSparkMax m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::Joystick m_stick{0};

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
@@ -13,8 +13,8 @@
* Runs the motors with split arcade steering and an Xbox controller.
*/
class Robot : public frc::TimedRobot {
frc::PWMVictorSPX m_leftMotor{0};
frc::PWMVictorSPX m_rightMotor{1};
frc::PWMSparkMax m_leftMotor{0};
frc::PWMSparkMax m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::XboxController m_driverController{0};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/ArmFeedforward.h>
#include <frc2/command/ProfiledPIDSubsystem.h>
#include <units/angle.h>
@@ -24,7 +24,7 @@ class ArmSubsystem : public frc2::ProfiledPIDSubsystem<units::radians> {
units::radian_t GetMeasurement() override;
private:
frc::PWMVictorSPX m_motor;
frc::PWMSparkMax m_motor;
frc::Encoder m_encoder;
frc::ArmFeedforward m_feedforward;
};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -70,10 +70,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -70,10 +70,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -5,7 +5,7 @@
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/RobotController.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
@@ -43,7 +43,7 @@ class Robot : public frc::TimedRobot {
// Standard classes for controlling our arm
frc2::PIDController m_controller{kArmKp, 0, 0};
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::Joystick m_joystick{kJoystickPort};
// Simulation classes help us simulate what's going on, including gravity.

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -52,10 +52,10 @@ class Drivetrain {
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
frc::PWMVictorSPX m_leftLeader{1};
frc::PWMVictorSPX m_leftFollower{2};
frc::PWMVictorSPX m_rightLeader{3};
frc::PWMVictorSPX m_rightFollower{4};
frc::PWMSparkMax m_leftLeader{1};
frc::PWMSparkMax m_leftFollower{2};
frc::PWMSparkMax m_rightLeader{3};
frc::PWMSparkMax m_rightFollower{4};
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -52,10 +52,10 @@ class Drivetrain {
static constexpr units::meter_t kWheelRadius = 0.0508_m;
static constexpr int kEncoderResolution = 4096;
frc::PWMVictorSPX m_leftLeader{1};
frc::PWMVictorSPX m_leftFollower{2};
frc::PWMVictorSPX m_rightLeader{3};
frc::PWMVictorSPX m_rightFollower{4};
frc::PWMSparkMax m_leftLeader{1};
frc::PWMSparkMax m_leftFollower{2};
frc::PWMSparkMax m_rightLeader{3};
frc::PWMSparkMax m_rightFollower{4};
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};

View File

@@ -4,7 +4,7 @@
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/trajectory/TrapezoidProfile.h>
@@ -37,7 +37,7 @@ class Robot : public frc::TimedRobot {
private:
frc::Joystick m_joystick{1};
frc::Encoder m_encoder{1, 2};
frc::PWMVictorSPX m_motor{1};
frc::PWMSparkMax m_motor{1};
// Create a PID controller whose setpoint's change is subject to maximum
// velocity and acceleration constraints.

View File

@@ -5,7 +5,7 @@
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/RobotController.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
@@ -48,7 +48,7 @@ class Robot : public frc::TimedRobot {
// Standard classes for controlling our elevator
frc2::PIDController m_controller{kElevatorKp, 0, 0};
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::Joystick m_joystick{kJoystickPort};
// Simulation classes help us simulate what's going on, including gravity.

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -70,10 +70,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc2/command/PIDSubsystem.h>
#include <units/angle.h>
@@ -25,8 +25,8 @@ class ShooterSubsystem : public frc2::PIDSubsystem {
void StopFeeder();
private:
frc::PWMVictorSPX m_shooterMotor;
frc::PWMVictorSPX m_feederMotor;
frc::PWMSparkMax m_shooterMotor;
frc::PWMSparkMax m_feederMotor;
frc::Encoder m_shooterEncoder;
frc::SimpleMotorFeedforward<units::turns> m_shooterFeedforward;
};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/DigitalInput.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc2/command/SubsystemBase.h>
/**
@@ -50,6 +50,6 @@ class Claw : public frc2::SubsystemBase {
void Periodic() override;
private:
frc::PWMVictorSPX m_motor{7};
frc::PWMSparkMax m_motor{7};
frc::DigitalInput m_contact{5};
};

View File

@@ -7,7 +7,7 @@
#include <frc/AnalogGyro.h>
#include <frc/AnalogInput.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -64,12 +64,12 @@ class DriveTrain : public frc2::SubsystemBase {
void Periodic() override;
private:
frc::PWMVictorSPX m_frontLeft{1};
frc::PWMVictorSPX m_rearLeft{2};
frc::PWMSparkMax m_frontLeft{1};
frc::PWMSparkMax m_rearLeft{2};
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
frc::PWMVictorSPX m_frontRight{3};
frc::PWMVictorSPX m_rearRight{4};
frc::PWMSparkMax m_frontRight{3};
frc::PWMSparkMax m_rearRight{4};
frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
frc::DifferentialDrive m_robotDrive{m_left, m_right};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/AnalogPotentiometer.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc2/command/PIDSubsystem.h>
/**
@@ -43,7 +43,7 @@ class Elevator : public frc2::PIDSubsystem {
void Periodic() override;
private:
frc::PWMVictorSPX m_motor{5};
frc::PWMSparkMax m_motor{5};
double m_setpoint = 0;
// Conversion value of potentiometer varies between the real world and

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/AnalogPotentiometer.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc2/command/PIDSubsystem.h>
/**
@@ -40,7 +40,7 @@ class Wrist : public frc2::PIDSubsystem {
void Periodic() override;
private:
frc::PWMVictorSPX m_motor{6};
frc::PWMSparkMax m_motor{6};
double m_setpoint = 0;
// Conversion value of potentiometer varies between the real world and

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/drive/DifferentialDrive.h>
@@ -45,8 +45,8 @@ class Robot : public frc::TimedRobot {
private:
// Robot drive system
frc::PWMVictorSPX m_left{0};
frc::PWMVictorSPX m_right{1};
frc::PWMSparkMax m_left{0};
frc::PWMSparkMax m_right{1};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::Joystick m_stick{0};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/DifferentialDrive.h>
@@ -44,8 +44,8 @@ class Robot : public frc::TimedRobot {
static constexpr int kGyroPort = 0;
static constexpr int kJoystickPort = 0;
frc::PWMVictorSPX m_left{kLeftMotorPort};
frc::PWMVictorSPX m_right{kRightMotorPort};
frc::PWMSparkMax m_left{kLeftMotorPort};
frc::PWMSparkMax m_right{kRightMotorPort};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::AnalogGyro m_gyro{kGyroPort};

View File

@@ -6,7 +6,7 @@
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -86,10 +86,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -4,7 +4,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/MecanumDrive.h>
@@ -44,10 +44,10 @@ class Robot : public frc::TimedRobot {
static constexpr int kGyroPort = 0;
static constexpr int kJoystickPort = 0;
frc::PWMVictorSPX m_frontLeft{kFrontLeftMotorPort};
frc::PWMVictorSPX m_rearLeft{kRearLeftMotorPort};
frc::PWMVictorSPX m_frontRight{kFrontRightMotorPort};
frc::PWMVictorSPX m_rearRight{kRearRightMotorPort};
frc::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
frc::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
frc::PWMSparkMax m_frontRight{kFrontRightMotorPort};
frc::PWMSparkMax m_rearRight{kRearRightMotorPort};
frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
m_rearRight};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -70,10 +70,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
@@ -70,10 +70,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/geometry/Translation2d.h>
@@ -35,10 +35,10 @@ class Drivetrain {
wpi::math::pi}; // 1/2 rotation per second
private:
frc::PWMVictorSPX m_frontLeftMotor{1};
frc::PWMVictorSPX m_frontRightMotor{2};
frc::PWMVictorSPX m_backLeftMotor{3};
frc::PWMVictorSPX m_backRightMotor{4};
frc::PWMSparkMax m_frontLeftMotor{1};
frc::PWMSparkMax m_frontRightMotor{2};
frc::PWMSparkMax m_backLeftMotor{3};
frc::PWMSparkMax m_backRightMotor{4};
frc::Encoder m_frontLeftEncoder{0, 1};
frc::Encoder m_frontRightEncoder{2, 3};

View File

@@ -6,7 +6,7 @@
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/drive/MecanumDrive.h>
#include <frc/geometry/Pose2d.h>
#include <frc/geometry/Rotation2d.h>
@@ -135,10 +135,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_frontLeft;
frc::PWMVictorSPX m_rearLeft;
frc::PWMVictorSPX m_frontRight;
frc::PWMVictorSPX m_rearRight;
frc::PWMSparkMax m_frontLeft;
frc::PWMSparkMax m_rearLeft;
frc::PWMSparkMax m_frontRight;
frc::PWMSparkMax m_rearRight;
// The robot's drive
frc::MecanumDrive m_drive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/MecanumDrive.h>
@@ -35,10 +35,10 @@ class Robot : public frc::TimedRobot {
static constexpr int kJoystickChannel = 0;
frc::PWMVictorSPX m_frontLeft{kFrontLeftChannel};
frc::PWMVictorSPX m_rearLeft{kRearLeftChannel};
frc::PWMVictorSPX m_frontRight{kFrontRightChannel};
frc::PWMVictorSPX m_rearRight{kRearRightChannel};
frc::PWMSparkMax m_frontLeft{kFrontLeftChannel};
frc::PWMSparkMax m_rearLeft{kRearLeftChannel};
frc::PWMSparkMax m_frontRight{kFrontRightChannel};
frc::PWMSparkMax m_rearRight{kRearRightChannel};
frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
m_rearRight};

View File

@@ -17,7 +17,7 @@ frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
std::function<void(units::meters_per_second_t, const frc::Encoder&,
frc2::PIDController&, frc::PWMVictorSPX&)>
frc2::PIDController&, frc::PWMSparkMax&)>
calcAndSetSpeeds =
[&m_feedforward = m_feedforward](units::meters_per_second_t speed,
const auto& encoder,

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/estimator/MecanumDrivePoseEstimator.h>
@@ -35,10 +35,10 @@ class Drivetrain {
wpi::math::pi}; // 1/2 rotation per second
private:
frc::PWMVictorSPX m_frontLeftMotor{1};
frc::PWMVictorSPX m_frontRightMotor{2};
frc::PWMVictorSPX m_backLeftMotor{3};
frc::PWMVictorSPX m_backRightMotor{4};
frc::PWMSparkMax m_frontLeftMotor{1};
frc::PWMSparkMax m_frontRightMotor{2};
frc::PWMSparkMax m_backLeftMotor{3};
frc::PWMSparkMax m_backRightMotor{4};
frc::Encoder m_frontLeftEncoder{0, 1};
frc::Encoder m_frontRightEncoder{2, 3};

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
/**
@@ -20,7 +20,7 @@ class Robot : public frc::TimedRobot {
private:
frc::Joystick m_stick{0};
frc::PWMVictorSPX m_motor{0};
frc::PWMSparkMax m_motor{0};
};
#ifndef RUNNING_FRC_TESTS

View File

@@ -4,7 +4,7 @@
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/smartdashboard/SmartDashboard.h>
#include <wpi/math>
@@ -40,7 +40,7 @@ class Robot : public frc::TimedRobot {
private:
frc::Joystick m_stick{0};
frc::PWMVictorSPX m_motor{0};
frc::PWMSparkMax m_motor{0};
frc::Encoder m_encoder{0, 1};
};

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/DigitalInput.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/Solenoid.h>
#include <frc/commands/Subsystem.h>
@@ -66,7 +66,7 @@ class Collector : public frc::Subsystem {
private:
// Subsystem devices
frc::PWMVictorSPX m_rollerMotor{6};
frc::PWMSparkMax m_rollerMotor{6};
frc::DigitalInput m_ballDetector{10};
frc::Solenoid m_piston{1};
frc::DigitalInput m_openDetector{6};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/commands/Subsystem.h>
#include <frc/drive/DifferentialDrive.h>
@@ -60,12 +60,12 @@ class DriveTrain : public frc::Subsystem {
private:
// Subsystem devices
frc::PWMVictorSPX m_frontLeftCIM{1};
frc::PWMVictorSPX m_rearLeftCIM{2};
frc::PWMSparkMax m_frontLeftCIM{1};
frc::PWMSparkMax m_rearLeftCIM{2};
frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
frc::PWMVictorSPX m_frontRightCIM{3};
frc::PWMVictorSPX m_rearRightCIM{4};
frc::PWMSparkMax m_frontRightCIM{3};
frc::PWMSparkMax m_rearRightCIM{4};
frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogPotentiometer.h>
#include <frc/DigitalInput.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/commands/PIDSubsystem.h>
/**
@@ -67,5 +67,5 @@ class Pivot : public frc::PIDSubsystem {
frc::AnalogPotentiometer m_pot{1};
// Motor to move the pivot
frc::PWMVictorSPX m_motor{5};
frc::PWMSparkMax m_motor{5};
};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogInput.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
@@ -62,7 +62,7 @@ class Robot : public frc::TimedRobot {
frc::AnalogInput m_potentiometer{kPotChannel};
frc::Joystick m_joystick{kJoystickChannel};
frc::PWMVictorSPX m_elevatorMotor{kMotorChannel};
frc::PWMSparkMax m_elevatorMotor{kMotorChannel};
frc2::PIDController m_pidController{kP, kI, kD};
};

View File

@@ -6,7 +6,7 @@
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/geometry/Pose2d.h>
@@ -117,10 +117,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
frc::PWMSparkMax m_left1;
frc::PWMSparkMax m_left2;
frc::PWMSparkMax m_right1;
frc::PWMSparkMax m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -52,10 +52,10 @@ class Drivetrain {
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
frc::PWMVictorSPX m_leftLeader{1};
frc::PWMVictorSPX m_leftFollower{2};
frc::PWMVictorSPX m_rightLeader{3};
frc::PWMVictorSPX m_rightFollower{4};
frc::PWMSparkMax m_leftLeader{1};
frc::PWMSparkMax m_leftFollower{2};
frc::PWMSparkMax m_rightLeader{3};
frc::PWMSparkMax m_rightFollower{4};
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};

View File

@@ -5,7 +5,7 @@
#include <frc/AnalogPotentiometer.h>
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/shuffleboard/Shuffleboard.h>
@@ -61,9 +61,9 @@ class Robot : public frc::TimedRobot {
}
private:
frc::PWMVictorSPX m_left{0};
frc::PWMVictorSPX m_right{1};
frc::PWMVictorSPX m_elevatorMotor{2};
frc::PWMSparkMax m_left{0};
frc::PWMSparkMax m_right{1};
frc::PWMSparkMax m_elevatorMotor{2};
frc::DifferentialDrive m_robotDrive{m_left, m_right};

View File

@@ -6,7 +6,7 @@
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -68,10 +68,10 @@ class Drivetrain {
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
frc::PWMVictorSPX m_leftLeader{1};
frc::PWMVictorSPX m_leftFollower{2};
frc::PWMVictorSPX m_rightLeader{3};
frc::PWMVictorSPX m_rightFollower{4};
frc::PWMSparkMax m_leftLeader{1};
frc::PWMSparkMax m_leftFollower{2};
frc::PWMSparkMax m_rightLeader{3};
frc::PWMSparkMax m_rightFollower{4};
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};

View File

@@ -4,7 +4,7 @@
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
@@ -84,7 +84,7 @@ class Robot : public frc::TimedRobot {
// An encoder set up to measure arm position in radians per second.
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::XboxController m_joystick{kJoystickPort};
frc::TrapezoidProfile<units::radians>::Constraints m_constraints{

View File

@@ -6,7 +6,7 @@
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/geometry/Pose2d.h>
@@ -128,10 +128,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
// declared private and exposed only through public methods.
// The motor controllers
frc::PWMVictorSPX m_left1{DriveConstants::kLeftMotor1Port};
frc::PWMVictorSPX m_left2{DriveConstants::kLeftMotor2Port};
frc::PWMVictorSPX m_right1{DriveConstants::kRightMotor1Port};
frc::PWMVictorSPX m_right2{DriveConstants::kRightMotor2Port};
frc::PWMSparkMax m_left1{DriveConstants::kLeftMotor1Port};
frc::PWMSparkMax m_left2{DriveConstants::kLeftMotor2Port};
frc::PWMSparkMax m_right1{DriveConstants::kRightMotor1Port};
frc::PWMSparkMax m_right2{DriveConstants::kRightMotor2Port};
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};

View File

@@ -4,7 +4,7 @@
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
@@ -81,7 +81,7 @@ class Robot : public frc::TimedRobot {
// An encoder set up to measure elevator height in meters.
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::XboxController m_joystick{kJoystickPort};
frc::TrapezoidProfile<units::meters>::Constraints m_constraints{3_fps,

View File

@@ -5,7 +5,7 @@
#include <frc/DriverStation.h>
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
@@ -77,7 +77,7 @@ class Robot : public frc::TimedRobot {
// An encoder set up to measure flywheel velocity in radians per second.
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::XboxController m_joystick{kJoystickPort};
public:

View File

@@ -5,7 +5,7 @@
#include <frc/DriverStation.h>
#include <frc/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
@@ -78,7 +78,7 @@ class Robot : public frc::TimedRobot {
// An encoder set up to measure flywheel velocity in radians per second.
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::PWMSparkMax m_motor{kMotorPort};
frc::XboxController m_joystick{kJoystickPort};
public:

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -31,8 +31,8 @@ class SwerveModule {
static constexpr auto kModuleMaxAngularAcceleration =
wpi::math::pi * 2_rad_per_s / 1_s; // radians per second^2
frc::PWMVictorSPX m_driveMotor;
frc::PWMVictorSPX m_turningMotor;
frc::PWMSparkMax m_driveMotor;
frc::PWMSparkMax m_turningMotor;
frc::Encoder m_driveEncoder{0, 1};
frc::Encoder m_turningEncoder{2, 3};

View File

@@ -6,7 +6,7 @@
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/drive/MecanumDrive.h>
#include <frc/geometry/Pose2d.h>
#include <frc/geometry/Rotation2d.h>

View File

@@ -5,7 +5,7 @@
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -31,8 +31,8 @@ class SwerveModule {
static constexpr auto kModuleMaxAngularAcceleration =
wpi::math::pi * 2_rad_per_s / 1_s; // radians per second^2
frc::PWMVictorSPX m_driveMotor;
frc::PWMVictorSPX m_turningMotor;
frc::PWMSparkMax m_driveMotor;
frc::PWMSparkMax m_turningMotor;
frc::Encoder m_driveEncoder{0, 1};
frc::Encoder m_turningEncoder{2, 3};

View File

@@ -3,7 +3,7 @@
// the WPILib BSD license file in the root directory of this project.
#include <frc/GenericHID.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
#include <frc/drive/DifferentialDrive.h>
@@ -13,8 +13,8 @@
* Runs the motors with tank steering and an Xbox controller.
*/
class Robot : public frc::TimedRobot {
frc::PWMVictorSPX m_leftMotor{0};
frc::PWMVictorSPX m_rightMotor{1};
frc::PWMSparkMax m_leftMotor{0};
frc::PWMSparkMax m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::XboxController m_driverController{0};

View File

@@ -4,7 +4,7 @@
#include <frc/AnalogInput.h>
#include <frc/MedianFilter.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/drive/DifferentialDrive.h>
@@ -49,8 +49,8 @@ class Robot : public frc::TimedRobot {
frc::AnalogInput m_ultrasonic{kUltrasonicPort};
frc::PWMVictorSPX m_left{kLeftMotorPort};
frc::PWMVictorSPX m_right{kRightMotorPort};
frc::PWMSparkMax m_left{kLeftMotorPort};
frc::PWMSparkMax m_right{kRightMotorPort};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
};

View File

@@ -4,7 +4,7 @@
#include <frc/AnalogInput.h>
#include <frc/MedianFilter.h>
#include <frc/PWMVictorSPX.h>
#include <frc/PWMSparkMax.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
#include <frc/drive/DifferentialDrive.h>
@@ -55,8 +55,8 @@ class Robot : public frc::TimedRobot {
frc::AnalogInput m_ultrasonic{kUltrasonicPort};
frc::PWMVictorSPX m_left{kLeftMotorPort};
frc::PWMVictorSPX m_right{kRightMotorPort};
frc::PWMSparkMax m_left{kLeftMotorPort};
frc::PWMSparkMax m_right{kRightMotorPort};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc2::PIDController m_pidController{kP, kI, kD};