[wpilib] Add functional interface equivalents to MotorController (#6053)

This does not deprecate any current functionality, but prepares the way for future deprecation.

The drive classes now accept void(double) functions, which makes them more flexible.

The C++ API ended up a bit more verbose, but the Java API is really concise with method references, which is >80% of our userbase. For example:

`DifferentialDrive drive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);`

Lambdas can be passed to interoperate with vendor motor controller APIs that don't have e.g., set(double), so CTRE doesn't have to maintain their WPI_ classes anymore.

MotorControllerGroup was replaced with PWMMotorController.addFollower() for PWM motor controllers. Users of CAN motor controllers should use their vendor's follower functionality.
This commit is contained in:
Tyler Veness
2024-01-01 13:37:51 -08:00
committed by GitHub
parent 8aca706217
commit e7c9f27683
132 changed files with 1159 additions and 697 deletions

View File

@@ -13,13 +13,20 @@ 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);
// 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() {

View File

@@ -6,7 +6,6 @@
#include <frc/Encoder.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/motorcontrol/MotorControllerGroup.h>
#include <frc/motorcontrol/PWMSparkMax.h>
#include <frc2/command/SubsystemBase.h>
@@ -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;