mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[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:
@@ -14,10 +14,17 @@
|
||||
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:
|
||||
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
|
||||
|
||||
@@ -14,10 +14,17 @@
|
||||
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:
|
||||
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
|
||||
|
||||
@@ -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() {
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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() {
|
||||
|
||||
@@ -4,15 +4,13 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
* controller.
|
||||
*
|
||||
* <p>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() {}
|
||||
};
|
||||
|
||||
@@ -8,7 +8,6 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Commands.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
@@ -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;
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/angular_velocity.h>
|
||||
@@ -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};
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -21,7 +21,6 @@
|
||||
#include <frc/geometry/Quaternion.h>
|
||||
#include <frc/geometry/Transform3d.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/AnalogGyroSim.h>
|
||||
#include <frc/simulation/DifferentialDrivetrainSim.h>
|
||||
@@ -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};
|
||||
|
||||
|
||||
@@ -12,16 +12,14 @@ 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.
|
||||
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);
|
||||
|
||||
|
||||
@@ -4,15 +4,13 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
* controller.
|
||||
*
|
||||
* <p>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;
|
||||
|
||||
@@ -83,5 +83,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::SimpleMotorFeedforward<units::meters> 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); }};
|
||||
};
|
||||
|
||||
@@ -4,15 +4,13 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
* controller.
|
||||
*
|
||||
* <p>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() {}
|
||||
};
|
||||
|
||||
@@ -4,15 +4,13 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
* controller.
|
||||
*
|
||||
* <p>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() {}
|
||||
};
|
||||
|
||||
@@ -13,10 +13,16 @@ 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);
|
||||
|
||||
// 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);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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};
|
||||
|
||||
@@ -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.
|
||||
@@ -48,7 +51,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;
|
||||
|
||||
@@ -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
|
||||
@@ -50,7 +55,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};
|
||||
|
||||
@@ -13,10 +13,16 @@ 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);
|
||||
|
||||
// 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);
|
||||
|
||||
@@ -7,7 +7,6 @@
|
||||
#include <frc/ADXRS450_Gyro.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>
|
||||
#include <units/angle.h>
|
||||
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
@@ -48,8 +53,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};
|
||||
|
||||
@@ -15,10 +15,16 @@ 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);
|
||||
|
||||
// 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);
|
||||
|
||||
@@ -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>
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -15,10 +15,16 @@ 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);
|
||||
|
||||
// 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);
|
||||
|
||||
@@ -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>
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
@@ -40,8 +45,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};
|
||||
};
|
||||
|
||||
@@ -17,10 +17,16 @@ 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);
|
||||
|
||||
// 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 +47,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();
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,6 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/geometry/Pose2d.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/voltage.h>
|
||||
@@ -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;
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/angular_velocity.h>
|
||||
#include <units/length.h>
|
||||
@@ -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};
|
||||
|
||||
|
||||
@@ -9,10 +9,16 @@
|
||||
#include <frc2/command/Commands.h>
|
||||
|
||||
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);
|
||||
|
||||
// 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);
|
||||
|
||||
@@ -8,7 +8,6 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
@@ -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],
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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)
|
||||
@@ -65,7 +68,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};
|
||||
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/AnalogGyroSim.h>
|
||||
#include <frc/simulation/DifferentialDrivetrainSim.h>
|
||||
@@ -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};
|
||||
|
||||
|
||||
@@ -14,10 +14,16 @@
|
||||
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);
|
||||
|
||||
// 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 +46,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 +68,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();
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,6 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/geometry/Pose2d.h>
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/ADXRS450_GyroSim.h>
|
||||
#include <frc/simulation/DifferentialDrivetrainSim.h>
|
||||
@@ -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],
|
||||
|
||||
@@ -14,12 +14,17 @@
|
||||
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};
|
||||
|
||||
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.
|
||||
|
||||
@@ -14,11 +14,16 @@
|
||||
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:
|
||||
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.
|
||||
|
||||
@@ -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());
|
||||
|
||||
@@ -18,6 +18,7 @@
|
||||
*/
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
Robot();
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
|
||||
@@ -44,6 +45,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};
|
||||
};
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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;
|
||||
|
||||
Reference in New Issue
Block a user