From 5ecbf82a4e6a51b42ba161953a9996ba5b1b3b7a Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Thu, 14 Dec 2023 21:09:42 -0800 Subject: [PATCH 01/10] [wpilib] Replace MotorController interface with functional interface --- .../native/cpp/drive/DifferentialDrive.cpp | 39 ++++---- .../main/native/cpp/drive/MecanumDrive.cpp | 64 ++++++++------ .../cpp/motorcontrol/MotorControllerGroup.cpp | 4 + .../cpp/motorcontrol/NidecBrushless.cpp | 4 + .../cpp/motorcontrol/PWMMotorController.cpp | 25 +++++- .../include/frc/drive/DifferentialDrive.h | 69 ++++++--------- .../native/include/frc/drive/MecanumDrive.h | 35 +++++++- .../frc/motorcontrol/MotorController.h | 3 +- .../frc/motorcontrol/MotorControllerGroup.h | 14 ++- .../include/frc/motorcontrol/NidecBrushless.h | 5 ++ .../frc/motorcontrol/PWMMotorController.h | 29 ++++++ .../cpp/drive/DifferentialDriveTest.cpp | 44 ++++++---- .../native/cpp/drive/MecanumDriveTest.cpp | 41 +++++---- .../motorcontrol/MockPWMMotorController.cpp | 31 +++++++ .../motorcontrol/MotorControllerGroupTest.cpp | 5 ++ .../motorcontrol/MockMotorController.h | 6 ++ .../motorcontrol/MockPWMMotorController.h | 23 +++++ .../cpp/examples/ArcadeDrive/cpp/Robot.cpp | 4 +- .../ArcadeDriveXboxController/cpp/Robot.cpp | 4 +- .../ArmBot/cpp/subsystems/DriveSubsystem.cpp | 6 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../cpp/subsystems/DriveSubsystem.cpp | 6 +- .../include/ExampleSmartMotorController.h | 16 ++-- .../include/subsystems/DriveSubsystem.h | 10 +-- .../DifferentialDriveBot/cpp/Drivetrain.cpp | 4 +- .../DifferentialDriveBot/include/Drivetrain.h | 9 +- .../cpp/Drivetrain.cpp | 13 +-- .../include/Drivetrain.h | 4 - .../include/ExampleSmartMotorController.h | 16 ++-- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/ExampleSmartMotorController.h | 16 ++-- .../include/ExampleSmartMotorController.h | 16 ++-- .../cpp/subsystems/DriveSubsystem.cpp | 5 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../GearsBot/cpp/subsystems/Drivetrain.cpp | 5 +- .../GearsBot/include/subsystems/Drivetrain.h | 7 +- .../cpp/examples/GettingStarted/cpp/Robot.cpp | 4 +- .../src/main/cpp/examples/Gyro/cpp/Robot.cpp | 3 +- .../cpp/subsystems/DriveSubsystem.cpp | 5 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../cpp/examples/GyroMecanum/cpp/Robot.cpp | 7 +- .../cpp/subsystems/DriveSubsystem.cpp | 5 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../cpp/subsystems/DriveSubsystem.cpp | 5 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../include/subsystems/DriveSubsystem.h | 5 +- .../cpp/examples/MecanumDrive/cpp/Robot.cpp | 7 +- .../cpp/subsystems/DriveSubsystem.cpp | 9 +- .../include/subsystems/DriveSubsystem.h | 10 +-- .../RamseteController/cpp/Drivetrain.cpp | 4 +- .../RamseteController/include/Drivetrain.h | 9 +- .../cpp/subsystems/Drive.cpp | 5 +- .../include/subsystems/Drive.h | 8 +- .../include/subsystems/Drivetrain.h | 4 +- .../cpp/examples/ShuffleBoard/cpp/Robot.cpp | 4 +- .../cpp/Drivetrain.cpp | 8 +- .../include/Drivetrain.h | 11 ++- .../cpp/subsystems/DriveSubsystem.cpp | 16 ++-- .../include/subsystems/DriveSubsystem.h | 10 +-- .../main/cpp/examples/TankDrive/cpp/Robot.cpp | 4 +- .../TankDriveXboxController/cpp/Robot.cpp | 4 +- .../examples/UltrasonicPID/include/Robot.h | 4 +- .../include/subsystems/Drivetrain.h | 4 +- .../src/main/native/cpp/MotorEncoderTest.cpp | 5 ++ .../main/native/cpp/MotorInvertingTest.cpp | 6 ++ .../wpilibj/drive/DifferentialDrive.java | 88 ++++++++----------- .../wpi/first/wpilibj/drive/MecanumDrive.java | 69 ++++++++++----- .../wpilibj/motorcontrol/MotorController.java | 7 +- .../motorcontrol/MotorControllerGroup.java | 9 +- .../wpilibj/motorcontrol/NidecBrushless.java | 1 + .../motorcontrol/PWMMotorController.java | 22 ++++- .../wpilibj/drive/DifferentialDriveTest.java | 38 ++++---- .../first/wpilibj/drive/MecanumDriveTest.java | 32 +++---- .../motorcontrol/MockMotorController.java | 1 + .../motorcontrol/MockPWMMotorController.java | 8 +- .../MotorControllerGroupTest.java | 1 + .../wpilibj/examples/arcadedrive/Robot.java | 3 +- .../arcadedrivexboxcontroller/Robot.java | 3 +- .../armbot/subsystems/DriveSubsystem.java | 21 +++-- .../ExampleSmartMotorController.java | 10 +-- .../subsystems/DriveSubsystem.java | 21 +++-- .../differentialdrivebot/Drivetrain.java | 24 +++-- .../Drivetrain.java | 28 +++--- .../ExampleSmartMotorController.java | 10 +-- .../subsystems/DriveSubsystem.java | 8 +- .../ExampleSmartMotorController.java | 10 +-- .../examples/elevatorprofiledpid/Robot.java | 3 +- .../ExampleSmartMotorController.java | 10 +-- .../wpilibj/examples/eventloop/Robot.java | 7 +- .../frisbeebot/subsystems/DriveSubsystem.java | 21 +++-- .../gearsbot/subsystems/Drivetrain.java | 29 +++--- .../examples/gettingstarted/Robot.java | 3 +- .../first/wpilibj/examples/gyro/Robot.java | 3 +- .../subsystems/DriveSubsystem.java | 21 +++-- .../subsystems/DriveSubsystem.java | 21 +++-- .../subsystems/DriveSubsystem.java | 21 +++-- .../examples/mecanumbot/Drivetrain.java | 9 +- .../mecanumdriveposeestimator/Drivetrain.java | 9 +- .../wpilibj/examples/motorcontrol/Robot.java | 3 +- .../subsystems/DriveSubsystem.java | 25 +++--- .../ramsetecontroller/Drivetrain.java | 24 +++-- .../subsystems/Drive.java | 21 +++-- .../romireference/subsystems/Drivetrain.java | 3 +- .../wpilibj/examples/shuffleboard/Robot.java | 4 +- .../Drivetrain.java | 21 ++--- .../wpilibj/examples/statespacearm/Robot.java | 3 +- .../subsystems/DriveSubsystem.java | 29 +++--- .../examples/statespaceelevator/Robot.java | 3 +- .../examples/statespaceflywheel/Robot.java | 3 +- .../statespaceflywheelsysid/Robot.java | 3 +- .../examples/swervebot/SwerveModule.java | 5 +- .../SwerveModule.java | 5 +- .../wpilibj/examples/tankdrive/Robot.java | 7 +- .../tankdrivexboxcontroller/Robot.java | 3 +- .../wpilibj/examples/ultrasonicpid/Robot.java | 3 +- .../xrpreference/subsystems/Drivetrain.java | 3 +- .../subsystems/RomiDrivetrain.java | 3 +- .../romieducational/RomiDrivetrain.java | 3 +- .../templates/romitimed/RomiDrivetrain.java | 3 +- .../subsystems/XRPDrivetrain.java | 3 +- .../xrpeducational/XRPDrivetrain.java | 3 +- .../templates/xrptimed/XRPDrivetrain.java | 3 +- .../wpilibj/fixtures/MotorEncoderFixture.java | 1 + .../edu/wpi/first/wpilibj/xrp/XRPMotor.java | 1 + .../src/main/native/cpp/xrp/XRPMotor.cpp | 6 ++ .../main/native/include/frc/xrp/XRPMotor.h | 5 ++ 126 files changed, 875 insertions(+), 697 deletions(-) create mode 100644 wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp create mode 100644 wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.h rename wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java => wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockPWMMotorController.java (83%) diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index b72b22b80c2..b50e9c484db 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -16,11 +16,20 @@ using namespace frc; +WPI_IGNORE_DEPRECATED + DifferentialDrive::DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor) - : m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) { - wpi::SendableRegistry::AddChild(this, m_leftMotor); - wpi::SendableRegistry::AddChild(this, m_rightMotor); + : DifferentialDrive{[&](double output) { leftMotor.Set(output); }, + [&](double output) { rightMotor.Set(output); }} {} + +WPI_UNIGNORE_DEPRECATED + +DifferentialDrive::DifferentialDrive(std::function leftMotor, + std::function rightMotor) + : m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} { + // wpi::SendableRegistry::AddChild(this, m_leftMotor); + // wpi::SendableRegistry::AddChild(this, m_rightMotor); static int instances = 0; ++instances; wpi::SendableRegistry::AddLW(this, "DifferentialDrive", instances); @@ -40,8 +49,8 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, auto [left, right] = ArcadeDriveIK(xSpeed, zRotation, squareInputs); - m_leftMotor->Set(left * m_maxOutput); - m_rightMotor->Set(right * m_maxOutput); + m_leftMotor(left * m_maxOutput); + m_rightMotor(right * m_maxOutput); Feed(); } @@ -60,8 +69,8 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation, auto [left, right] = CurvatureDriveIK(xSpeed, zRotation, allowTurnInPlace); - m_leftMotor->Set(left * m_maxOutput); - m_rightMotor->Set(right * m_maxOutput); + m_leftMotor(left * m_maxOutput); + m_rightMotor(right * m_maxOutput); Feed(); } @@ -80,8 +89,8 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed, auto [left, right] = TankDriveIK(leftSpeed, rightSpeed, squareInputs); - m_leftMotor->Set(left * m_maxOutput); - m_rightMotor->Set(right * m_maxOutput); + m_leftMotor(left * m_maxOutput); + m_rightMotor(right * m_maxOutput); Feed(); } @@ -157,8 +166,8 @@ DifferentialDrive::WheelSpeeds DifferentialDrive::TankDriveIK( } void DifferentialDrive::StopMotor() { - m_leftMotor->StopMotor(); - m_rightMotor->StopMotor(); + m_leftMotor(0.0); + m_rightMotor(0.0); Feed(); } @@ -170,10 +179,6 @@ void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("DifferentialDrive"); builder.SetActuator(true); builder.SetSafeState([=, this] { StopMotor(); }); - builder.AddDoubleProperty( - "Left Motor Speed", [=, this] { return m_leftMotor->Get(); }, - [=, this](double value) { m_leftMotor->Set(value); }); - builder.AddDoubleProperty( - "Right Motor Speed", [=, this] { return m_rightMotor->Get(); }, - [=, this](double value) { m_rightMotor->Set(value); }); + builder.AddDoubleProperty("Left Motor Speed", nullptr, m_leftMotor); + builder.AddDoubleProperty("Right Motor Speed", nullptr, m_rightMotor); } diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 2bf6a3f3c49..492bf8e345c 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -16,18 +16,31 @@ using namespace frc; +WPI_IGNORE_DEPRECATED + MecanumDrive::MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor, MotorController& frontRightMotor, MotorController& rearRightMotor) - : m_frontLeftMotor(&frontLeftMotor), - m_rearLeftMotor(&rearLeftMotor), - m_frontRightMotor(&frontRightMotor), - m_rearRightMotor(&rearRightMotor) { - wpi::SendableRegistry::AddChild(this, m_frontLeftMotor); - wpi::SendableRegistry::AddChild(this, m_rearLeftMotor); - wpi::SendableRegistry::AddChild(this, m_frontRightMotor); - wpi::SendableRegistry::AddChild(this, m_rearRightMotor); + : MecanumDrive{[&](double output) { frontLeftMotor.Set(output); }, + [&](double output) { rearLeftMotor.Set(output); }, + [&](double output) { frontRightMotor.Set(output); }, + [&](double output) { rearRightMotor.Set(output); }} {} + +WPI_UNIGNORE_DEPRECATED + +MecanumDrive::MecanumDrive(std::function frontLeftMotor, + std::function rearLeftMotor, + std::function frontRightMotor, + std::function rearRightMotor) + : m_frontLeftMotor{std::move(frontLeftMotor)}, + m_rearLeftMotor{std::move(rearLeftMotor)}, + m_frontRightMotor{std::move(frontRightMotor)}, + m_rearRightMotor{std::move(rearRightMotor)} { + // wpi::SendableRegistry::AddChild(this, m_frontLeftMotor); + // wpi::SendableRegistry::AddChild(this, m_rearLeftMotor); + // wpi::SendableRegistry::AddChild(this, m_frontRightMotor); + // wpi::SendableRegistry::AddChild(this, m_rearRightMotor); static int instances = 0; ++instances; wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances); @@ -47,10 +60,10 @@ void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, auto [frontLeft, frontRight, rearLeft, rearRight] = DriveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); - m_frontLeftMotor->Set(frontLeft * m_maxOutput); - m_frontRightMotor->Set(frontRight * m_maxOutput); - m_rearLeftMotor->Set(rearLeft * m_maxOutput); - m_rearRightMotor->Set(rearRight * m_maxOutput); + m_frontLeftMotor(frontLeft * m_maxOutput); + m_frontRightMotor(frontRight * m_maxOutput); + m_rearLeftMotor(rearLeft * m_maxOutput); + m_rearRightMotor(rearRight * m_maxOutput); Feed(); } @@ -68,10 +81,10 @@ void MecanumDrive::DrivePolar(double magnitude, Rotation2d angle, } void MecanumDrive::StopMotor() { - m_frontLeftMotor->StopMotor(); - m_frontRightMotor->StopMotor(); - m_rearLeftMotor->StopMotor(); - m_rearRightMotor->StopMotor(); + m_frontLeftMotor(0.0); + m_frontRightMotor(0.0); + m_rearLeftMotor(0.0); + m_rearRightMotor(0.0); Feed(); } @@ -107,16 +120,11 @@ void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("MecanumDrive"); builder.SetActuator(true); builder.SetSafeState([=, this] { StopMotor(); }); - builder.AddDoubleProperty( - "Front Left Motor Speed", [=, this] { return m_frontLeftMotor->Get(); }, - [=, this](double value) { m_frontLeftMotor->Set(value); }); - builder.AddDoubleProperty( - "Front Right Motor Speed", [=, this] { return m_frontRightMotor->Get(); }, - [=, this](double value) { m_frontRightMotor->Set(value); }); - builder.AddDoubleProperty( - "Rear Left Motor Speed", [=, this] { return m_rearLeftMotor->Get(); }, - [=, this](double value) { m_rearLeftMotor->Set(value); }); - builder.AddDoubleProperty( - "Rear Right Motor Speed", [=, this] { return m_rearRightMotor->Get(); }, - [=, this](double value) { m_rearRightMotor->Set(value); }); + builder.AddDoubleProperty("Front Left Motor Speed", nullptr, + m_frontLeftMotor); + builder.AddDoubleProperty("Front Right Motor Speed", nullptr, + m_frontRightMotor); + builder.AddDoubleProperty("Rear Left Motor Speed", nullptr, m_rearLeftMotor); + builder.AddDoubleProperty("Rear Right Motor Speed", nullptr, + m_rearRightMotor); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp index f855d14b0ee..cf57f7c55b2 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp @@ -12,6 +12,8 @@ using namespace frc; // Can't use a delegated constructor here because of an MSVC bug. // https://developercommunity.visualstudio.com/content/problem/583/compiler-bug-with-delegating-a-constructor.html +WPI_IGNORE_DEPRECATED + MotorControllerGroup::MotorControllerGroup( std::vector>&& motorControllers) : m_motorControllers(std::move(motorControllers)) { @@ -74,3 +76,5 @@ void MotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) { "Value", [=, this] { return Get(); }, [=, this](double value) { Set(value); }); } + +WPI_UNIGNORE_DEPRECATED diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp index f25aa9180bf..a05b7cc8416 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp @@ -11,6 +11,8 @@ using namespace frc; +WPI_IGNORE_DEPRECATED + NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) : m_dio(dioChannel), m_pwm(pwmChannel) { wpi::SendableRegistry::AddChild(this, &m_dio); @@ -26,6 +28,8 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel); } +WPI_UNIGNORE_DEPRECATED + void NidecBrushless::Set(double speed) { if (!m_disabled) { m_speed = speed; diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp index 3692f757b12..1690138c01e 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp @@ -8,13 +8,28 @@ #include #include +#include "frc/RobotController.h" + using namespace frc; void PWMMotorController::Set(double speed) { - m_pwm.SetSpeed(m_isInverted ? -speed : speed); + if (m_isInverted) { + speed = -speed; + } + m_pwm.SetSpeed(speed); + + for (auto& follower : m_followers) { + follower->Set(speed); + } + Feed(); } +void PWMMotorController::SetVoltage(units::volt_t output) { + // NOLINTNEXTLINE(bugprone-integer-division) + Set(output / RobotController::GetBatteryVoltage()); +} + double PWMMotorController::Get() const { return m_pwm.GetSpeed() * (m_isInverted ? -1.0 : 1.0); } @@ -48,11 +63,19 @@ void PWMMotorController::EnableDeadbandElimination(bool eliminateDeadband) { m_pwm.EnableDeadbandElimination(eliminateDeadband); } +void PWMMotorController::AddFollower(PWMMotorController& follower) { + m_followers.emplace_back(&follower); +} + +WPI_IGNORE_DEPRECATED + PWMMotorController::PWMMotorController(std::string_view name, int channel) : m_pwm(channel, false) { wpi::SendableRegistry::AddLW(this, name, channel); } +WPI_UNIGNORE_DEPRECATED + void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index 2e701a38179..c258e3869e9 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -4,8 +4,10 @@ #pragma once +#include #include +#include #include #include @@ -20,43 +22,9 @@ class MotorController; * the Kit of Parts drive base, "tank drive", or West Coast Drive. * * These drive bases typically have drop-center / skid-steer with two or more - * wheels per side (e.g., 6WD or 8WD). This class takes a MotorController per - * side. For four and six motor drivetrains, construct and pass in - * MotorControllerGroup instances as follows. - * - * Four motor drivetrain: - * @code{.cpp} - * class Robot { - * public: - * frc::PWMVictorSPX m_frontLeft{1}; - * frc::PWMVictorSPX m_rearLeft{2}; - * frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft}; - * - * frc::PWMVictorSPX m_frontRight{3}; - * frc::PWMVictorSPX m_rearRight{4}; - * frc::MotorControllerGroup m_right{m_frontRight, m_rearRight}; - * - * frc::DifferentialDrive m_drive{m_left, m_right}; - * }; - * @endcode - * - * Six motor drivetrain: - * @code{.cpp} - * class Robot { - * public: - * frc::PWMVictorSPX m_frontLeft{1}; - * frc::PWMVictorSPX m_midLeft{2}; - * frc::PWMVictorSPX m_rearLeft{3}; - * frc::MotorControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft}; - * - * frc::PWMVictorSPX m_frontRight{4}; - * frc::PWMVictorSPX m_midRight{5}; - * frc::PWMVictorSPX m_rearRight{6}; - * frc::MotorControllerGroup m_right{m_frontRight, m_midRight, m_rearRight}; - * - * frc::DifferentialDrive m_drive{m_left, m_right}; - * }; - * @endcode + * wheels per side (e.g., 6WD or 8WD). This class takes a setter per side. For + * four and six motor drivetrains, use CAN motor controller followers or + * PWMMotorController::AddFollower(). * * A differential drive robot has left and right wheels separated by an * arbitrary width. @@ -101,13 +69,34 @@ class DifferentialDrive : public RobotDriveBase, double right = 0.0; }; + WPI_IGNORE_DEPRECATED + + /** + * Construct a DifferentialDrive. + * + * To pass multiple motors per side, use CAN motor controller followers or + * PWMSpeedController::AddFollower(). If a motor needs to be inverted, do so + * before passing it in. + * + * @param leftMotor Left motor. + * @param rightMotor Right motor. + */ + WPI_DEPRECATED("Use DifferentialDrive constructor with function arguments.") + DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor); + + WPI_UNIGNORE_DEPRECATED + /** * Construct a DifferentialDrive. * * To pass multiple motors per side, use a MotorControllerGroup. If a motor * needs to be inverted, do so before passing it in. + * + * @param leftMotor Left motor setter. + * @param rightMotor Right motor setter. */ - DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor); + DifferentialDrive(std::function leftMotor, + std::function rightMotor); ~DifferentialDrive() override = default; @@ -210,8 +199,8 @@ class DifferentialDrive : public RobotDriveBase, void InitSendable(wpi::SendableBuilder& builder) override; private: - MotorController* m_leftMotor; - MotorController* m_rightMotor; + std::function m_leftMotor; + std::function m_rightMotor; }; } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h index f4c28f423d8..90c436eadac 100644 --- a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h @@ -4,10 +4,12 @@ #pragma once +#include #include #include #include +#include #include #include @@ -69,15 +71,40 @@ class MecanumDrive : public RobotDriveBase, double rearRight = 0.0; }; + WPI_IGNORE_DEPRECATED + /** * Construct a MecanumDrive. * * If a motor needs to be inverted, do so before passing it in. + * + * @param frontLeftMotor Front-left motor. + * @param rearLeftMotor Rear-left motor. + * @param frontRightMotor Front-right motor. + * @param rearRightMotor Rear-right motor. */ + WPI_DEPRECATED("Use MecanumDrive constructor with function arguments.") MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor, MotorController& frontRightMotor, MotorController& rearRightMotor); + WPI_UNIGNORE_DEPRECATED + + /** + * Construct a MecanumDrive. + * + * If a motor needs to be inverted, do so before passing it in. + * + * @param frontLeftMotor Front-left motor setter. + * @param rearLeftMotor Rear-left motor setter. + * @param frontRightMotor Front-right motor setter. + * @param rearRightMotor Rear-right motor setter. + */ + MecanumDrive(std::function frontLeftMotor, + std::function rearLeftMotor, + std::function frontRightMotor, + std::function rearRightMotor); + ~MecanumDrive() override = default; MecanumDrive(MecanumDrive&&) = default; @@ -141,10 +168,10 @@ class MecanumDrive : public RobotDriveBase, void InitSendable(wpi::SendableBuilder& builder) override; private: - MotorController* m_frontLeftMotor; - MotorController* m_rearLeftMotor; - MotorController* m_frontRightMotor; - MotorController* m_rearRightMotor; + std::function m_frontLeftMotor; + std::function m_rearLeftMotor; + std::function m_frontRightMotor; + std::function m_rearRightMotor; bool reported = false; }; diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h b/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h index 24e1b179554..1b3716d0f3b 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h @@ -11,7 +11,8 @@ namespace frc { /** * Interface for motor controlling devices. */ -class MotorController { +class [[deprecated( + "This class is being removed with no replacement")]] MotorController { public: virtual ~MotorController() = default; diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h b/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h index 99a9e4e164c..a429dda5b08 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h @@ -7,19 +7,25 @@ #include #include +#include #include #include #include "frc/motorcontrol/MotorController.h" +WPI_IGNORE_DEPRECATED + namespace frc { /** * Allows multiple MotorController objects to be linked together. */ -class MotorControllerGroup : public wpi::Sendable, - public MotorController, - public wpi::SendableHelper { +class [[deprecated( + "Use CAN motor controller followers or " + "PWMMotorController::AddFollower()")]] MotorControllerGroup + : public wpi::Sendable, + public MotorController, + public wpi::SendableHelper { public: template explicit MotorControllerGroup(MotorController& motorController, @@ -50,3 +56,5 @@ class MotorControllerGroup : public wpi::Sendable, } // namespace frc #include "frc/motorcontrol/MotorControllerGroup.inc" + +WPI_UNIGNORE_DEPRECATED diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h b/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h index cc95d7115d3..d50c836170f 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h @@ -6,6 +6,7 @@ #include +#include #include #include @@ -16,6 +17,8 @@ namespace frc { +WPI_IGNORE_DEPRECATED + /** * Nidec Brushless Motor. */ @@ -95,4 +98,6 @@ class NidecBrushless : public MotorController, double m_speed = 0.0; }; +WPI_UNIGNORE_DEPRECATED + } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h index bca5d7f64e7..7d79a087aa4 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h @@ -6,7 +6,10 @@ #include #include +#include +#include +#include #include #include @@ -17,6 +20,8 @@ namespace frc { class DMA; +WPI_IGNORE_DEPRECATED + /** * Common base class for all PWM Motor Controllers. */ @@ -40,6 +45,20 @@ class PWMMotorController : public MotorController, */ void Set(double value) override; + /** + * Sets the voltage output of the PWMMotorController. Compensates for + * the current bus voltage to ensure that the desired voltage is output even + * if the battery voltage is below 12V - highly useful when the voltage + * outputs are "meaningful" (e.g. they come from a feedforward calculation). + * + *

NOTE: This function *must* be called regularly in order for voltage + * compensation to work properly - unlike the ordinary set function, it is not + * "set it and forget it." + * + * @param output The voltage to output. + */ + void SetVoltage(units::volt_t output) override; + /** * Get the recently set value of the PWM. This value is affected by the * inversion property. If you want the value that is sent directly to the @@ -71,6 +90,13 @@ class PWMMotorController : public MotorController, */ void EnableDeadbandElimination(bool eliminateDeadband); + /** + * Make the given PWM motor controller follow the output of this one. + * + * @param follower The motor controller follower. + */ + void AddFollower(PWMMotorController& follower); + protected: /** * Constructor for a PWM Motor %Controller connected via PWM. @@ -87,8 +113,11 @@ class PWMMotorController : public MotorController, private: bool m_isInverted = false; + std::vector m_followers; PWM* GetPwm() { return &m_pwm; } }; +WPI_UNIGNORE_DEPRECATED + } // namespace frc diff --git a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp index f21f268f25b..9a22987ee02 100644 --- a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp +++ b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp @@ -5,7 +5,7 @@ #include #include "frc/drive/DifferentialDrive.h" -#include "motorcontrol/MockMotorController.h" +#include "motorcontrol/MockPWMMotorController.h" TEST(DifferentialDriveTest, ArcadeDriveIK) { // Forward @@ -240,9 +240,10 @@ TEST(DifferentialDriveTest, TankDriveIKSquared) { } TEST(DifferentialDriveTest, ArcadeDrive) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -277,9 +278,10 @@ TEST(DifferentialDriveTest, ArcadeDrive) { } TEST(DifferentialDriveTest, ArcadeDriveSquared) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -314,9 +316,10 @@ TEST(DifferentialDriveTest, ArcadeDriveSquared) { } TEST(DifferentialDriveTest, CurvatureDrive) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -351,9 +354,10 @@ TEST(DifferentialDriveTest, CurvatureDrive) { } TEST(DifferentialDriveTest, CurvatureDriveTurnInPlace) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -388,9 +392,10 @@ TEST(DifferentialDriveTest, CurvatureDriveTurnInPlace) { } TEST(DifferentialDriveTest, TankDrive) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -425,9 +430,10 @@ TEST(DifferentialDriveTest, TankDrive) { } TEST(DifferentialDriveTest, TankDriveSquared) { - frc::MockMotorController left; - frc::MockMotorController right; - frc::DifferentialDrive drive{left, right}; + frc::MockPWMMotorController left; + frc::MockPWMMotorController right; + frc::DifferentialDrive drive{[&](double output) { left.Set(output); }, + [&](double output) { right.Set(output); }}; drive.SetDeadband(0.0); // Forward diff --git a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp index 1bbf464106c..b32b03c8246 100644 --- a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp +++ b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp @@ -5,7 +5,7 @@ #include #include "frc/drive/MecanumDrive.h" -#include "motorcontrol/MockMotorController.h" +#include "motorcontrol/MockPWMMotorController.h" TEST(MecanumDriveTest, CartesianIK) { // Forward @@ -82,11 +82,14 @@ TEST(MecanumDriveTest, CartesianIKGyro90CW) { } TEST(MecanumDriveTest, Cartesian) { - frc::MockMotorController fl; - frc::MockMotorController rl; - frc::MockMotorController fr; - frc::MockMotorController rr; - frc::MecanumDrive drive{fl, rl, fr, rr}; + frc::MockPWMMotorController fl; + frc::MockPWMMotorController rl; + frc::MockPWMMotorController fr; + frc::MockPWMMotorController rr; + frc::MecanumDrive drive{[&](double output) { fl.Set(output); }, + [&](double output) { rl.Set(output); }, + [&](double output) { fr.Set(output); }, + [&](double output) { rr.Set(output); }}; drive.SetDeadband(0.0); // Forward @@ -126,11 +129,14 @@ TEST(MecanumDriveTest, Cartesian) { } TEST(MecanumDriveTest, CartesianGyro90CW) { - frc::MockMotorController fl; - frc::MockMotorController fr; - frc::MockMotorController rl; - frc::MockMotorController rr; - frc::MecanumDrive drive{fl, rl, fr, rr}; + frc::MockPWMMotorController fl; + frc::MockPWMMotorController rl; + frc::MockPWMMotorController fr; + frc::MockPWMMotorController rr; + frc::MecanumDrive drive{[&](double output) { fl.Set(output); }, + [&](double output) { rl.Set(output); }, + [&](double output) { fr.Set(output); }, + [&](double output) { rr.Set(output); }}; drive.SetDeadband(0.0); // Forward in global frame; left in robot frame @@ -170,11 +176,14 @@ TEST(MecanumDriveTest, CartesianGyro90CW) { } TEST(MecanumDriveTest, Polar) { - frc::MockMotorController fl; - frc::MockMotorController fr; - frc::MockMotorController rl; - frc::MockMotorController rr; - frc::MecanumDrive drive{fl, rl, fr, rr}; + frc::MockPWMMotorController fl; + frc::MockPWMMotorController rl; + frc::MockPWMMotorController fr; + frc::MockPWMMotorController rr; + frc::MecanumDrive drive{[&](double output) { fl.Set(output); }, + [&](double output) { rl.Set(output); }, + [&](double output) { fr.Set(output); }, + [&](double output) { rr.Set(output); }}; drive.SetDeadband(0.0); // Forward diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp new file mode 100644 index 00000000000..7a51f33b9a1 --- /dev/null +++ b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp @@ -0,0 +1,31 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "motorcontrol/MockPWMMotorController.h" + +using namespace frc; + +void MockPWMMotorController::Set(double speed) { + m_speed = m_isInverted ? -speed : speed; +} + +double MockPWMMotorController::Get() const { + return m_speed; +} + +void MockPWMMotorController::SetInverted(bool isInverted) { + m_isInverted = isInverted; +} + +bool MockPWMMotorController::GetInverted() const { + return m_isInverted; +} + +void MockPWMMotorController::Disable() { + m_speed = 0; +} + +void MockPWMMotorController::StopMotor() { + Disable(); +} diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp index 4ff889ad81e..740c46fe1a8 100644 --- a/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp +++ b/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp @@ -8,6 +8,7 @@ #include #include +#include #include "motorcontrol/MockMotorController.h" @@ -32,6 +33,8 @@ std::ostream& operator<<(std::ostream& os, return os; } +WPI_IGNORE_DEPRECATED + /** * A fixture used for MotorControllerGroup testing. */ @@ -124,3 +127,5 @@ TEST_P(MotorControllerGroupTest, StopMotor) { INSTANTIATE_TEST_SUITE_P(Tests, MotorControllerGroupTest, testing::Values(TEST_ONE, TEST_TWO, TEST_THREE)); + +WPI_UNIGNORE_DEPRECATED diff --git a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h index e17931fbb69..aab6ce47492 100644 --- a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h +++ b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.h @@ -4,10 +4,14 @@ #pragma once +#include + #include "frc/motorcontrol/MotorController.h" namespace frc { +WPI_IGNORE_DEPRECATED + class MockMotorController : public MotorController { public: void Set(double speed) override; @@ -22,4 +26,6 @@ class MockMotorController : public MotorController { bool m_isInverted = false; }; +WPI_UNIGNORE_DEPRECATED + } // namespace frc diff --git a/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.h b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.h new file mode 100644 index 00000000000..18bd1f56159 --- /dev/null +++ b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.h @@ -0,0 +1,23 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +namespace frc { + +class MockPWMMotorController { + public: + void Set(double speed); + double Get() const; + void SetInverted(bool isInverted); + bool GetInverted() const; + void Disable(); + void StopMotor(); + + private: + double m_speed = 0.0; + bool m_isInverted = false; +}; + +} // namespace frc diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp index b636b44b47f..067506bbfe8 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp @@ -14,7 +14,9 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::Joystick m_stick{0}; public: diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp index 23c9a569dd1..db97498a058 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp @@ -14,7 +14,9 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::XboxController m_driverController{0}; public: diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp index aeeac3ddf90..0ca95c0c218 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp @@ -13,13 +13,17 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); } void DriveSubsystem::Periodic() { diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h index 47bf28e4d91..47d3f3d49b2 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -75,14 +74,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp index 16409ad7a77..3c3f789d193 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp @@ -13,13 +13,17 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); } void DriveSubsystem::Periodic() { diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h index 5d55839892f..bd48d88e0bc 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h @@ -4,15 +4,13 @@ #pragma once -#include - /** * A simplified stub class that simulates the API of a common "smart" motor * controller. * *

Has no actual functionality. */ -class ExampleSmartMotorController : public frc::MotorController { +class ExampleSmartMotorController { public: enum PIDMode { kPosition, kVelocity, kMovementWitchcraft }; @@ -68,15 +66,15 @@ class ExampleSmartMotorController : public frc::MotorController { */ void ResetEncoder() {} - void Set(double speed) override {} + void Set(double speed) {} - double Get() const override { return 0; } + double Get() const { return 0; } - void SetInverted(bool isInverted) override {} + void SetInverted(bool isInverted) {} - bool GetInverted() const override { return false; } + bool GetInverted() const { return false; } - void Disable() override {} + void Disable() {} - void StopMotor() override {} + void StopMotor() {} }; diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h index 6830b960d09..ca7e28e8293 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h @@ -8,7 +8,6 @@ #include #include -#include #include #include #include @@ -73,14 +72,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp index cc7db7b3bab..9470a7ad3aa 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp @@ -12,8 +12,8 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { const double rightOutput = m_rightPIDController.Calculate( m_rightEncoder.GetRate(), speeds.right.value()); - m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); - m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); + m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); + m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); } void Drivetrain::Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h index 54b2e26290f..85bccc7f521 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h @@ -12,7 +12,6 @@ #include #include #include -#include #include #include #include @@ -25,10 +24,13 @@ class Drivetrain { public: Drivetrain() { + m_leftLeader.AddFollower(m_leftFollower); + m_rightLeader.AddFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.SetInverted(true); + m_rightLeader.SetInverted(true); m_gyro.Reset(); // Set the distance per pulse for the drive encoders. We can simply use the @@ -63,9 +65,6 @@ class Drivetrain { frc::PWMSparkMax m_rightLeader{3}; frc::PWMSparkMax m_rightFollower{4}; - frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower}; - frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower}; - frc::Encoder m_leftEncoder{0, 1}; frc::Encoder m_rightEncoder{2, 3}; diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp index 725074a71a7..caba17d9e93 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp @@ -7,10 +7,13 @@ #include "ExampleGlobalMeasurementSensor.h" Drivetrain::Drivetrain() { + m_leftLeader.AddFollower(m_leftFollower); + m_rightLeader.AddFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.SetInverted(true); + m_rightLeader.SetInverted(true); m_gyro.Reset(); @@ -37,8 +40,8 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { const double rightOutput = m_rightPIDController.Calculate( m_rightEncoder.GetRate(), speeds.right.value()); - m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); - m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); + m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); + m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); } void Drivetrain::Drive(units::meters_per_second_t xSpeed, @@ -110,9 +113,9 @@ void Drivetrain::SimulationPeriodic() { // To update our simulation, we set motor voltage inputs, update the // simulation, and write the simulated positions and velocities to our // simulated encoder and gyro. - m_drivetrainSimulator.SetInputs(units::volt_t{m_leftGroup.Get()} * + m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} * frc::RobotController::GetInputVoltage(), - units::volt_t{m_rightGroup.Get()} * + units::volt_t{m_rightLeader.Get()} * frc::RobotController::GetInputVoltage()); m_drivetrainSimulator.Update(20_ms); diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h index ac4de4c566f..63a9aea0142 100644 --- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h @@ -21,7 +21,6 @@ #include #include #include -#include #include #include #include @@ -140,9 +139,6 @@ class Drivetrain { frc::PWMSparkMax m_rightLeader{3}; frc::PWMSparkMax m_rightFollower{4}; - frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower}; - frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower}; - frc::Encoder m_leftEncoder{0, 1}; frc::Encoder m_rightEncoder{2, 3}; diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h index 71dc4d4864a..fe09a15f226 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h @@ -4,15 +4,13 @@ #pragma once -#include - /** * A simplified stub class that simulates the API of a common "smart" motor * controller. * *

Has no actual functionality. */ -class ExampleSmartMotorController : public frc::MotorController { +class ExampleSmartMotorController { public: enum PIDMode { kPosition, kVelocity, kMovementWitchcraft }; @@ -68,17 +66,17 @@ class ExampleSmartMotorController : public frc::MotorController { */ void ResetEncoder() {} - void Set(double speed) override { m_value = speed; } + void Set(double speed) { m_value = speed; } - double Get() const override { return m_value; } + double Get() const { return m_value; } - void SetInverted(bool isInverted) override {} + void SetInverted(bool isInverted) {} - bool GetInverted() const override { return false; } + bool GetInverted() const { return false; } - void Disable() override {} + void Disable() {} - void StopMotor() override {} + void StopMotor() {} private: double m_value = 0.0; diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h index 9086353bf94..3dd5f03f10a 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h @@ -83,5 +83,7 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::SimpleMotorFeedforward m_feedforward; // The robot's drive - frc::DifferentialDrive m_drive{m_leftLeader, m_rightLeader}; + frc::DifferentialDrive m_drive{ + [&](double output) { m_leftLeader.Set(output); }, + [&](double output) { m_rightLeader.Set(output); }}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h index 5d55839892f..bd48d88e0bc 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h @@ -4,15 +4,13 @@ #pragma once -#include - /** * A simplified stub class that simulates the API of a common "smart" motor * controller. * *

Has no actual functionality. */ -class ExampleSmartMotorController : public frc::MotorController { +class ExampleSmartMotorController { public: enum PIDMode { kPosition, kVelocity, kMovementWitchcraft }; @@ -68,15 +66,15 @@ class ExampleSmartMotorController : public frc::MotorController { */ void ResetEncoder() {} - void Set(double speed) override {} + void Set(double speed) {} - double Get() const override { return 0; } + double Get() const { return 0; } - void SetInverted(bool isInverted) override {} + void SetInverted(bool isInverted) {} - bool GetInverted() const override { return false; } + bool GetInverted() const { return false; } - void Disable() override {} + void Disable() {} - void StopMotor() override {} + void StopMotor() {} }; diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h index 5d55839892f..bd48d88e0bc 100644 --- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h +++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h @@ -4,15 +4,13 @@ #pragma once -#include - /** * A simplified stub class that simulates the API of a common "smart" motor * controller. * *

Has no actual functionality. */ -class ExampleSmartMotorController : public frc::MotorController { +class ExampleSmartMotorController { public: enum PIDMode { kPosition, kVelocity, kMovementWitchcraft }; @@ -68,15 +66,15 @@ class ExampleSmartMotorController : public frc::MotorController { */ void ResetEncoder() {} - void Set(double speed) override {} + void Set(double speed) {} - double Get() const override { return 0; } + double Get() const { return 0; } - void SetInverted(bool isInverted) override {} + void SetInverted(bool isInverted) {} - bool GetInverted() const override { return false; } + bool GetInverted() const { return false; } - void Disable() override {} + void Disable() {} - void StopMotor() override {} + void StopMotor() {} }; diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp index f40a649ec84..53f289c3119 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp @@ -13,10 +13,13 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_leftMotors.SetInverted(true); + m_left1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h index 47bf28e4d91..47d3f3d49b2 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -75,14 +74,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp index 2bfd391d6aa..34a84b6c0b2 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp @@ -11,10 +11,13 @@ #include Drivetrain::Drivetrain() { + m_frontLeft.AddFollower(m_rearLeft); + m_frontRight.AddFollower(m_rearRight); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_right.SetInverted(true); + m_frontRight.SetInverted(true); // Encoders may measure differently in the real world and in // simulation. In this example the robot moves 0.042 barleycorns 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 9e739c4dbc3..cc3c95f9b3a 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h @@ -8,7 +8,6 @@ #include #include #include -#include #include #include @@ -66,13 +65,13 @@ class Drivetrain : public frc2::SubsystemBase { private: frc::PWMSparkMax m_frontLeft{1}; frc::PWMSparkMax m_rearLeft{2}; - frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft}; frc::PWMSparkMax m_frontRight{3}; frc::PWMSparkMax m_rearRight{4}; - frc::MotorControllerGroup m_right{m_frontRight, m_rearRight}; - frc::DifferentialDrive m_robotDrive{m_left, m_right}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_frontLeft.Set(output); }, + [&](double output) { m_frontRight.Set(output); }}; frc::Encoder m_leftEncoder{1, 2}; frc::Encoder m_rightEncoder{3, 4}; diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index 01b72108759..43380851815 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -48,7 +48,9 @@ class Robot : public frc::TimedRobot { // Robot drive system frc::PWMSparkMax m_left{0}; frc::PWMSparkMax m_right{1}; - frc::DifferentialDrive m_robotDrive{m_left, m_right}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_left.Set(output); }, + [&](double output) { m_right.Set(output); }}; frc::XboxController m_controller{0}; frc::Timer m_timer; diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index 5230c7c3973..f5db62ef406 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -50,7 +50,8 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_left{kLeftMotorPort}; frc::PWMSparkMax m_right{kRightMotorPort}; - frc::DifferentialDrive m_drive{m_left, m_right}; + frc::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); }, + [&](double output) { m_right.Set(output); }}; frc::AnalogGyro m_gyro{kGyroPort}; frc::Joystick m_joystick{kJoystickPort}; diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp index 0cbd0e548d1..234f837c9ba 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp @@ -13,10 +13,13 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h index 96174dd4f7a..d7cce6c05c2 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h @@ -7,7 +7,6 @@ #include #include #include -#include #include #include #include @@ -91,14 +90,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp index 2207f79de51..cdd3ef5be8f 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp @@ -48,8 +48,11 @@ class Robot : public frc::TimedRobot { 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}; + frc::MecanumDrive m_robotDrive{ + [&](double output) { m_frontLeft.Set(output); }, + [&](double output) { m_rearLeft.Set(output); }, + [&](double output) { m_frontRight.Set(output); }, + [&](double output) { m_rearRight.Set(output); }}; frc::AnalogGyro m_gyro{kGyroPort}; frc::Joystick m_joystick{kJoystickPort}; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp index 3372a4dca9d..44e56bf2c85 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp @@ -15,10 +15,13 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h index 5984a1a4f38..6cab5803884 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -63,14 +62,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp index 3372a4dca9d..44e56bf2c85 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp @@ -15,10 +15,13 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h index 5984a1a4f38..6cab5803884 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h @@ -6,7 +6,6 @@ #include #include -#include #include #include @@ -63,14 +62,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h index 579a3950eaa..7efb2250874 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h @@ -148,7 +148,10 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_rearRight; // The robot's drive - frc::MecanumDrive m_drive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight}; + frc::MecanumDrive m_drive{[&](double output) { m_frontLeft.Set(output); }, + [&](double output) { m_rearLeft.Set(output); }, + [&](double output) { m_frontRight.Set(output); }, + [&](double output) { m_rearRight.Set(output); }}; // The front-left-side drive encoder frc::Encoder m_frontLeftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index 8d9d7aebf75..3a450be766c 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -40,8 +40,11 @@ class Robot : public frc::TimedRobot { 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}; + frc::MecanumDrive m_robotDrive{ + [&](double output) { m_frontLeft.Set(output); }, + [&](double output) { m_rearLeft.Set(output); }, + [&](double output) { m_frontRight.Set(output); }, + [&](double output) { m_rearRight.Set(output); }}; frc::Joystick m_stick{kJoystickChannel}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp index 0bc598e4e9d..9ac07694e85 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp @@ -17,10 +17,13 @@ DriveSubsystem::DriveSubsystem() m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]}, m_odometry{m_gyro.GetRotation2d(), units::meter_t{0}, units::meter_t{0}} { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse.value()); @@ -41,8 +44,8 @@ void DriveSubsystem::ArcadeDrive(double fwd, double rot) { } void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) { - m_leftMotors.SetVoltage(left); - m_rightMotors.SetVoltage(right); + m_left1.SetVoltage(left); + m_right1.SetVoltage(right); m_drive.Feed(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h index 8ea14dad398..e1580e1b480 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h @@ -9,7 +9,6 @@ #include #include #include -#include #include #include #include @@ -122,14 +121,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1; frc::PWMSparkMax m_right2; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder; diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp index 8c1e6323bed..9ce08e9b9ad 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp @@ -12,8 +12,8 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { const double rightOutput = m_rightPIDController.Calculate( m_rightEncoder.GetRate(), speeds.right.value()); - m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); - m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); + m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); + m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); } void Drivetrain::Drive(units::meters_per_second_t xSpeed, diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h index 341cd38c1cd..39511c7a4b7 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h @@ -12,7 +12,6 @@ #include #include #include -#include #include #include #include @@ -25,10 +24,13 @@ class Drivetrain { Drivetrain() { m_gyro.Reset(); + m_leftLeader.AddFollower(m_leftFollower); + m_rightLeader.AddFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.SetInverted(true); + m_rightLeader.SetInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -64,9 +66,6 @@ class Drivetrain { frc::PWMSparkMax m_rightLeader{3}; frc::PWMSparkMax m_rightFollower{4}; - frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower}; - frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower}; - frc::Encoder m_leftEncoder{0, 1}; frc::Encoder m_rightEncoder{2, 3}; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp index 98ff0cac75f..b7857ec542c 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp @@ -9,10 +9,13 @@ #include Drive::Drive() { + m_leftLeader.AddFollower(m_leftFollower); + m_rightLeader.AddFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_rightLeader.SetInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h index ac96c52839c..8432e57b6b0 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h @@ -8,7 +8,6 @@ #include #include -#include #include #include #include @@ -45,10 +44,9 @@ class Drive : public frc2::SubsystemBase { frc::PWMSparkMax m_rightLeader{DriveConstants::kRightMotor1Port}; frc::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port}; - frc::MotorControllerGroup m_leftMotors{m_leftLeader, m_leftFollower}; - frc::MotorControllerGroup m_rightMotors{m_rightLeader, m_rightFollower}; - - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{ + [&](double output) { m_leftLeader.Set(output); }, + [&](double output) { m_rightLeader.Set(output); }}; frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0], DriveConstants::kLeftEncoderPorts[1], diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h index ace7d33bc77..d679178fd04 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h @@ -114,7 +114,9 @@ class Drivetrain : public frc2::SubsystemBase { frc::Encoder m_leftEncoder{4, 5}; frc::Encoder m_rightEncoder{6, 7}; - frc::DifferentialDrive m_drive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_drive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::RomiGyro m_gyro; frc::BuiltInAccelerometer m_accelerometer; diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp index b951f18bbe9..da8ccd141d4 100644 --- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp @@ -65,7 +65,9 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_right{1}; frc::PWMSparkMax m_elevatorMotor{2}; - frc::DifferentialDrive m_robotDrive{m_left, m_right}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_left.Set(output); }, + [&](double output) { m_right.Set(output); }}; frc::Joystick m_stick{0}; diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp index 93d0889df50..e0b63cabe49 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp @@ -14,8 +14,8 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { double rightOutput = m_rightPIDController.Calculate(m_rightEncoder.GetRate(), speeds.right.value()); - m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); - m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); + m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); + m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); } void Drivetrain::Drive(units::meters_per_second_t xSpeed, @@ -43,9 +43,9 @@ void Drivetrain::SimulationPeriodic() { // simulation, and write the simulated positions and velocities to our // simulated encoder and gyro. We negate the right side so that positive // voltages make the right side move forward. - m_drivetrainSimulator.SetInputs(units::volt_t{m_leftGroup.Get()} * + m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} * frc::RobotController::GetInputVoltage(), - units::volt_t{m_rightGroup.Get()} * + units::volt_t{m_rightLeader.Get()} * frc::RobotController::GetInputVoltage()); m_drivetrainSimulator.Update(20_ms); diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h index 4c274fe476d..ca82547f7cb 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h @@ -12,7 +12,6 @@ #include #include #include -#include #include #include #include @@ -33,10 +32,13 @@ class Drivetrain { Drivetrain() { m_gyro.Reset(); + m_leftLeader.AddFollower(m_leftFollower); + m_rightLeader.AddFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.SetInverted(true); + m_rightLeader.SetInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -49,7 +51,7 @@ class Drivetrain { m_leftEncoder.Reset(); m_rightEncoder.Reset(); - m_rightGroup.SetInverted(true); + m_rightLeader.SetInverted(true); frc::SmartDashboard::PutData("Field", &m_fieldSim); } @@ -80,9 +82,6 @@ class Drivetrain { frc::PWMSparkMax m_rightLeader{3}; frc::PWMSparkMax m_rightFollower{4}; - frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower}; - frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower}; - frc::Encoder m_leftEncoder{0, 1}; frc::Encoder m_rightEncoder{2, 3}; diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp index 15d85964359..af14c689b5b 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp @@ -14,10 +14,13 @@ using namespace DriveConstants; DriveSubsystem::DriveSubsystem() { + m_left1.AddFollower(m_left2); + m_right1.AddFollower(m_right2); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.SetInverted(true); + m_right1.SetInverted(true); // Set the distance per pulse for the encoders m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); @@ -40,10 +43,9 @@ void DriveSubsystem::SimulationPeriodic() { // simulation, and write the simulated positions and velocities to our // simulated encoder and gyro. We negate the right side so that positive // voltages make the right side move forward. - m_drivetrainSimulator.SetInputs(units::volt_t{m_leftMotors.Get()} * - frc::RobotController::GetInputVoltage(), - units::volt_t{m_rightMotors.Get()} * - frc::RobotController::GetInputVoltage()); + m_drivetrainSimulator.SetInputs( + units::volt_t{m_left1.Get()} * frc::RobotController::GetInputVoltage(), + units::volt_t{m_right1.Get()} * frc::RobotController::GetInputVoltage()); m_drivetrainSimulator.Update(20_ms); m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value()); @@ -63,8 +65,8 @@ void DriveSubsystem::ArcadeDrive(double fwd, double rot) { } void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) { - m_leftMotors.SetVoltage(left); - m_rightMotors.SetVoltage(right); + m_left1.SetVoltage(left); + m_right1.SetVoltage(right); m_drive.Feed(); } diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h index 57392c723ba..5e412019bca 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h @@ -9,7 +9,6 @@ #include #include #include -#include #include #include #include @@ -133,14 +132,9 @@ class DriveSubsystem : public frc2::SubsystemBase { frc::PWMSparkMax m_right1{DriveConstants::kRightMotor1Port}; frc::PWMSparkMax m_right2{DriveConstants::kRightMotor2Port}; - // The motors on the left side of the drive - frc::MotorControllerGroup m_leftMotors{m_left1, m_left2}; - - // The motors on the right side of the drive - frc::MotorControllerGroup m_rightMotors{m_right1, m_right2}; - // The robot's drive - frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); }, + [&](double output) { m_right1.Set(output); }}; // The left-side drive encoder frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0], diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp index 4e48d475842..1d91437efaa 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp @@ -14,7 +14,9 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::Joystick m_leftStick{0}; frc::Joystick m_rightStick{1}; diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp index b8cff3271e7..250c002341e 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp @@ -14,7 +14,9 @@ class Robot : public frc::TimedRobot { frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::XboxController m_driverController{0}; public: diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h index 4ff2700d6a0..4e9f0bf7627 100644 --- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h @@ -46,6 +46,8 @@ class Robot : public frc::TimedRobot { frc::Ultrasonic m_ultrasonic{kUltrasonicPingPort, kUltrasonicEchoPort}; frc::PWMSparkMax m_left{kLeftMotorPort}; frc::PWMSparkMax m_right{kRightMotorPort}; - frc::DifferentialDrive m_robotDrive{m_left, m_right}; + frc::DifferentialDrive m_robotDrive{ + [&](double output) { m_left.Set(output); }, + [&](double output) { m_right.Set(output); }}; frc::PIDController m_pidController{kP, kI, kD}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h index e665601228e..c2a2ef319f1 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h @@ -118,7 +118,9 @@ class Drivetrain : public frc2::SubsystemBase { frc::Encoder m_leftEncoder{4, 5}; frc::Encoder m_rightEncoder{6, 7}; - frc::DifferentialDrive m_drive{m_leftMotor, m_rightMotor}; + frc::DifferentialDrive m_drive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; frc::XRPGyro m_gyro; frc::BuiltInAccelerometer m_accelerometer; diff --git a/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp index be7efb8e68e..949950472ca 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp @@ -6,6 +6,7 @@ #include #include +#include #include "TestBench.h" #include "frc/Encoder.h" @@ -37,6 +38,8 @@ std::ostream& operator<<(std::ostream& os, MotorEncoderTestType const& type) { static constexpr auto kMotorTime = 0.5_s; +WPI_IGNORE_DEPRECATED + /** * A fixture that includes a PWM motor controller and an encoder connected to * the same motor. @@ -197,3 +200,5 @@ TEST_P(MotorEncoderTest, Reset) { INSTANTIATE_TEST_SUITE_P(Tests, MotorEncoderTest, testing::Values(TEST_VICTOR, TEST_JAGUAR, TEST_TALON)); + +WPI_UNIGNORE_DEPRECATED diff --git a/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp b/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp index 870f029f9d7..49a419c10dc 100644 --- a/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp +++ b/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp @@ -4,6 +4,7 @@ #include #include +#include #include "TestBench.h" #include "frc/Encoder.h" @@ -32,6 +33,9 @@ std::ostream& operator<<(std::ostream& os, MotorInvertingTestType const& type) { return os; } + +WPI_IGNORE_DEPRECATED + class MotorInvertingTest : public testing::TestWithParam { protected: @@ -153,3 +157,5 @@ TEST_P(MotorInvertingTest, InvertingSwitchingNegToPos) { INSTANTIATE_TEST_SUITE_P(Tests, MotorInvertingTest, testing::Values(TEST_VICTOR, TEST_JAGUAR, TEST_TALON)); + +WPI_UNIGNORE_DEPRECATED 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 a6a59c17e52..a1e09775439 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 @@ -14,49 +14,16 @@ import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.motorcontrol.MotorController; +import java.util.function.DoubleConsumer; /** * A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive * base, "tank drive", or West Coast Drive. * *

These drive bases typically have drop-center / skid-steer with two or more wheels per side - * (e.g., 6WD or 8WD). This class takes a MotorController per side. For four and six motor - * drivetrains, construct and pass in {@link - * edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup} instances as follows. - * - *

Four motor drivetrain: - * - *


- * public class Robot {
- *   MotorController m_frontLeft = new PWMVictorSPX(1);
- *   MotorController m_rearLeft = new PWMVictorSPX(2);
- *   MotorControllerGroup m_left = new MotorControllerGroup(m_frontLeft, m_rearLeft);
- *
- *   MotorController m_frontRight = new PWMVictorSPX(3);
- *   MotorController m_rearRight = new PWMVictorSPX(4);
- *   MotorControllerGroup m_right = new MotorControllerGroup(m_frontRight, m_rearRight);
- *
- *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
- * }
- * 
- * - *

Six motor drivetrain: - * - *


- * public class Robot {
- *   MotorController m_frontLeft = new PWMVictorSPX(1);
- *   MotorController m_midLeft = new PWMVictorSPX(2);
- *   MotorController m_rearLeft = new PWMVictorSPX(3);
- *   MotorControllerGroup m_left = new MotorControllerGroup(m_frontLeft, m_midLeft, m_rearLeft);
- *
- *   MotorController m_frontRight = new PWMVictorSPX(4);
- *   MotorController m_midRight = new PWMVictorSPX(5);
- *   MotorController m_rearRight = new PWMVictorSPX(6);
- *   MotorControllerGroup m_right = new MotorControllerGroup(m_frontRight, m_midRight, m_rearRight);
- *
- *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
- * }
- * 
+ * (e.g., 6WD or 8WD). This class takes a setter per side. For four and six motor drivetrains, use + * CAN motor controller followers or {@link + * edu.wpi.first.wpilibj.motorcontrol.PWMMotorController#addFollower(PWMMotorController)}. * *

A differential drive robot has left and right wheels separated by an arbitrary width. * @@ -88,8 +55,8 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoCloseable { private static int instances; - private final MotorController m_leftMotor; - private final MotorController m_rightMotor; + private final DoubleConsumer m_leftMotor; + private final DoubleConsumer m_rightMotor; private boolean m_reported; @@ -127,16 +94,33 @@ public WheelSpeeds(double left, double right) { * * @param leftMotor Left motor. * @param rightMotor Right motor. + * @deprecated Use DifferentialDrive constructor with function arguments. */ - @SuppressWarnings("this-escape") + @Deprecated(forRemoval = true, since = "2024") + @SuppressWarnings({"removal", "this-escape"}) public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) { + this((double output) -> leftMotor.set(output), (double output) -> rightMotor.set(output)); + } + + /** + * Construct a DifferentialDrive. + * + *

To pass multiple motors per side, use CAN motor controller followers or {@link + * edu.wpi.first.wpilibj.motorcontrol.PWMMotorController#addFollower(PWMMotorController)}. If a + * motor needs to be inverted, do so before passing it in. + * + * @param leftMotor Left motor setter. + * @param rightMotor Right motor setter. + */ + @SuppressWarnings("this-escape") + public DifferentialDrive(DoubleConsumer leftMotor, DoubleConsumer rightMotor) { requireNonNullParam(leftMotor, "leftMotor", "DifferentialDrive"); requireNonNullParam(rightMotor, "rightMotor", "DifferentialDrive"); m_leftMotor = leftMotor; m_rightMotor = rightMotor; - SendableRegistry.addChild(this, m_leftMotor); - SendableRegistry.addChild(this, m_rightMotor); + // SendableRegistry.addChild(this, m_leftMotor); + // SendableRegistry.addChild(this, m_rightMotor); instances++; SendableRegistry.addLW(this, "DifferentialDrive", instances); } @@ -178,8 +162,8 @@ public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) { var speeds = arcadeDriveIK(xSpeed, zRotation, squareInputs); - m_leftMotor.set(speeds.left * m_maxOutput); - m_rightMotor.set(speeds.right * m_maxOutput); + m_leftMotor.accept(speeds.left * m_maxOutput); + m_rightMotor.accept(speeds.right * m_maxOutput); feed(); } @@ -207,8 +191,8 @@ public void curvatureDrive(double xSpeed, double zRotation, boolean allowTurnInP var speeds = curvatureDriveIK(xSpeed, zRotation, allowTurnInPlace); - m_leftMotor.set(speeds.left * m_maxOutput); - m_rightMotor.set(speeds.right * m_maxOutput); + m_leftMotor.accept(speeds.left * m_maxOutput); + m_rightMotor.accept(speeds.right * m_maxOutput); feed(); } @@ -245,8 +229,8 @@ public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) var speeds = tankDriveIK(leftSpeed, rightSpeed, squareInputs); - m_leftMotor.set(speeds.left * m_maxOutput); - m_rightMotor.set(speeds.right * m_maxOutput); + m_leftMotor.accept(speeds.left * m_maxOutput); + m_rightMotor.accept(speeds.right * m_maxOutput); feed(); } @@ -351,8 +335,8 @@ public static WheelSpeeds tankDriveIK(double leftSpeed, double rightSpeed, boole @Override public void stopMotor() { - m_leftMotor.stopMotor(); - m_rightMotor.stopMotor(); + m_leftMotor.accept(0.0); + m_rightMotor.accept(0.0); feed(); } @@ -366,7 +350,7 @@ public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("DifferentialDrive"); builder.setActuator(true); builder.setSafeState(this::stopMotor); - builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set); - builder.addDoubleProperty("Right Motor Speed", m_rightMotor::get, m_rightMotor::set); + builder.addDoubleProperty("Left Motor Speed", null, m_leftMotor::accept); + builder.addDoubleProperty("Right Motor Speed", null, m_rightMotor::accept); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index abdfefedd6d..fa51a149e9a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -16,6 +16,7 @@ import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.motorcontrol.MotorController; +import java.util.function.DoubleConsumer; /** * A class for driving Mecanum drive platforms. @@ -56,10 +57,10 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoCloseable { private static int instances; - private final MotorController m_frontLeftMotor; - private final MotorController m_rearLeftMotor; - private final MotorController m_frontRightMotor; - private final MotorController m_rearRightMotor; + private final DoubleConsumer m_frontLeftMotor; + private final DoubleConsumer m_rearLeftMotor; + private final DoubleConsumer m_frontRightMotor; + private final DoubleConsumer m_rearRightMotor; private boolean m_reported; @@ -104,12 +105,35 @@ public WheelSpeeds(double frontLeft, double frontRight, double rearLeft, double * @param frontRightMotor The motor on the front-right corner. * @param rearRightMotor The motor on the rear-right corner. */ - @SuppressWarnings("this-escape") + @SuppressWarnings({"removal", "this-escape"}) public MecanumDrive( MotorController frontLeftMotor, MotorController rearLeftMotor, MotorController frontRightMotor, MotorController rearRightMotor) { + this( + (double output) -> frontLeftMotor.set(output), + (double output) -> rearLeftMotor.set(output), + (double output) -> frontRightMotor.set(output), + (double output) -> rearRightMotor.set(output)); + } + + /** + * Construct a MecanumDrive. + * + *

If a motor needs to be inverted, do so before passing it in. + * + * @param frontLeftMotor The setter for the motor on the front-left corner. + * @param rearLeftMotor The setter for the motor on the rear-left corner. + * @param frontRightMotor The setter for the motor on the front-right corner. + * @param rearRightMotor The setter for the motor on the rear-right corner. + */ + @SuppressWarnings("this-escape") + public MecanumDrive( + DoubleConsumer frontLeftMotor, + DoubleConsumer rearLeftMotor, + DoubleConsumer frontRightMotor, + DoubleConsumer rearRightMotor) { requireNonNullParam(frontLeftMotor, "frontLeftMotor", "MecanumDrive"); requireNonNullParam(rearLeftMotor, "rearLeftMotor", "MecanumDrive"); requireNonNullParam(frontRightMotor, "frontRightMotor", "MecanumDrive"); @@ -119,10 +143,10 @@ public MecanumDrive( m_rearLeftMotor = rearLeftMotor; m_frontRightMotor = frontRightMotor; m_rearRightMotor = rearRightMotor; - SendableRegistry.addChild(this, m_frontLeftMotor); - SendableRegistry.addChild(this, m_rearLeftMotor); - SendableRegistry.addChild(this, m_frontRightMotor); - SendableRegistry.addChild(this, m_rearRightMotor); + // SendableRegistry.addChild(this, m_frontLeftMotor); + // SendableRegistry.addChild(this, m_rearLeftMotor); + // SendableRegistry.addChild(this, m_frontRightMotor); + // SendableRegistry.addChild(this, m_rearRightMotor); instances++; SendableRegistry.addLW(this, "MecanumDrive", instances); } @@ -172,10 +196,10 @@ public void driveCartesian(double xSpeed, double ySpeed, double zRotation, Rotat var speeds = driveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); - m_frontLeftMotor.set(speeds.frontLeft * m_maxOutput); - m_frontRightMotor.set(speeds.frontRight * m_maxOutput); - m_rearLeftMotor.set(speeds.rearLeft * m_maxOutput); - m_rearRightMotor.set(speeds.rearRight * m_maxOutput); + m_frontLeftMotor.accept(speeds.frontLeft * m_maxOutput); + m_frontRightMotor.accept(speeds.frontRight * m_maxOutput); + m_rearLeftMotor.accept(speeds.rearLeft * m_maxOutput); + m_rearRightMotor.accept(speeds.rearRight * m_maxOutput); feed(); } @@ -256,10 +280,10 @@ public static WheelSpeeds driveCartesianIK( @Override public void stopMotor() { - m_frontLeftMotor.stopMotor(); - m_frontRightMotor.stopMotor(); - m_rearLeftMotor.stopMotor(); - m_rearRightMotor.stopMotor(); + m_frontLeftMotor.accept(0.0); + m_frontRightMotor.accept(0.0); + m_rearLeftMotor.accept(0.0); + m_rearRightMotor.accept(0.0); feed(); } @@ -273,12 +297,9 @@ public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("MecanumDrive"); builder.setActuator(true); builder.setSafeState(this::stopMotor); - builder.addDoubleProperty( - "Front Left Motor Speed", m_frontLeftMotor::get, m_frontLeftMotor::set); - builder.addDoubleProperty( - "Front Right Motor Speed", m_frontRightMotor::get, m_frontRightMotor::set); - builder.addDoubleProperty("Rear Left Motor Speed", m_rearLeftMotor::get, m_rearLeftMotor::set); - builder.addDoubleProperty( - "Rear Right Motor Speed", m_rearRightMotor::get, m_rearRightMotor::set); + builder.addDoubleProperty("Front Left Motor Speed", null, m_frontLeftMotor::accept); + builder.addDoubleProperty("Front Right Motor Speed", null, m_frontRightMotor::accept); + builder.addDoubleProperty("Rear Left Motor Speed", null, m_rearLeftMotor::accept); + builder.addDoubleProperty("Rear Right Motor Speed", null, m_rearRightMotor::accept); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java index 4cd50da11d8..cf080898cd6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java @@ -6,7 +6,12 @@ import edu.wpi.first.wpilibj.RobotController; -/** Interface for motor controlling devices. */ +/** + * Interface for motor controlling devices. + * + * @deprecated This class is being removed with no replacement. + */ +@Deprecated(forRemoval = true, since = "2024") public interface MotorController { /** * Common interface for setting the speed of a motor controller. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java index 88e7efe1325..50bb0a8e3e1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java @@ -9,7 +9,14 @@ import edu.wpi.first.util.sendable.SendableRegistry; import java.util.Arrays; -/** Allows multiple {@link MotorController} objects to be linked together. */ +/** + * Allows multiple {@link MotorController} objects to be linked together. + * + * @deprecated Use CAN motor controller followers or {@link + * PWMMotorController#addFollower(PWMMotorController)}. + */ +@SuppressWarnings("removal") +@Deprecated(forRemoval = true, since = "2024") public class MotorControllerGroup implements MotorController, Sendable, AutoCloseable { private boolean m_isInverted; private final MotorController[] m_motorControllers; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java index c5aac4f090e..01af76563cb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java @@ -14,6 +14,7 @@ import edu.wpi.first.wpilibj.PWM; /** Nidec Brushless Motor. */ +@SuppressWarnings("removal") public class NidecBrushless extends MotorSafety implements MotorController, Sendable, AutoCloseable { private boolean m_isInverted; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java index 0d2f83717b3..2f1bff790b7 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java @@ -9,11 +9,14 @@ import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.MotorSafety; import edu.wpi.first.wpilibj.PWM; +import java.util.ArrayList; /** Common base class for all PWM Motor Controllers. */ +@SuppressWarnings("removal") public abstract class PWMMotorController extends MotorSafety implements MotorController, Sendable, AutoCloseable { private boolean m_isInverted; + private final ArrayList m_followers = new ArrayList<>(); protected PWM m_pwm; /** @@ -46,7 +49,15 @@ public void close() { */ @Override public void set(double speed) { - m_pwm.setSpeed(m_isInverted ? -speed : speed); + if (m_isInverted) { + speed = -speed; + } + m_pwm.setSpeed(speed); + + for (var follower : m_followers) { + follower.set(speed); + } + feed(); } @@ -117,6 +128,15 @@ public void enableDeadbandElimination(boolean eliminateDeadband) { m_pwm.enableDeadbandElimination(eliminateDeadband); } + /** + * Make the given PWM motor controller follow the output of this one. + * + * @param follower The motor controller follower. + */ + public void addFollower(PWMMotorController follower) { + m_followers.add(follower); + } + @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Motor Controller"); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java index 4675a7f2be0..474dc89bb8e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/DifferentialDriveTest.java @@ -6,7 +6,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; -import edu.wpi.first.wpilibj.motorcontrol.MockMotorController; +import edu.wpi.first.wpilibj.motorcontrol.MockPWMMotorController; import org.junit.jupiter.api.Test; class DifferentialDriveTest { @@ -250,9 +250,9 @@ void testTankDriveIKSquared() { @Test void testArcadeDrive() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward @@ -288,9 +288,9 @@ void testArcadeDrive() { @Test void testArcadeDriveSquared() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward @@ -326,9 +326,9 @@ void testArcadeDriveSquared() { @Test void testCurvatureDrive() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward @@ -364,9 +364,9 @@ void testCurvatureDrive() { @Test void testCurvatureDriveTurnInPlace() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward @@ -402,9 +402,9 @@ void testCurvatureDriveTurnInPlace() { @Test void testTankDrive() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward @@ -440,9 +440,9 @@ void testTankDrive() { @Test void testTankDriveSquared() { - var left = new MockMotorController(); - var right = new MockMotorController(); - var drive = new DifferentialDrive(left, right); + var left = new MockPWMMotorController(); + var right = new MockPWMMotorController(); + var drive = new DifferentialDrive(left::set, right::set); drive.setDeadband(0.0); // Forward diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java index 034ba10c0cd..a1017d51e95 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/drive/MecanumDriveTest.java @@ -7,7 +7,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.wpilibj.motorcontrol.MockMotorController; +import edu.wpi.first.wpilibj.motorcontrol.MockPWMMotorController; import org.junit.jupiter.api.Test; class MecanumDriveTest { @@ -89,11 +89,11 @@ void testCartesianIKGyro90CW() { @Test void testCartesian() { - var fl = new MockMotorController(); - var fr = new MockMotorController(); - var rl = new MockMotorController(); - var rr = new MockMotorController(); - var drive = new MecanumDrive(fl, rl, fr, rr); + var fl = new MockPWMMotorController(); + var rl = new MockPWMMotorController(); + var fr = new MockPWMMotorController(); + var rr = new MockPWMMotorController(); + var drive = new MecanumDrive(fl::set, rl::set, fr::set, rr::set); drive.setDeadband(0.0); // Forward @@ -134,11 +134,11 @@ void testCartesian() { @Test void testCartesianGyro90CW() { - var fl = new MockMotorController(); - var fr = new MockMotorController(); - var rl = new MockMotorController(); - var rr = new MockMotorController(); - var drive = new MecanumDrive(fl, rl, fr, rr); + var fl = new MockPWMMotorController(); + var rl = new MockPWMMotorController(); + var fr = new MockPWMMotorController(); + var rr = new MockPWMMotorController(); + var drive = new MecanumDrive(fl::set, rl::set, fr::set, rr::set); drive.setDeadband(0.0); // Forward in global frame; left in robot frame @@ -179,11 +179,11 @@ void testCartesianGyro90CW() { @Test void testPolar() { - var fl = new MockMotorController(); - var fr = new MockMotorController(); - var rl = new MockMotorController(); - var rr = new MockMotorController(); - var drive = new MecanumDrive(fl, rl, fr, rr); + var fl = new MockPWMMotorController(); + var rl = new MockPWMMotorController(); + var fr = new MockPWMMotorController(); + var rr = new MockPWMMotorController(); + var drive = new MecanumDrive(fl::set, rl::set, fr::set, rr::set); drive.setDeadband(0.0); // Forward diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java index e7a6b8eb365..4ac3dc8f56f 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.motorcontrol; +@SuppressWarnings("removal") public class MockMotorController implements MotorController { private double m_speed; private boolean m_isInverted; diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockPWMMotorController.java similarity index 83% rename from wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java rename to wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockPWMMotorController.java index e7a6b8eb365..bf2c287f692 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MockMotorController.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MockPWMMotorController.java @@ -4,36 +4,30 @@ package edu.wpi.first.wpilibj.motorcontrol; -public class MockMotorController implements MotorController { +public class MockPWMMotorController { private double m_speed; private boolean m_isInverted; - @Override public void set(double speed) { m_speed = m_isInverted ? -speed : speed; } - @Override public double get() { return m_speed; } - @Override public void setInverted(boolean isInverted) { m_isInverted = isInverted; } - @Override public boolean getInverted() { return m_isInverted; } - @Override public void disable() { m_speed = 0; } - @Override public void stopMotor() { disable(); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroupTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroupTest.java index 6efb3def8b2..a8f71f6b6a9 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroupTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroupTest.java @@ -15,6 +15,7 @@ import org.junit.jupiter.params.provider.Arguments; import org.junit.jupiter.params.provider.MethodSource; +@SuppressWarnings("removal") class MotorControllerGroupTest { private static Stream motorControllerArguments() { return IntStream.of(1, 2, 3) diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java index 45333a5e3cf..20b2e17522c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java @@ -16,7 +16,8 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftMotor = new PWMSparkMax(0); private final PWMSparkMax m_rightMotor = new PWMSparkMax(1); - private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final Joystick m_stick = new Joystick(0); @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java index aa0f9a20ea2..d10e7d3025e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java @@ -16,7 +16,8 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftMotor = new PWMSparkMax(0); private final PWMSparkMax m_rightMotor = new PWMSparkMax(1); - private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final XboxController m_driverController = new XboxController(0); @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java index 4ecaa77231b..dde17979135 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java @@ -7,25 +7,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -47,10 +43,13 @@ public DriveSubsystem() { m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); } /** diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java index 4f95b4003e6..7801a1fa8a5 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/ExampleSmartMotorController.java @@ -4,14 +4,12 @@ package edu.wpi.first.wpilibj.examples.armbotoffboard; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; - /** * A simplified stub class that simulates the API of a common "smart" motor controller. * *

Has no actual functionality. */ -public class ExampleSmartMotorController implements MotorController { +public class ExampleSmartMotorController { public enum PIDMode { kPosition, kVelocity, @@ -72,25 +70,19 @@ public double getEncoderRate() { /** Resets the encoder to zero distance. */ public void resetEncoder() {} - @Override public void set(double speed) {} - @Override public double get() { return 0; } - @Override public void setInverted(boolean isInverted) {} - @Override public boolean getInverted() { return false; } - @Override public void disable() {} - @Override public void stopMotor() {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java index e3c91595370..2dbf00b2c04 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java @@ -7,7 +7,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -16,19 +15,16 @@ public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -50,10 +46,13 @@ public DriveSubsystem() { m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); } /** 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 8b4734a0f7b..adc52e2ef67 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 @@ -12,8 +12,6 @@ import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** Represents a differential drive style drivetrain. */ @@ -25,19 +23,14 @@ public class Drivetrain { private static final double kWheelRadius = 0.0508; // meters private static final int kEncoderResolution = 4096; - private final MotorController m_leftLeader = new PWMSparkMax(1); - private final MotorController m_leftFollower = new PWMSparkMax(2); - private final MotorController m_rightLeader = new PWMSparkMax(3); - private final MotorController m_rightFollower = new PWMSparkMax(4); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(1); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(2); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(3); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(4); private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); - private final MotorControllerGroup m_leftGroup = - new MotorControllerGroup(m_leftLeader, m_leftFollower); - private final MotorControllerGroup m_rightGroup = - new MotorControllerGroup(m_rightLeader, m_rightFollower); - private final AnalogGyro m_gyro = new AnalogGyro(0); private final PIDController m_leftPIDController = new PIDController(1, 0, 0); @@ -58,10 +51,13 @@ public class Drivetrain { public Drivetrain() { m_gyro.reset(); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.setInverted(true); + m_rightLeader.setInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -90,8 +86,8 @@ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); final double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond); - m_leftGroup.setVoltage(leftOutput + leftFeedforward); - m_rightGroup.setVoltage(rightOutput + rightFeedforward); + m_leftLeader.setVoltage(leftOutput + leftFeedforward); + m_rightLeader.setVoltage(rightOutput + rightFeedforward); } /** diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java index ceceaf32676..9b7ec75b5f8 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java @@ -30,8 +30,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj.simulation.AnalogGyroSim; import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim; @@ -48,19 +46,14 @@ public class Drivetrain { private static final double kWheelRadius = 0.0508; // meters private static final int kEncoderResolution = 4096; - private final MotorController m_leftLeader = new PWMSparkMax(1); - private final MotorController m_leftFollower = new PWMSparkMax(2); - private final MotorController m_rightLeader = new PWMSparkMax(3); - private final MotorController m_rightFollower = new PWMSparkMax(4); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(1); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(2); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(3); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(4); private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); - private final MotorControllerGroup m_leftGroup = - new MotorControllerGroup(m_leftLeader, m_leftFollower); - private final MotorControllerGroup m_rightGroup = - new MotorControllerGroup(m_rightLeader, m_rightFollower); - private final AnalogGyro m_gyro = new AnalogGyro(0); private final PIDController m_leftPIDController = new PIDController(1, 0, 0); @@ -113,10 +106,13 @@ public class Drivetrain { public Drivetrain(DoubleArrayTopic cameraToObjectTopic) { m_gyro.reset(); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.setInverted(true); + m_rightLeader.setInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -148,8 +144,8 @@ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); final double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond); - m_leftGroup.setVoltage(leftOutput + leftFeedforward); - m_rightGroup.setVoltage(rightOutput + rightFeedforward); + m_leftLeader.setVoltage(leftOutput + leftFeedforward); + m_rightLeader.setVoltage(rightOutput + rightFeedforward); } /** @@ -251,8 +247,8 @@ public void simulationPeriodic() { // simulation, and write the simulated positions and velocities to our // simulated encoder and gyro. m_drivetrainSimulator.setInputs( - m_leftGroup.get() * RobotController.getInputVoltage(), - m_rightGroup.get() * RobotController.getInputVoltage()); + m_leftLeader.get() * RobotController.getInputVoltage(), + m_rightLeader.get() * RobotController.getInputVoltage()); m_drivetrainSimulator.update(0.02); m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters()); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java index 487974cadbc..12c51ab4414 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/ExampleSmartMotorController.java @@ -4,14 +4,12 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; - /** * A simplified stub class that simulates the API of a common "smart" motor controller. * *

Has no actual functionality. */ -public class ExampleSmartMotorController implements MotorController { +public class ExampleSmartMotorController { public enum PIDMode { kPosition, kVelocity, @@ -74,27 +72,21 @@ public double getEncoderRate() { /** Resets the encoder to zero distance. */ public void resetEncoder() {} - @Override public void set(double speed) { m_value = speed; } - @Override public double get() { return m_value; } - @Override public void setInverted(boolean isInverted) {} - @Override public boolean getInverted() { return false; } - @Override public void disable() {} - @Override public void stopMotor() {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java index 520261d4028..6273d099b78 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java @@ -34,7 +34,8 @@ public class DriveSubsystem extends SubsystemBase { DriveConstants.kaVoltSecondsSquaredPerMeter); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftLeader, m_rightLeader); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); /** Creates a new DriveSubsystem. */ public DriveSubsystem() { @@ -43,11 +44,6 @@ public DriveSubsystem() { // gearbox is constructed, you might have to invert the left side instead. m_rightLeader.setInverted(true); - // You might need to not do this depending on the specific motor controller - // that you are using -- contact the respective vendor's documentation for - // more details. - m_rightFollower.setInverted(true); - m_leftFollower.follow(m_leftLeader); m_rightFollower.follow(m_rightLeader); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/ExampleSmartMotorController.java index e252f850039..2b37b967893 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorexponentialprofile/ExampleSmartMotorController.java @@ -4,14 +4,12 @@ package edu.wpi.first.wpilibj.examples.elevatorexponentialprofile; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; - /** * A simplified stub class that simulates the API of a common "smart" motor controller. * *

Has no actual functionality. */ -public class ExampleSmartMotorController implements MotorController { +public class ExampleSmartMotorController { public enum PIDMode { kPosition, kVelocity, @@ -72,25 +70,19 @@ public double getEncoderRate() { /** Resets the encoder to zero distance. */ public void resetEncoder() {} - @Override public void set(double speed) {} - @Override public double get() { return 0; } - @Override public void setInverted(boolean isInverted) {} - @Override public boolean getInverted() { return false; } - @Override public void disable() {} - @Override public void stopMotor() {} } 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 b6228c9c9e7..670fd7b8ee9 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 @@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; @SuppressWarnings("PMD.RedundantFieldInitializer") @@ -27,7 +26,7 @@ public class Robot extends TimedRobot { private final Joystick m_joystick = new Joystick(1); private final Encoder m_encoder = new Encoder(1, 2); - private final MotorController m_motor = new PWMSparkMax(1); + private final PWMSparkMax m_motor = new PWMSparkMax(1); // Create a PID controller whose setpoint's change is subject to maximum // velocity and acceleration constraints. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java index a1366e6f356..6d9ac23743a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/ExampleSmartMotorController.java @@ -4,14 +4,12 @@ package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; - /** * A simplified stub class that simulates the API of a common "smart" motor controller. * *

Has no actual functionality. */ -public class ExampleSmartMotorController implements MotorController { +public class ExampleSmartMotorController { public enum PIDMode { kPosition, kVelocity, @@ -72,25 +70,19 @@ public double getEncoderRate() { /** Resets the encoder to zero distance. */ public void resetEncoder() {} - @Override public void set(double speed) {} - @Override public double get() { return 0; } - @Override public void setInverted(boolean isInverted) {} - @Override public boolean getInverted() { return false; } - @Override public void disable() {} - @Override public void stopMotor() {} } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java index 03c5577157a..08de65c5919 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java @@ -12,7 +12,6 @@ import edu.wpi.first.wpilibj.Ultrasonic; import edu.wpi.first.wpilibj.event.BooleanEvent; import edu.wpi.first.wpilibj.event.EventLoop; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; public class Robot extends TimedRobot { @@ -20,15 +19,15 @@ public class Robot extends TimedRobot { public static final int TOLERANCE = 8; // rpm public static final int KICKER_THRESHOLD = 15; // mm - private final MotorController m_shooter = new PWMSparkMax(0); + private final PWMSparkMax m_shooter = new PWMSparkMax(0); private final Encoder m_shooterEncoder = new Encoder(0, 1); private final PIDController m_controller = new PIDController(0.3, 0, 0); private final SimpleMotorFeedforward m_ff = new SimpleMotorFeedforward(0.1, 0.065); - private final MotorController m_kicker = new PWMSparkMax(1); + private final PWMSparkMax m_kicker = new PWMSparkMax(1); private final Ultrasonic m_kickerSensor = new Ultrasonic(2, 3); - private final MotorController m_intake = new PWMSparkMax(2); + private final PWMSparkMax m_intake = new PWMSparkMax(2); private final EventLoop m_loop = new EventLoop(); private final Joystick m_joystick = new Joystick(0); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java index 5773da182db..b126e86eb68 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java @@ -7,25 +7,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -43,10 +39,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); 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 ffde63d4026..60ad2a5e2ff 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 @@ -10,28 +10,20 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.gearsbot.Constants.DriveConstants; import edu.wpi.first.wpilibj.examples.gearsbot.Robot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Drivetrain extends SubsystemBase { - /** - * The Drivetrain subsystem incorporates the sensors and actuators attached to the robots chassis. - * These include four drive motors, a left and right encoder and a gyro. - */ - private final MotorController m_leftMotor = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotorPort1), - new PWMSparkMax(DriveConstants.kLeftMotorPort1)); + // The Drivetrain subsystem incorporates the sensors and actuators attached to the robots chassis. + // These include four drive motors, a left and right encoder and a gyro. + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotorPort1); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotorPort2); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotorPort1); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotorPort2); - private final MotorController m_rightMotor = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotorPort2), - new PWMSparkMax(DriveConstants.kLeftMotorPort2)); - - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); private final Encoder m_leftEncoder = new Encoder( @@ -50,10 +42,13 @@ public class Drivetrain extends SubsystemBase { public Drivetrain() { super(); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotor.setInverted(true); + m_rightLeader.setInverted(true); // Encoders may measure differently in the real world and in // simulation. In this example the robot moves 0.042 barleycorns 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 dd337e656a5..2474242c874 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 @@ -19,7 +19,8 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftDrive = new PWMSparkMax(0); private final PWMSparkMax m_rightDrive = new PWMSparkMax(1); - private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftDrive::set, m_rightDrive::set); private final XboxController m_controller = new XboxController(0); private final Timer m_timer = new Timer(); 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 1f9e41df523..0da37bb762c 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 @@ -30,7 +30,8 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort); private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort); - private final DifferentialDrive m_myRobot = new DifferentialDrive(m_leftDrive, m_rightDrive); + private final DifferentialDrive m_myRobot = + new DifferentialDrive(m_leftDrive::set, m_rightDrive::set); 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/gyrodrivecommands/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java index 9adb6ec0f96..55ebe1053ad 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java @@ -8,25 +8,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -47,10 +43,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java index 1376195dc15..9c28511c444 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java @@ -8,25 +8,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -44,10 +40,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java index 8a5296d8604..b3f2adae6ac 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java @@ -8,25 +8,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -44,10 +40,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); 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 15e813a0c30..c64c9b3958a 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 @@ -14,7 +14,6 @@ import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** Represents a mecanum drive style drivetrain. */ @@ -22,10 +21,10 @@ public class Drivetrain { public static final double kMaxSpeed = 3.0; // 3 meters per second public static final double kMaxAngularSpeed = Math.PI; // 1/2 rotation per second - private final MotorController m_frontLeftMotor = new PWMSparkMax(1); - private final MotorController m_frontRightMotor = new PWMSparkMax(2); - private final MotorController m_backLeftMotor = new PWMSparkMax(3); - private final MotorController m_backRightMotor = new PWMSparkMax(4); + private final PWMSparkMax m_frontLeftMotor = new PWMSparkMax(1); + private final PWMSparkMax m_frontRightMotor = new PWMSparkMax(2); + private final PWMSparkMax m_backLeftMotor = new PWMSparkMax(3); + private final PWMSparkMax m_backRightMotor = new PWMSparkMax(4); private final Encoder m_frontLeftEncoder = new Encoder(0, 1); private final Encoder m_frontRightEncoder = new Encoder(2, 3); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java index b5c34c47bf6..0625b3fc374 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java @@ -18,7 +18,6 @@ import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** Represents a mecanum drive style drivetrain. */ @@ -26,10 +25,10 @@ public class Drivetrain { public static final double kMaxSpeed = 3.0; // 3 meters per second public static final double kMaxAngularSpeed = Math.PI; // 1/2 rotation per second - private final MotorController m_frontLeftMotor = new PWMSparkMax(1); - private final MotorController m_frontRightMotor = new PWMSparkMax(2); - private final MotorController m_backLeftMotor = new PWMSparkMax(3); - private final MotorController m_backRightMotor = new PWMSparkMax(4); + private final PWMSparkMax m_frontLeftMotor = new PWMSparkMax(1); + private final PWMSparkMax m_frontRightMotor = new PWMSparkMax(2); + private final PWMSparkMax m_backLeftMotor = new PWMSparkMax(3); + private final PWMSparkMax m_backRightMotor = new PWMSparkMax(4); private final Encoder m_frontLeftEncoder = new Encoder(0, 1); private final Encoder m_frontRightEncoder = new Encoder(2, 3); 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 82ced20919a..cbb4babbdf0 100644 --- 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 @@ -7,7 +7,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; @@ -27,7 +26,7 @@ public class Robot extends TimedRobot { private static final int kEncoderPortA = 0; private static final int kEncoderPortB = 1; - private MotorController m_motor; + private PWMSparkMax m_motor; private Joystick m_joystick; private Encoder m_encoder; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java index 288baeda4b4..f5ae467edcb 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java @@ -11,25 +11,21 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -53,10 +49,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); @@ -121,8 +120,8 @@ public void arcadeDrive(double fwd, double rot) { * @param rightVolts the commanded right output */ public void tankDriveVolts(double leftVolts, double rightVolts) { - m_leftMotors.setVoltage(leftVolts); - m_rightMotors.setVoltage(rightVolts); + m_leftLeader.setVoltage(leftVolts); + m_rightLeader.setVoltage(rightVolts); m_drive.feed(); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java index 69288a15a99..98d185694e0 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java @@ -13,8 +13,6 @@ import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** Represents a differential drive style drivetrain. */ @@ -26,19 +24,14 @@ public class Drivetrain { private static final double kWheelRadius = 0.0508; // meters private static final int kEncoderResolution = 4096; - private final MotorController m_leftLeader = new PWMSparkMax(1); - private final MotorController m_leftFollower = new PWMSparkMax(2); - private final MotorController m_rightLeader = new PWMSparkMax(3); - private final MotorController m_rightFollower = new PWMSparkMax(4); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(1); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(2); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(3); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(4); private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); - private final MotorControllerGroup m_leftGroup = - new MotorControllerGroup(m_leftLeader, m_leftFollower); - private final MotorControllerGroup m_rightGroup = - new MotorControllerGroup(m_rightLeader, m_rightFollower); - private final AnalogGyro m_gyro = new AnalogGyro(0); private final PIDController m_leftPIDController = new PIDController(1, 0, 0); @@ -59,10 +52,13 @@ public class Drivetrain { public Drivetrain() { m_gyro.reset(); + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.setInverted(true); + m_rightLeader.setInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -91,8 +87,8 @@ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond); final double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond); - m_leftGroup.setVoltage(leftOutput + leftFeedforward); - m_rightGroup.setVoltage(rightOutput + rightFeedforward); + m_leftLeader.setVoltage(leftOutput + leftFeedforward); + m_rightLeader.setVoltage(rightOutput + rightFeedforward); } /** diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java index 736ff446da4..3637110a2a4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java @@ -7,7 +7,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -15,19 +14,16 @@ public class Drive extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -45,10 +41,13 @@ public class Drive extends SubsystemBase { /** Creates a new Drive subsystem. */ public Drive() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java index d805590c068..c0b1a3cbe2d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java @@ -26,7 +26,8 @@ public class Drivetrain extends SubsystemBase { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); // Set up the RomiGyro private final RomiGyro m_gyro = new RomiGyro(); 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 47109e0f2fb..dbf4a902686 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 @@ -16,8 +16,10 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; public class Robot extends TimedRobot { + private final PWMSparkMax m_leftDriveMotor = new PWMSparkMax(0); + private final PWMSparkMax m_rightDriveMotor = new PWMSparkMax(1); private final DifferentialDrive m_tankDrive = - new DifferentialDrive(new PWMSparkMax(0), new PWMSparkMax(1)); + new DifferentialDrive(m_leftDriveMotor::set, m_rightDriveMotor::set); private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java index a9f53a9170d..fcae9283815 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java @@ -18,7 +18,6 @@ import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.RobotController; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj.simulation.AnalogGyroSim; import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim; @@ -41,11 +40,6 @@ public class Drivetrain { private final PWMSparkMax m_rightLeader = new PWMSparkMax(3); private final PWMSparkMax m_rightFollower = new PWMSparkMax(4); - private final MotorControllerGroup m_leftGroup = - new MotorControllerGroup(m_leftLeader, m_leftFollower); - private final MotorControllerGroup m_rightGroup = - new MotorControllerGroup(m_rightLeader, m_rightFollower); - private final Encoder m_leftEncoder = new Encoder(0, 1); private final Encoder m_rightEncoder = new Encoder(2, 3); @@ -77,10 +71,13 @@ public class Drivetrain { /** Subsystem constructor. */ public Drivetrain() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightGroup.setInverted(true); + m_rightLeader.setInverted(true); // Set the distance per pulse for the drive encoders. We can simply use the // distance traveled for one rotation of the wheel divided by the encoder @@ -91,7 +88,7 @@ public Drivetrain() { m_leftEncoder.reset(); m_rightEncoder.reset(); - m_rightGroup.setInverted(true); + m_rightLeader.setInverted(true); SmartDashboard.putData("Field", m_fieldSim); } @@ -104,8 +101,8 @@ public void setSpeeds(DifferentialDriveWheelSpeeds speeds) { double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond); - m_leftGroup.setVoltage(leftOutput + leftFeedforward); - m_rightGroup.setVoltage(rightOutput + rightFeedforward); + m_leftLeader.setVoltage(leftOutput + leftFeedforward); + m_rightLeader.setVoltage(rightOutput + rightFeedforward); } /** @@ -145,8 +142,8 @@ public void simulationPeriodic() { // simulated encoder and gyro. We negate the right side so that positive // voltages make the right side move forward. m_drivetrainSimulator.setInputs( - m_leftGroup.get() * RobotController.getInputVoltage(), - m_rightGroup.get() * RobotController.getInputVoltage()); + m_leftLeader.get() * RobotController.getInputVoltage(), + m_rightLeader.get() * RobotController.getInputVoltage()); m_drivetrainSimulator.update(0.02); m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters()); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java index 1b24a612501..3f91c93ab21 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm/Robot.java @@ -19,7 +19,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** @@ -92,7 +91,7 @@ public class Robot extends TimedRobot { // An encoder set up to measure arm position in radians. private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel); - private final MotorController m_motor = new PWMSparkMax(kMotorPort); + private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort); // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java index 406178a8abd..def536c489a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java @@ -15,7 +15,6 @@ import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.Constants.DriveConstants; -import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj.simulation.ADXRS450_GyroSim; import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim; @@ -26,19 +25,16 @@ public class DriveSubsystem extends SubsystemBase { // The motors on the left side of the drive. - private final MotorControllerGroup m_leftMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kLeftMotor1Port), - new PWMSparkMax(DriveConstants.kLeftMotor2Port)); + private final PWMSparkMax m_leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port); + private final PWMSparkMax m_leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port); // The motors on the right side of the drive. - private final MotorControllerGroup m_rightMotors = - new MotorControllerGroup( - new PWMSparkMax(DriveConstants.kRightMotor1Port), - new PWMSparkMax(DriveConstants.kRightMotor2Port)); + private final PWMSparkMax m_rightLeader = new PWMSparkMax(DriveConstants.kRightMotor1Port); + private final PWMSparkMax m_rightFollower = new PWMSparkMax(DriveConstants.kRightMotor2Port); // The robot's drive - private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors); + private final DifferentialDrive m_drive = + new DifferentialDrive(m_leftLeader::set, m_rightLeader::set); // The left-side drive encoder private final Encoder m_leftEncoder = @@ -70,10 +66,13 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + m_leftLeader.addFollower(m_leftFollower); + m_rightLeader.addFollower(m_rightFollower); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. - m_rightMotors.setInverted(true); + m_rightLeader.setInverted(true); // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); @@ -131,8 +130,8 @@ public void simulationPeriodic() { // We negate the right side so that positive voltages make the right side // move forward. m_drivetrainSimulator.setInputs( - m_leftMotors.get() * RobotController.getBatteryVoltage(), - m_rightMotors.get() * RobotController.getBatteryVoltage()); + m_leftLeader.get() * RobotController.getBatteryVoltage(), + m_rightLeader.get() * RobotController.getBatteryVoltage()); m_drivetrainSimulator.update(0.020); m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters()); @@ -202,8 +201,8 @@ public void arcadeDrive(double fwd, double rot) { * @param rightVolts the commanded right output */ public void tankDriveVolts(double leftVolts, double rightVolts) { - m_leftMotors.setVoltage(leftVolts); - m_rightMotors.setVoltage(rightVolts); + m_leftLeader.setVoltage(leftVolts); + m_rightLeader.setVoltage(rightVolts); m_drive.feed(); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java index cb196c814cd..52941913d1b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator/Robot.java @@ -19,7 +19,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** @@ -96,7 +95,7 @@ public class Robot extends TimedRobot { // An encoder set up to measure elevator height in meters. private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel); - private final MotorController m_motor = new PWMSparkMax(kMotorPort); + private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort); // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java index 06e8d29bb66..94566eac348 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java @@ -17,7 +17,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** @@ -77,7 +76,7 @@ public class Robot extends TimedRobot { // An encoder set up to measure flywheel velocity in radians per second. private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel); - private final MotorController m_motor = new PWMSparkMax(kMotorPort); + private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort); // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java index 26ee8f702ac..3a073fe9d5e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java @@ -16,7 +16,6 @@ import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** @@ -72,7 +71,7 @@ public class Robot extends TimedRobot { // An encoder set up to measure flywheel velocity in radians per second. private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel); - private final MotorController m_motor = new PWMSparkMax(kMotorPort); + private final PWMSparkMax m_motor = new PWMSparkMax(kMotorPort); // A joystick to read the trigger from. private final Joystick m_joystick = new Joystick(kJoystickPort); 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 65089f973da..c168860c99b 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 @@ -12,7 +12,6 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; public class SwerveModule { @@ -23,8 +22,8 @@ public class SwerveModule { private static final double kModuleMaxAngularAcceleration = 2 * Math.PI; // radians per second squared - private final MotorController m_driveMotor; - private final MotorController m_turningMotor; + private final PWMSparkMax m_driveMotor; + private final PWMSparkMax m_turningMotor; private final Encoder m_driveEncoder; private final Encoder m_turningEncoder; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java index 938b6c8f3c7..8ee8f4b07b8 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/SwerveModule.java @@ -12,7 +12,6 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; public class SwerveModule { @@ -23,8 +22,8 @@ public class SwerveModule { private static final double kModuleMaxAngularAcceleration = 2 * Math.PI; // radians per second squared - private final MotorController m_driveMotor; - private final MotorController m_turningMotor; + private final PWMSparkMax m_driveMotor; + private final PWMSparkMax m_turningMotor; private final Encoder m_driveEncoder; private final Encoder m_turningEncoder; 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 3883d145866..80001154a26 100644 --- 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 @@ -7,7 +7,6 @@ import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; -import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; /** @@ -19,8 +18,8 @@ public class Robot extends TimedRobot { private Joystick m_leftStick; private Joystick m_rightStick; - private final MotorController m_leftMotor = new PWMSparkMax(0); - private final MotorController m_rightMotor = new PWMSparkMax(1); + private final PWMSparkMax m_leftMotor = new PWMSparkMax(0); + private final PWMSparkMax m_rightMotor = new PWMSparkMax(1); @Override public void robotInit() { @@ -29,7 +28,7 @@ public void robotInit() { // gearbox is constructed, you might have to invert the left side instead. m_rightMotor.setInverted(true); - m_myRobot = new DifferentialDrive(m_leftMotor, m_rightMotor); + m_myRobot = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); m_leftStick = new Joystick(0); m_rightStick = new Joystick(1); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java index c6a985af5c9..8305ac1f932 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java @@ -16,7 +16,8 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftMotor = new PWMSparkMax(0); private final PWMSparkMax m_rightMotor = new PWMSparkMax(1); - private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final XboxController m_driverController = new XboxController(0); @Override 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 532e9ac4482..aa0a8b9eb14 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 @@ -41,7 +41,8 @@ public class Robot extends TimedRobot { private final Ultrasonic m_ultrasonic = new Ultrasonic(kUltrasonicPingPort, kUltrasonicEchoPort); private final PWMSparkMax m_leftMotor = new PWMSparkMax(kLeftMotorPort); private final PWMSparkMax m_rightMotor = new PWMSparkMax(kRightMotorPort); - private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final PIDController m_pidController = new PIDController(kP, kI, kD); @Override diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java index f618add665d..7f19d35c50e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java @@ -29,7 +29,8 @@ public class Drivetrain extends SubsystemBase { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); // Set up the XRPGyro private final XRPGyro m_gyro = new XRPGyro(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java index 276e5cee7d8..c1cfac1f325 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java @@ -24,7 +24,8 @@ public class RomiDrivetrain extends SubsystemBase { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new RomiDrivetrain. */ public RomiDrivetrain() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java index 4b73a448a08..7d2a4381cb2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java @@ -23,7 +23,8 @@ public class RomiDrivetrain { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new RomiDrivetrain. */ public RomiDrivetrain() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java index e4f85599cea..a0f4f47b38b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java @@ -23,7 +23,8 @@ public class RomiDrivetrain { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new RomiDrivetrain. */ public RomiDrivetrain() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/subsystems/XRPDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/subsystems/XRPDrivetrain.java index a3a1063a211..85febbed592 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/subsystems/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpcommandbased/subsystems/XRPDrivetrain.java @@ -27,7 +27,8 @@ public class XRPDrivetrain extends SubsystemBase { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new XRPDrivetrain. */ public XRPDrivetrain() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/XRPDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/XRPDrivetrain.java index 8f73baec50d..a2459558056 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrpeducational/XRPDrivetrain.java @@ -26,7 +26,8 @@ public class XRPDrivetrain { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new XRPDrivetrain. */ public XRPDrivetrain() { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/XRPDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/XRPDrivetrain.java index e66d750d092..790acc7801b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/XRPDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/xrptimed/XRPDrivetrain.java @@ -26,7 +26,8 @@ public class XRPDrivetrain { private final Encoder m_rightEncoder = new Encoder(6, 7); // Set up the differential drive controller - private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor); + private final DifferentialDrive m_diffDrive = + new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); /** Creates a new XRPDrivetrain. */ public XRPDrivetrain() { diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java index ca93c4a2ac1..d6322913dc9 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java @@ -22,6 +22,7 @@ * fixture. This allows tests to be mailable so that you can easily reconfigure the physical testbed * without breaking the tests. */ +@SuppressWarnings("removal") public abstract class MotorEncoderFixture implements ITestFixture { private static final Logger logger = Logger.getLogger(MotorEncoderFixture.class.getName()); private boolean m_initialized = false; diff --git a/xrpVendordep/src/main/java/edu/wpi/first/wpilibj/xrp/XRPMotor.java b/xrpVendordep/src/main/java/edu/wpi/first/wpilibj/xrp/XRPMotor.java index 957f9e7a3c8..6db4fc236ac 100644 --- a/xrpVendordep/src/main/java/edu/wpi/first/wpilibj/xrp/XRPMotor.java +++ b/xrpVendordep/src/main/java/edu/wpi/first/wpilibj/xrp/XRPMotor.java @@ -17,6 +17,7 @@ * *

A SimDevice based motor controller representing the motors on an XRP robot */ +@SuppressWarnings("removal") public class XRPMotor implements MotorController { private static HashMap s_simDeviceNameMap = new HashMap<>(); private static HashSet s_registeredDevices = new HashSet<>(); diff --git a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp index 02d1d587916..6d16f7b6a1b 100644 --- a/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp +++ b/xrpVendordep/src/main/native/cpp/xrp/XRPMotor.cpp @@ -6,6 +6,8 @@ #include +#include + using namespace frc; std::map XRPMotor::s_simDeviceMap = { @@ -27,6 +29,8 @@ void XRPMotor::CheckDeviceAllocation(int deviceNum) { s_registeredDevices.insert(deviceNum); } +WPI_IGNORE_DEPRECATED + XRPMotor::XRPMotor(int deviceNum) { CheckDeviceAllocation(deviceNum); @@ -42,6 +46,8 @@ XRPMotor::XRPMotor(int deviceNum) { } } +WPI_UNIGNORE_DEPRECATED + void XRPMotor::Set(double speed) { if (m_simSpeed) { bool invert = false; diff --git a/xrpVendordep/src/main/native/include/frc/xrp/XRPMotor.h b/xrpVendordep/src/main/native/include/frc/xrp/XRPMotor.h index c174cbf7e3d..8a220c08002 100644 --- a/xrpVendordep/src/main/native/include/frc/xrp/XRPMotor.h +++ b/xrpVendordep/src/main/native/include/frc/xrp/XRPMotor.h @@ -12,9 +12,12 @@ #include #include +#include namespace frc { +WPI_IGNORE_DEPRECATED + class XRPMotor : public frc::MotorController, public frc::MotorSafety { public: explicit XRPMotor(int deviceNum); @@ -43,4 +46,6 @@ class XRPMotor : public frc::MotorController, public frc::MotorSafety { static void CheckDeviceAllocation(int deviceNum); }; +WPI_UNIGNORE_DEPRECATED + } // namespace frc From 8644dde4b3c4e8667f1d7cf47557bcf3f9198d70 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 19 Dec 2023 13:12:12 -0800 Subject: [PATCH 02/10] Remove redundant motor inversion from C++ example --- .../DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp index db8ba707551..ad666b4b3eb 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp @@ -17,11 +17,6 @@ DriveSubsystem::DriveSubsystem() // gearbox is constructed, you might have to invert the left side instead. m_rightLeader.SetInverted(true); - // You might need to not do this depending on the specific motor controller - // that you are using -- contact the respective vendor's documentation for - // more details. - m_rightFollower.SetInverted(true); - m_leftFollower.Follow(m_leftLeader); m_rightFollower.Follow(m_rightLeader); From 0cef78107498eec3b4bf478ec0a1eb1100d19d1c Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 19 Dec 2023 23:20:57 -0800 Subject: [PATCH 03/10] Add Sendable getters --- .../native/cpp/drive/DifferentialDrive.cpp | 27 +++++++++++----- .../main/native/cpp/drive/MecanumDrive.cpp | 32 ++++++++++++------- .../include/frc/drive/DifferentialDrive.h | 4 +++ .../native/include/frc/drive/MecanumDrive.h | 6 ++++ .../wpilibj/drive/DifferentialDrive.java | 29 ++++++++++++----- .../wpi/first/wpilibj/drive/MecanumDrive.java | 31 +++++++++++++----- 6 files changed, 94 insertions(+), 35 deletions(-) diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index b50e9c484db..e50b86d1d39 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -49,8 +49,11 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, auto [left, right] = ArcadeDriveIK(xSpeed, zRotation, squareInputs); - m_leftMotor(left * m_maxOutput); - m_rightMotor(right * m_maxOutput); + m_leftOutput = left * m_maxOutput; + m_rightOutput = right * m_maxOutput; + + m_leftMotor(m_leftOutput); + m_rightMotor(m_rightOutput); Feed(); } @@ -69,8 +72,11 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation, auto [left, right] = CurvatureDriveIK(xSpeed, zRotation, allowTurnInPlace); - m_leftMotor(left * m_maxOutput); - m_rightMotor(right * m_maxOutput); + m_leftOutput = left * m_maxOutput; + m_rightOutput = right * m_maxOutput; + + m_leftMotor(m_leftOutput); + m_rightMotor(m_rightOutput); Feed(); } @@ -89,8 +95,11 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed, auto [left, right] = TankDriveIK(leftSpeed, rightSpeed, squareInputs); - m_leftMotor(left * m_maxOutput); - m_rightMotor(right * m_maxOutput); + m_leftOutput = left * m_maxOutput; + m_rightOutput = right * m_maxOutput; + + m_leftMotor(m_leftOutput); + m_rightMotor(m_rightOutput); Feed(); } @@ -179,6 +188,8 @@ void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("DifferentialDrive"); builder.SetActuator(true); builder.SetSafeState([=, this] { StopMotor(); }); - builder.AddDoubleProperty("Left Motor Speed", nullptr, m_leftMotor); - builder.AddDoubleProperty("Right Motor Speed", nullptr, m_rightMotor); + builder.AddDoubleProperty( + "Left Motor Speed", [&] { return m_leftOutput; }, m_leftMotor); + builder.AddDoubleProperty( + "Right Motor Speed", [&] { return m_rightOutput; }, m_rightMotor); } diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 492bf8e345c..f50122e13f7 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -60,10 +60,15 @@ void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, auto [frontLeft, frontRight, rearLeft, rearRight] = DriveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); - m_frontLeftMotor(frontLeft * m_maxOutput); - m_frontRightMotor(frontRight * m_maxOutput); - m_rearLeftMotor(rearLeft * m_maxOutput); - m_rearRightMotor(rearRight * m_maxOutput); + m_frontLeftOutput = frontLeft * m_maxOutput; + m_rearLeftOutput = rearLeft * m_maxOutput; + m_frontRightOutput = frontRight * m_maxOutput; + m_rearRightOutput = rearRight * m_maxOutput; + + m_frontLeftMotor(m_frontLeftOutput); + m_frontRightMotor(m_frontRightOutput); + m_rearLeftMotor(m_rearLeftOutput); + m_rearRightMotor(m_rearRightOutput); Feed(); } @@ -120,11 +125,16 @@ void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) { builder.SetSmartDashboardType("MecanumDrive"); builder.SetActuator(true); builder.SetSafeState([=, this] { StopMotor(); }); - builder.AddDoubleProperty("Front Left Motor Speed", nullptr, - m_frontLeftMotor); - builder.AddDoubleProperty("Front Right Motor Speed", nullptr, - m_frontRightMotor); - builder.AddDoubleProperty("Rear Left Motor Speed", nullptr, m_rearLeftMotor); - builder.AddDoubleProperty("Rear Right Motor Speed", nullptr, - m_rearRightMotor); + builder.AddDoubleProperty( + "Front Left Motor Speed", [&] { return m_frontLeftOutput; }, + m_frontLeftMotor); + builder.AddDoubleProperty( + "Front Right Motor Speed", [&] { return m_frontRightOutput; }, + m_frontRightMotor); + builder.AddDoubleProperty( + "Rear Left Motor Speed", [&] { return m_rearLeftOutput; }, + m_rearLeftMotor); + builder.AddDoubleProperty( + "Rear Right Motor Speed", [&] { return m_rearRightOutput; }, + m_rearRightMotor); } diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index c258e3869e9..afd5ecb9c9f 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -201,6 +201,10 @@ class DifferentialDrive : public RobotDriveBase, private: std::function m_leftMotor; std::function m_rightMotor; + + // Used for Sendable property getters + double m_leftOutput = 0.0; + double m_rightOutput = 0.0; }; } // namespace frc diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h index 90c436eadac..dd5a6f0f70d 100644 --- a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h @@ -173,6 +173,12 @@ class MecanumDrive : public RobotDriveBase, std::function m_frontRightMotor; std::function m_rearRightMotor; + // Used for Sendable property getters + double m_frontLeftOutput = 0.0; + double m_rearLeftOutput = 0.0; + double m_frontRightOutput = 0.0; + double m_rearRightOutput = 0.0; + bool reported = false; }; 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 a1e09775439..c77e2ea45c4 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 @@ -58,6 +58,10 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC private final DoubleConsumer m_leftMotor; private final DoubleConsumer m_rightMotor; + // Used for Sendable property getters + private double m_leftOutput; + private double m_rightOutput; + private boolean m_reported; /** @@ -162,8 +166,11 @@ public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) { var speeds = arcadeDriveIK(xSpeed, zRotation, squareInputs); - m_leftMotor.accept(speeds.left * m_maxOutput); - m_rightMotor.accept(speeds.right * m_maxOutput); + m_leftOutput = speeds.left * m_maxOutput; + m_rightOutput = speeds.right * m_maxOutput; + + m_leftMotor.accept(m_leftOutput); + m_rightMotor.accept(m_rightOutput); feed(); } @@ -191,8 +198,11 @@ public void curvatureDrive(double xSpeed, double zRotation, boolean allowTurnInP var speeds = curvatureDriveIK(xSpeed, zRotation, allowTurnInPlace); - m_leftMotor.accept(speeds.left * m_maxOutput); - m_rightMotor.accept(speeds.right * m_maxOutput); + m_leftOutput = speeds.left * m_maxOutput; + m_rightOutput = speeds.right * m_maxOutput; + + m_leftMotor.accept(m_leftOutput); + m_rightMotor.accept(m_rightOutput); feed(); } @@ -229,8 +239,11 @@ public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) var speeds = tankDriveIK(leftSpeed, rightSpeed, squareInputs); - m_leftMotor.accept(speeds.left * m_maxOutput); - m_rightMotor.accept(speeds.right * m_maxOutput); + m_leftOutput = speeds.left * m_maxOutput; + m_rightOutput = speeds.right * m_maxOutput; + + m_leftMotor.accept(m_leftOutput); + m_rightMotor.accept(m_rightOutput); feed(); } @@ -350,7 +363,7 @@ public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("DifferentialDrive"); builder.setActuator(true); builder.setSafeState(this::stopMotor); - builder.addDoubleProperty("Left Motor Speed", null, m_leftMotor::accept); - builder.addDoubleProperty("Right Motor Speed", null, m_rightMotor::accept); + builder.addDoubleProperty("Left Motor Speed", () -> m_leftOutput, m_leftMotor::accept); + builder.addDoubleProperty("Right Motor Speed", () -> m_rightOutput, m_rightMotor::accept); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index fa51a149e9a..6de7bdbff21 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -62,6 +62,12 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea private final DoubleConsumer m_frontRightMotor; private final DoubleConsumer m_rearRightMotor; + // Used for Sendable property getters + private double m_frontLeftOutput; + private double m_rearLeftOutput; + private double m_frontRightOutput; + private double m_rearRightOutput; + private boolean m_reported; /** @@ -196,10 +202,15 @@ public void driveCartesian(double xSpeed, double ySpeed, double zRotation, Rotat var speeds = driveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); - m_frontLeftMotor.accept(speeds.frontLeft * m_maxOutput); - m_frontRightMotor.accept(speeds.frontRight * m_maxOutput); - m_rearLeftMotor.accept(speeds.rearLeft * m_maxOutput); - m_rearRightMotor.accept(speeds.rearRight * m_maxOutput); + m_frontLeftOutput = speeds.frontLeft * m_maxOutput; + m_rearLeftOutput = speeds.rearLeft * m_maxOutput; + m_frontRightOutput = speeds.frontRight * m_maxOutput; + m_rearRightOutput = speeds.rearRight * m_maxOutput; + + m_frontLeftMotor.accept(m_frontLeftOutput); + m_frontRightMotor.accept(m_frontRightOutput); + m_rearLeftMotor.accept(m_rearLeftOutput); + m_rearRightMotor.accept(m_rearRightOutput); feed(); } @@ -297,9 +308,13 @@ public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("MecanumDrive"); builder.setActuator(true); builder.setSafeState(this::stopMotor); - builder.addDoubleProperty("Front Left Motor Speed", null, m_frontLeftMotor::accept); - builder.addDoubleProperty("Front Right Motor Speed", null, m_frontRightMotor::accept); - builder.addDoubleProperty("Rear Left Motor Speed", null, m_rearLeftMotor::accept); - builder.addDoubleProperty("Rear Right Motor Speed", null, m_rearRightMotor::accept); + builder.addDoubleProperty( + "Front Left Motor Speed", () -> m_frontLeftOutput, m_frontLeftMotor::accept); + builder.addDoubleProperty( + "Front Right Motor Speed", () -> m_frontRightOutput, m_frontRightMotor::accept); + builder.addDoubleProperty( + "Rear Left Motor Speed", () -> m_rearLeftOutput, m_rearLeftMotor::accept); + builder.addDoubleProperty( + "Rear Right Motor Speed", () -> m_rearRightOutput, m_rearRightMotor::accept); } } From a452b42c3546714c259cf642dacc6b1bae6062e8 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 20 Dec 2023 11:31:41 -0800 Subject: [PATCH 04/10] Update internal variables in StopMotor() --- wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp | 4 ++++ wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp | 6 ++++++ .../java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java | 4 ++++ .../main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java | 6 ++++++ 4 files changed, 20 insertions(+) diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index e50b86d1d39..b66654c0989 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -175,8 +175,12 @@ DifferentialDrive::WheelSpeeds DifferentialDrive::TankDriveIK( } void DifferentialDrive::StopMotor() { + m_leftOutput = 0.0; + m_rightOutput = 0.0; + m_leftMotor(0.0); m_rightMotor(0.0); + Feed(); } diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index f50122e13f7..ec242afea55 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -86,10 +86,16 @@ void MecanumDrive::DrivePolar(double magnitude, Rotation2d angle, } void MecanumDrive::StopMotor() { + m_frontLeftOutput = 0.0; + m_frontRightOutput = 0.0; + m_rearLeftOutput = 0.0; + m_rearRightOutput = 0.0; + m_frontLeftMotor(0.0); m_frontRightMotor(0.0); m_rearLeftMotor(0.0); m_rearRightMotor(0.0); + Feed(); } 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 c77e2ea45c4..a62d8da4373 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 @@ -348,8 +348,12 @@ public static WheelSpeeds tankDriveIK(double leftSpeed, double rightSpeed, boole @Override public void stopMotor() { + m_leftOutput = 0.0; + m_rightOutput = 0.0; + m_leftMotor.accept(0.0); m_rightMotor.accept(0.0); + feed(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 6de7bdbff21..508d5ed533c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -291,10 +291,16 @@ public static WheelSpeeds driveCartesianIK( @Override public void stopMotor() { + m_frontLeftOutput = 0.0; + m_frontRightOutput = 0.0; + m_rearLeftOutput = 0.0; + m_rearRightOutput = 0.0; + m_frontLeftMotor.accept(0.0); m_frontRightMotor.accept(0.0); m_rearLeftMotor.accept(0.0); m_rearRightMotor.accept(0.0); + feed(); } From 7456207782947d707be4154a2def8d39b901ae78 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 23 Dec 2023 16:00:13 -0800 Subject: [PATCH 05/10] Add rvalue support to PWMMotorController::AddFollower() --- .../cpp/motorcontrol/PWMMotorController.cpp | 7 +++++-- .../frc/motorcontrol/PWMMotorController.h | 18 +++++++++++++++++- 2 files changed, 22 insertions(+), 3 deletions(-) diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp index 1690138c01e..924e4fd3053 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp @@ -18,7 +18,10 @@ void PWMMotorController::Set(double speed) { } m_pwm.SetSpeed(speed); - for (auto& follower : m_followers) { + for (auto& follower : m_nonowningFollowers) { + follower->Set(speed); + } + for (auto& follower : m_owningFollowers) { follower->Set(speed); } @@ -64,7 +67,7 @@ void PWMMotorController::EnableDeadbandElimination(bool eliminateDeadband) { } void PWMMotorController::AddFollower(PWMMotorController& follower) { - m_followers.emplace_back(&follower); + m_nonowningFollowers.emplace_back(&follower); } WPI_IGNORE_DEPRECATED diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h index 7d79a087aa4..1d173a9bc47 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h @@ -4,8 +4,12 @@ #pragma once +#include +#include #include #include +#include +#include #include #include @@ -97,6 +101,17 @@ class PWMMotorController : public MotorController, */ void AddFollower(PWMMotorController& follower); + /** + * Make the given PWM motor controller follow the output of this one. + * + * @param follower The motor controller follower. + */ + template T> + void AddFollower(T&& follower) { + m_owningFollowers.emplace_back( + std::make_unique>(std::forward(follower))); + } + protected: /** * Constructor for a PWM Motor %Controller connected via PWM. @@ -113,7 +128,8 @@ class PWMMotorController : public MotorController, private: bool m_isInverted = false; - std::vector m_followers; + std::vector m_nonowningFollowers; + std::vector> m_owningFollowers; PWM* GetPwm() { return &m_pwm; } }; From c491a670362737ee5e87becb732ac0bce96984b3 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 23 Dec 2023 16:08:53 -0800 Subject: [PATCH 06/10] Move AddChild() calls to deprecated drive constructor --- .../src/main/native/cpp/drive/DifferentialDrive.cpp | 7 ++++--- wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp | 11 ++++++----- .../wpi/first/wpilibj/drive/DifferentialDrive.java | 4 ++-- .../edu/wpi/first/wpilibj/drive/MecanumDrive.java | 8 ++++---- 4 files changed, 16 insertions(+), 14 deletions(-) diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index b66654c0989..e3a0a8c4945 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -21,15 +21,16 @@ WPI_IGNORE_DEPRECATED DifferentialDrive::DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor) : DifferentialDrive{[&](double output) { leftMotor.Set(output); }, - [&](double output) { rightMotor.Set(output); }} {} + [&](double output) { rightMotor.Set(output); }} { + wpi::SendableRegistry::AddChild(this, &leftMotor); + wpi::SendableRegistry::AddChild(this, &rightMotor); +} WPI_UNIGNORE_DEPRECATED DifferentialDrive::DifferentialDrive(std::function leftMotor, std::function rightMotor) : m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} { - // wpi::SendableRegistry::AddChild(this, m_leftMotor); - // wpi::SendableRegistry::AddChild(this, m_rightMotor); static int instances = 0; ++instances; wpi::SendableRegistry::AddLW(this, "DifferentialDrive", instances); diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index ec242afea55..aeec27d0ded 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -25,7 +25,12 @@ MecanumDrive::MecanumDrive(MotorController& frontLeftMotor, : MecanumDrive{[&](double output) { frontLeftMotor.Set(output); }, [&](double output) { rearLeftMotor.Set(output); }, [&](double output) { frontRightMotor.Set(output); }, - [&](double output) { rearRightMotor.Set(output); }} {} + [&](double output) { rearRightMotor.Set(output); }} { + wpi::SendableRegistry::AddChild(this, &frontLeftMotor); + wpi::SendableRegistry::AddChild(this, &rearLeftMotor); + wpi::SendableRegistry::AddChild(this, &frontRightMotor); + wpi::SendableRegistry::AddChild(this, &rearRightMotor); +} WPI_UNIGNORE_DEPRECATED @@ -37,10 +42,6 @@ MecanumDrive::MecanumDrive(std::function frontLeftMotor, m_rearLeftMotor{std::move(rearLeftMotor)}, m_frontRightMotor{std::move(frontRightMotor)}, m_rearRightMotor{std::move(rearRightMotor)} { - // wpi::SendableRegistry::AddChild(this, m_frontLeftMotor); - // wpi::SendableRegistry::AddChild(this, m_rearLeftMotor); - // wpi::SendableRegistry::AddChild(this, m_frontRightMotor); - // wpi::SendableRegistry::AddChild(this, m_rearRightMotor); static int instances = 0; ++instances; wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances); 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 a62d8da4373..e4ca9d91c18 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 @@ -104,6 +104,8 @@ public WheelSpeeds(double left, double right) { @SuppressWarnings({"removal", "this-escape"}) public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) { this((double output) -> leftMotor.set(output), (double output) -> rightMotor.set(output)); + SendableRegistry.addChild(this, leftMotor); + SendableRegistry.addChild(this, rightMotor); } /** @@ -123,8 +125,6 @@ public DifferentialDrive(DoubleConsumer leftMotor, DoubleConsumer rightMotor) { m_leftMotor = leftMotor; m_rightMotor = rightMotor; - // SendableRegistry.addChild(this, m_leftMotor); - // SendableRegistry.addChild(this, m_rightMotor); instances++; SendableRegistry.addLW(this, "DifferentialDrive", instances); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 508d5ed533c..2c74f0bde2d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -122,6 +122,10 @@ public MecanumDrive( (double output) -> rearLeftMotor.set(output), (double output) -> frontRightMotor.set(output), (double output) -> rearRightMotor.set(output)); + SendableRegistry.addChild(this, frontLeftMotor); + SendableRegistry.addChild(this, rearLeftMotor); + SendableRegistry.addChild(this, frontRightMotor); + SendableRegistry.addChild(this, rearRightMotor); } /** @@ -149,10 +153,6 @@ public MecanumDrive( m_rearLeftMotor = rearLeftMotor; m_frontRightMotor = frontRightMotor; m_rearRightMotor = rearRightMotor; - // SendableRegistry.addChild(this, m_frontLeftMotor); - // SendableRegistry.addChild(this, m_rearLeftMotor); - // SendableRegistry.addChild(this, m_frontRightMotor); - // SendableRegistry.addChild(this, m_rearRightMotor); instances++; SendableRegistry.addLW(this, "MecanumDrive", instances); } From faaa0a03bbaf1222362e10b74c17463bdb4cbfaa Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 23 Dec 2023 18:00:43 -0800 Subject: [PATCH 07/10] Add SendableRegistry AddChild() calls to examples --- .../src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp | 5 +++++ .../examples/ArcadeDriveXboxController/cpp/Robot.cpp | 5 +++++ .../examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../Frisbeebot/cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../examples/GearsBot/cpp/subsystems/Drivetrain.cpp | 3 +++ .../src/main/cpp/examples/GettingStarted/cpp/Robot.cpp | 3 +++ .../src/main/cpp/examples/Gyro/cpp/Robot.cpp | 5 +++++ .../cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp | 5 +++++ .../HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../cpp/subsystems/DriveSubsystem.cpp | 5 +++++ .../src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp | 5 +++++ .../RamseteCommand/cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../RapidReactCommandBot/cpp/subsystems/Drive.cpp | 3 +++ .../RomiReference/cpp/subsystems/Drivetrain.cpp | 3 +++ .../src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp | 3 +++ .../cpp/subsystems/DriveSubsystem.cpp | 3 +++ .../src/main/cpp/examples/TankDrive/cpp/Robot.cpp | 3 +++ .../cpp/examples/TankDriveXboxController/cpp/Robot.cpp | 3 +++ .../src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp | 5 +++++ .../main/cpp/examples/UltrasonicPID/include/Robot.h | 1 + .../XRPReference/cpp/subsystems/Drivetrain.cpp | 3 +++ .../wpi/first/wpilibj/examples/arcadedrive/Robot.java | 6 ++++++ .../examples/arcadedrivexboxcontroller/Robot.java | 6 ++++++ .../examples/armbot/subsystems/DriveSubsystem.java | 4 ++++ .../armbotoffboard/subsystems/DriveSubsystem.java | 4 ++++ .../subsystems/DriveSubsystem.java | 4 ++++ .../examples/frisbeebot/subsystems/DriveSubsystem.java | 4 ++++ .../examples/gearsbot/subsystems/Drivetrain.java | 4 ++++ .../first/wpilibj/examples/gettingstarted/Robot.java | 6 ++++++ .../edu/wpi/first/wpilibj/examples/gyro/Robot.java | 10 ++++++++-- .../gyrodrivecommands/subsystems/DriveSubsystem.java | 4 ++++ .../wpi/first/wpilibj/examples/gyromecanum/Robot.java | 6 ++++++ .../hatchbotinlined/subsystems/DriveSubsystem.java | 4 ++++ .../hatchbottraditional/subsystems/DriveSubsystem.java | 4 ++++ .../subsystems/DriveSubsystem.java | 6 ++++++ .../wpi/first/wpilibj/examples/mecanumdrive/Robot.java | 6 ++++++ .../ramsetecommand/subsystems/DriveSubsystem.java | 4 ++++ .../rapidreactcommandbot/subsystems/Drive.java | 4 ++++ .../examples/romireference/subsystems/Drivetrain.java | 4 ++++ .../wpi/first/wpilibj/examples/shuffleboard/Robot.java | 4 ++++ .../subsystems/DriveSubsystem.java | 4 ++++ .../wpi/first/wpilibj/examples/tankdrive/Robot.java | 10 +++++++--- .../examples/tankdrivexboxcontroller/Robot.java | 4 ++++ .../first/wpilibj/examples/ultrasonicpid/Robot.java | 6 ++++++ .../examples/xrpreference/subsystems/Drivetrain.java | 4 ++++ 49 files changed, 204 insertions(+), 5 deletions(-) diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp index 067506bbfe8..9c8d64064fa 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp @@ -20,6 +20,11 @@ class Robot : public frc::TimedRobot { frc::Joystick m_stick{0}; public: + Robot() { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + } + void RobotInit() override { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp index db97498a058..38ff862ab96 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp @@ -20,6 +20,11 @@ class Robot : public frc::TimedRobot { frc::XboxController m_driverController{0}; public: + Robot() { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + } + void RobotInit() override { // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp index 0ca95c0c218..13522950d80 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp @@ -13,6 +13,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp index 3c3f789d193..236d4682357 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp @@ -13,6 +13,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp index ad666b4b3eb..84fae4f2f0e 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp @@ -12,6 +12,9 @@ DriveSubsystem::DriveSubsystem() m_rightLeader{kRightMotor1Port}, m_rightFollower{kRightMotor2Port}, m_feedforward{ks, kv, ka} { + wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader); + wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp index 53f289c3119..0e4068f22eb 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp @@ -13,6 +13,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp index 34a84b6c0b2..2928036afc9 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp @@ -11,6 +11,9 @@ #include Drivetrain::Drivetrain() { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight); + m_frontLeft.AddFollower(m_rearLeft); m_frontRight.AddFollower(m_rearRight); diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp index 43380851815..0a73f1402f8 100644 --- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp @@ -11,6 +11,9 @@ class Robot : public frc::TimedRobot { public: Robot() { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp index f5db62ef406..d8af4100acb 100644 --- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp @@ -17,6 +17,11 @@ */ class Robot : public frc::TimedRobot { public: + Robot() { + wpi::SendableRegistry::AddChild(&m_drive, &m_left); + wpi::SendableRegistry::AddChild(&m_drive, &m_right); + } + void RobotInit() override { m_gyro.SetSensitivity(kVoltsPerDegreePerSecond); // We need to invert one side of the drivetrain so that positive voltages diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp index 234f837c9ba..a97a5c071f6 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp @@ -13,6 +13,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp index cdd3ef5be8f..7c589fd268e 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp @@ -16,6 +16,11 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight); + // Invert the right side motors. You may need to change or remove this to // match your robot. m_frontRight.SetInverted(true); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp index 44e56bf2c85..d7b33eac79d 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp @@ -15,6 +15,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp index 44e56bf2c85..d7b33eac79d 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp @@ -15,6 +15,9 @@ DriveSubsystem::DriveSubsystem() m_right2{kRightMotor2Port}, m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp index 292ad1f52c9..8a55821e71b 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp @@ -30,6 +30,11 @@ DriveSubsystem::DriveSubsystem() m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), getCurrentWheelDistances(), frc::Pose2d{}} { + wpi::SendableRegistry::AddChild(&m_drive, &m_frontLeft); + wpi::SendableRegistry::AddChild(&m_drive, &m_rearLeft); + wpi::SendableRegistry::AddChild(&m_drive, &m_frontRight); + wpi::SendableRegistry::AddChild(&m_drive, &m_rearRight); + // Set the distance per pulse for the encoders m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse); diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp index 3a450be766c..eeb9ce13233 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp @@ -14,6 +14,11 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight); + // Invert the right side motors. You may need to change or remove this to // match your robot. m_frontRight.SetInverted(true); diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp index 9ac07694e85..13e830678e6 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp @@ -17,6 +17,9 @@ DriveSubsystem::DriveSubsystem() m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]}, m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]}, m_odometry{m_gyro.GetRotation2d(), units::meter_t{0}, units::meter_t{0}} { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp index b7857ec542c..e03ce432124 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp @@ -9,6 +9,9 @@ #include Drive::Drive() { + wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader); + wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader); + m_leftLeader.AddFollower(m_leftFollower); m_rightLeader.AddFollower(m_rightFollower); diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp index 979f8a0e5d4..1d212d5c5d8 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp @@ -15,6 +15,9 @@ using namespace DriveConstants; // The Romi has onboard encoders that are hardcoded // to use DIO pins 4/5 and 6/7 for the left and right Drivetrain::Drivetrain() { + wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp index da8ccd141d4..b532bcbf75b 100644 --- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp @@ -30,6 +30,9 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right); + // Add a widget titled 'Max Speed' with a number slider. m_maxSpeed = frc::Shuffleboard::GetTab("Configuration") .Add("Max Speed", 1) diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp index af14c689b5b..ecef64ad82f 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp @@ -14,6 +14,9 @@ using namespace DriveConstants; DriveSubsystem::DriveSubsystem() { + wpi::SendableRegistry::AddChild(&m_drive, &m_left1); + wpi::SendableRegistry::AddChild(&m_drive, &m_right1); + m_left1.AddFollower(m_left2); m_right1.AddFollower(m_right2); diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp index 1d91437efaa..f7b3e9c6900 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp @@ -22,6 +22,9 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp index 250c002341e..7c0706ef791 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp @@ -21,6 +21,9 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp index 9d2b5c2003c..fecaf97fb9d 100644 --- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp @@ -4,6 +4,11 @@ #include "Robot.h" +Robot::Robot() { + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left); + wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right); +} + void Robot::AutonomousInit() { // Set setpoint of the pid controller m_pidController.SetSetpoint(kHoldDistance.value()); diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h index 9c272c4de09..696f0668fc9 100644 --- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h +++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h @@ -18,6 +18,7 @@ */ class Robot : public frc::TimedRobot { public: + Robot(); void AutonomousInit() override; void AutonomousPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp index bcec018bcda..25c520cef25 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp @@ -15,6 +15,9 @@ using namespace DriveConstants; // The XRP has onboard encoders that are hardcoded // to use DIO pins 4/5 and 6/7 for the left and right Drivetrain::Drivetrain() { + wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java index 20b2e17522c..aa343799a01 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.arcadedrive; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -20,6 +21,11 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final Joystick m_stick = new Joystick(0); + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); + } + @Override public void robotInit() { // We need to invert one side of the drivetrain so that positive voltages diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java index d10e7d3025e..a376fe0ae48 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.arcadedrivexboxcontroller; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -20,6 +21,11 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final XboxController m_driverController = new XboxController(0); + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); + } + @Override public void robotInit() { // We need to invert one side of the drivetrain so that positive voltages diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java index dde17979135..246b5c41185 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.armbot.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants; @@ -39,6 +40,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java index 2dbf00b2c04..f01ad9987d7 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants; @@ -42,6 +43,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + // Sets the distance per pulse for the encoders m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java index 6273d099b78..59d700bb1ed 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java @@ -6,6 +6,7 @@ import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.trajectory.TrapezoidProfile; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants; import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController; @@ -39,6 +40,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java index b126e86eb68..dc3a3c6cc1b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.frisbeebot.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants; @@ -39,6 +40,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); 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 60ad2a5e2ff..b632f8d5cac 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.gearsbot.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.Encoder; @@ -42,6 +43,9 @@ public class Drivetrain extends SubsystemBase { public Drivetrain() { super(); + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); 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 2474242c874..563235c2e1d 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.gettingstarted; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.XboxController; @@ -24,6 +25,11 @@ public class Robot extends TimedRobot { private final XboxController m_controller = new XboxController(0); private final Timer m_timer = new Timer(); + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftDrive); + SendableRegistry.addChild(m_robotDrive, m_rightDrive); + } + /** * This function is run when the robot is first started up and should be used for any * initialization code. 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 0da37bb762c..7d00c274e57 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.gyro; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; @@ -30,11 +31,16 @@ public class Robot extends TimedRobot { private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort); private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort); - private final DifferentialDrive m_myRobot = + private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive::set, m_rightDrive::set); private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort); private final Joystick m_joystick = new Joystick(kJoystickPort); + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftDrive); + SendableRegistry.addChild(m_robotDrive, m_rightDrive); + } + @Override public void robotInit() { m_gyro.setSensitivity(kVoltsPerDegreePerSecond); @@ -51,6 +57,6 @@ public void robotInit() { @Override public void teleopPeriodic() { double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP; - m_myRobot.arcadeDrive(-m_joystick.getY(), -turningValue); + m_robotDrive.arcadeDrive(-m_joystick.getY(), -turningValue); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java index 55ebe1053ad..db874104b6b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.gyrodrivecommands.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.ADXRS450_Gyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -43,6 +44,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); 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 b86277b8a88..a1adcc17f93 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.gyromecanum; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; @@ -37,6 +38,11 @@ public void robotInit() { PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel); PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel); + SendableRegistry.addChild(m_robotDrive, frontLeft); + SendableRegistry.addChild(m_robotDrive, rearLeft); + SendableRegistry.addChild(m_robotDrive, frontRight); + SendableRegistry.addChild(m_robotDrive, rearRight); + // Invert the right side motors. // You may need to change or remove this to match your robot. frontRight.setInverted(true); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java index 9c28511c444..8de4a90c294 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java @@ -5,6 +5,7 @@ package edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems; import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants; @@ -40,6 +41,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java index b3f2adae6ac..8942b41ca97 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java @@ -5,6 +5,7 @@ package edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems; import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants; @@ -40,6 +41,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java index 6d731bad428..a51f61213eb 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java @@ -9,6 +9,7 @@ import edu.wpi.first.math.kinematics.MecanumDriveOdometry; import edu.wpi.first.math.kinematics.MecanumDriveWheelPositions; import edu.wpi.first.math.kinematics.MecanumDriveWheelSpeeds; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.ADXRS450_Gyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.MecanumDrive; @@ -65,6 +66,11 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_frontLeft); + SendableRegistry.addChild(m_drive, m_rearLeft); + SendableRegistry.addChild(m_drive, m_frontRight); + SendableRegistry.addChild(m_drive, m_rearRight); + // Sets the distance per pulse for the encoders m_frontLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); m_rearLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse); 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 f37654321da..4436130bc2e 100644 --- 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.mecanumdrive; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.MecanumDrive; @@ -28,6 +29,11 @@ public void robotInit() { PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel); PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel); + SendableRegistry.addChild(m_robotDrive, frontLeft); + SendableRegistry.addChild(m_robotDrive, rearLeft); + SendableRegistry.addChild(m_robotDrive, frontRight); + SendableRegistry.addChild(m_robotDrive, rearRight); + // Invert the right side motors. // You may need to change or remove this to match your robot. frontRight.setInverted(true); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java index f5ae467edcb..f2b08406f40 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java @@ -7,6 +7,7 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.kinematics.DifferentialDriveOdometry; import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.ADXRS450_Gyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -49,6 +50,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java index 3637110a2a4..dd7854d15ff 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConstants; @@ -41,6 +42,9 @@ public class Drive extends SubsystemBase { /** Creates a new Drive subsystem. */ public Drive() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java index c0b1a3cbe2d..42cf45eef8c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.romireference.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.BuiltInAccelerometer; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -37,6 +38,9 @@ public class Drivetrain extends SubsystemBase { /** Creates a new Drivetrain. */ public Drivetrain() { + SendableRegistry.addChild(m_diffDrive, m_leftMotor); + SendableRegistry.addChild(m_diffDrive, m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. 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 dbf4a902686..436d72685d4 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 @@ -5,6 +5,7 @@ package edu.wpi.first.wpilibj.examples.shuffleboard; import edu.wpi.first.networktables.GenericEntry; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.AnalogPotentiometer; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.TimedRobot; @@ -29,6 +30,9 @@ public class Robot extends TimedRobot { @Override public void robotInit() { + SendableRegistry.addChild(m_tankDrive, m_leftDriveMotor); + SendableRegistry.addChild(m_tankDrive, m_rightDriveMotor); + // Add a 'max speed' widget to a tab named 'Configuration', using a number slider // The widget will be placed in the second column and row and will be TWO columns wide m_maxSpeed = diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java index def536c489a..79c871cbb45 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java @@ -9,6 +9,7 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.DifferentialDriveOdometry; import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.ADXRS450_Gyro; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.RobotBase; @@ -66,6 +67,9 @@ public class DriveSubsystem extends SubsystemBase { /** Creates a new DriveSubsystem. */ public DriveSubsystem() { + SendableRegistry.addChild(m_drive, m_leftLeader); + SendableRegistry.addChild(m_drive, m_rightLeader); + m_leftLeader.addFollower(m_leftFollower); m_rightLeader.addFollower(m_rightFollower); 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 80001154a26..a217f51b559 100644 --- 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 @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.tankdrive; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -14,7 +15,7 @@ * the code necessary to operate a robot with tank drive. */ public class Robot extends TimedRobot { - private DifferentialDrive m_myRobot; + private DifferentialDrive m_robotDrive; private Joystick m_leftStick; private Joystick m_rightStick; @@ -23,18 +24,21 @@ public class Robot extends TimedRobot { @Override public void robotInit() { + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. m_rightMotor.setInverted(true); - m_myRobot = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); + m_robotDrive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); m_leftStick = new Joystick(0); m_rightStick = new Joystick(1); } @Override public void teleopPeriodic() { - m_myRobot.tankDrive(-m_leftStick.getY(), -m_rightStick.getY()); + m_robotDrive.tankDrive(-m_leftStick.getY(), -m_rightStick.getY()); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java index 8305ac1f932..c1a850c5f70 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.tankdrivexboxcontroller; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -22,6 +23,9 @@ public class Robot extends TimedRobot { @Override public void robotInit() { + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. 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 e4b24e713ba..33681d00859 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 @@ -6,6 +6,7 @@ import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.filter.MedianFilter; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.Ultrasonic; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -44,6 +45,11 @@ public class Robot extends TimedRobot { new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final PIDController m_pidController = new PIDController(kP, kI, kD); + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftMotor); + SendableRegistry.addChild(m_robotDrive, m_rightMotor); + } + @Override public void autonomousInit() { // Set setpoint of the pid controller diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java index 7f19d35c50e..87b985d6522 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrpreference/subsystems/Drivetrain.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj.examples.xrpreference.subsystems; +import edu.wpi.first.util.sendable.SendableRegistry; import edu.wpi.first.wpilibj.BuiltInAccelerometer; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.drive.DifferentialDrive; @@ -40,6 +41,9 @@ public class Drivetrain extends SubsystemBase { /** Creates a new Drivetrain. */ public Drivetrain() { + SendableRegistry.addChild(m_diffDrive, m_leftMotor); + SendableRegistry.addChild(m_diffDrive, m_rightMotor); + // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's // gearbox is constructed, you might have to invert the left side instead. From ff4c567c10ee5f1aedac8489bc0e25ce7278af2b Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 23 Dec 2023 18:14:05 -0800 Subject: [PATCH 08/10] Deprecate MecanumDrive constructor --- .../src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java | 2 ++ .../java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java | 2 +- .../mecanumcontrollercommand/subsystems/DriveSubsystem.java | 2 +- .../java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java | 2 +- 4 files changed, 5 insertions(+), 3 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 2c74f0bde2d..681472a8a1d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -110,7 +110,9 @@ public WheelSpeeds(double frontLeft, double frontRight, double rearLeft, double * @param rearLeftMotor The motor on the rear-left corner. * @param frontRightMotor The motor on the front-right corner. * @param rearRightMotor The motor on the rear-right corner. + * @deprecated Use MecanumDrive constructor with function arguments. */ + @Deprecated(forRemoval = true, since = "2024") @SuppressWarnings({"removal", "this-escape"}) public MecanumDrive( MotorController frontLeftMotor, 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 a1adcc17f93..a43523252c4 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 @@ -48,7 +48,7 @@ public void robotInit() { frontRight.setInverted(true); rearRight.setInverted(true); - m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight); + m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set); m_gyro.setSensitivity(kVoltsPerDegreePerSecond); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java index a51f61213eb..b3f9b3462ab 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java @@ -24,7 +24,7 @@ public class DriveSubsystem extends SubsystemBase { private final PWMSparkMax m_rearRight = new PWMSparkMax(DriveConstants.kRearRightMotorPort); private final MecanumDrive m_drive = - new MecanumDrive(m_frontLeft, m_rearLeft, m_frontRight, m_rearRight); + new MecanumDrive(m_frontLeft::set, m_rearLeft::set, m_frontRight::set, m_rearRight::set); // The front-left-side drive encoder private final Encoder m_frontLeftEncoder = 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 4436130bc2e..77aa0cedb71 100644 --- 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 @@ -39,7 +39,7 @@ public void robotInit() { frontRight.setInverted(true); rearRight.setInverted(true); - m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight); + m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set); m_stick = new Joystick(kJoystickChannel); } From 26e05e82899bb6ad960d4a35ad6f2bb5f3ed243b Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 23 Dec 2023 18:19:33 -0800 Subject: [PATCH 09/10] Undeprecate MotorController drive constructors for now --- wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h | 1 - wpilibc/src/main/native/include/frc/drive/MecanumDrive.h | 1 - .../java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java | 2 -- .../src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java | 2 -- 4 files changed, 6 deletions(-) diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index afd5ecb9c9f..b4303d5b01c 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -81,7 +81,6 @@ class DifferentialDrive : public RobotDriveBase, * @param leftMotor Left motor. * @param rightMotor Right motor. */ - WPI_DEPRECATED("Use DifferentialDrive constructor with function arguments.") DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor); WPI_UNIGNORE_DEPRECATED diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h index dd5a6f0f70d..6f33f93ab64 100644 --- a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h @@ -83,7 +83,6 @@ class MecanumDrive : public RobotDriveBase, * @param frontRightMotor Front-right motor. * @param rearRightMotor Rear-right motor. */ - WPI_DEPRECATED("Use MecanumDrive constructor with function arguments.") MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor, MotorController& frontRightMotor, MotorController& rearRightMotor); 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 e4ca9d91c18..69e27672a9e 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 @@ -98,9 +98,7 @@ public WheelSpeeds(double left, double right) { * * @param leftMotor Left motor. * @param rightMotor Right motor. - * @deprecated Use DifferentialDrive constructor with function arguments. */ - @Deprecated(forRemoval = true, since = "2024") @SuppressWarnings({"removal", "this-escape"}) public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) { this((double output) -> leftMotor.set(output), (double output) -> rightMotor.set(output)); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 681472a8a1d..2c74f0bde2d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -110,9 +110,7 @@ public WheelSpeeds(double frontLeft, double frontRight, double rearLeft, double * @param rearLeftMotor The motor on the rear-left corner. * @param frontRightMotor The motor on the front-right corner. * @param rearRightMotor The motor on the rear-right corner. - * @deprecated Use MecanumDrive constructor with function arguments. */ - @Deprecated(forRemoval = true, since = "2024") @SuppressWarnings({"removal", "this-escape"}) public MecanumDrive( MotorController frontLeftMotor, From 28dfe3e6e883a963fa368a9c9d7b3e766c3c408f Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 26 Dec 2023 14:30:23 -0800 Subject: [PATCH 10/10] Undeprecate MotorController --- .../main/native/include/frc/motorcontrol/MotorController.h | 3 +-- .../wpi/first/wpilibj/motorcontrol/MotorController.java | 7 +------ 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h b/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h index 1b3716d0f3b..24e1b179554 100644 --- a/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h +++ b/wpilibc/src/main/native/include/frc/motorcontrol/MotorController.h @@ -11,8 +11,7 @@ namespace frc { /** * Interface for motor controlling devices. */ -class [[deprecated( - "This class is being removed with no replacement")]] MotorController { +class MotorController { public: virtual ~MotorController() = default; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java index cf080898cd6..4cd50da11d8 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorController.java @@ -6,12 +6,7 @@ import edu.wpi.first.wpilibj.RobotController; -/** - * Interface for motor controlling devices. - * - * @deprecated This class is being removed with no replacement. - */ -@Deprecated(forRemoval = true, since = "2024") +/** Interface for motor controlling devices. */ public interface MotorController { /** * Common interface for setting the speed of a motor controller.