[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

@@ -11,10 +11,16 @@
#include <units/length.h>
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);
// 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

View File

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