mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Move motor controllers to motorcontrol package (#3302)
Also deprecate SpeedController in favor of motorcontrol.MotorController and SpeedControllerGroup in favor of motorcontrol.MotorControllerGroup. The MotorController interface is derived from the SpeedController interface so that code such as SpeedController x = new VictorSP(1) continues to compile (just with a warning). SpeedControllerGroup and MotorControllerGroup are independent classes; both implement the MotorController interface.
This commit is contained in:
@@ -3,9 +3,9 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
|
||||
@@ -3,10 +3,10 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/ArmFeedforward.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/ProfiledPIDSubsystem.h>
|
||||
#include <units/angle.h>
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -76,10 +76,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/SpeedController.h>
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
@@ -12,7 +12,7 @@
|
||||
*
|
||||
* <p>Has no actual functionality.
|
||||
*/
|
||||
class ExampleSmartMotorController : public frc::SpeedController {
|
||||
class ExampleSmartMotorController : public frc::MotorController {
|
||||
public:
|
||||
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -76,10 +76,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/RobotController.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/BatterySim.h>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
#include <frc/simulation/RoboRioSim.h>
|
||||
|
||||
@@ -6,12 +6,12 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#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>
|
||||
#include <units/length.h>
|
||||
@@ -57,8 +57,8 @@ class Drivetrain {
|
||||
frc::PWMSparkMax m_rightLeader{3};
|
||||
frc::PWMSparkMax m_rightFollower{4};
|
||||
|
||||
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
|
||||
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
|
||||
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};
|
||||
|
||||
@@ -6,12 +6,12 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/estimator/DifferentialDrivePoseEstimator.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/angular_velocity.h>
|
||||
#include <units/length.h>
|
||||
@@ -57,8 +57,8 @@ class Drivetrain {
|
||||
frc::PWMSparkMax m_rightLeader{3};
|
||||
frc::PWMSparkMax m_rightFollower{4};
|
||||
|
||||
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
|
||||
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
|
||||
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};
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/SpeedController.h>
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
@@ -12,7 +12,7 @@
|
||||
*
|
||||
* <p>Has no actual functionality.
|
||||
*/
|
||||
class ExampleSmartMotorController : public frc::SpeedController {
|
||||
class ExampleSmartMotorController : public frc::MotorController {
|
||||
public:
|
||||
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
|
||||
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
#include <units/acceleration.h>
|
||||
#include <units/length.h>
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/RobotController.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/simulation/BatterySim.h>
|
||||
#include <frc/simulation/ElevatorSim.h>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/SpeedController.h>
|
||||
#include <frc/motorcontrol/MotorController.h>
|
||||
|
||||
/**
|
||||
* A simplified stub class that simulates the API of a common "smart" motor
|
||||
@@ -12,7 +12,7 @@
|
||||
*
|
||||
* <p>Has no actual functionality.
|
||||
*/
|
||||
class ExampleSmartMotorController : public frc::SpeedController {
|
||||
class ExampleSmartMotorController : public frc::MotorController {
|
||||
public:
|
||||
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -76,10 +76,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -5,8 +5,8 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/PIDSubsystem.h>
|
||||
#include <units/angle.h>
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
/**
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/AnalogInput.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
namespace frc {
|
||||
@@ -66,11 +66,11 @@ class DriveTrain : public frc2::SubsystemBase {
|
||||
private:
|
||||
frc::PWMSparkMax m_frontLeft{1};
|
||||
frc::PWMSparkMax m_rearLeft{2};
|
||||
frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
|
||||
frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft};
|
||||
|
||||
frc::PWMSparkMax m_frontRight{3};
|
||||
frc::PWMSparkMax m_rearRight{4};
|
||||
frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
|
||||
frc::MotorControllerGroup m_right{m_frontRight, m_rearRight};
|
||||
|
||||
frc::DifferentialDrive m_robotDrive{m_left, m_right};
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/PIDSubsystem.h>
|
||||
|
||||
/**
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/PIDSubsystem.h>
|
||||
|
||||
/**
|
||||
|
||||
@@ -3,11 +3,11 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/Timer.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/livewindow/LiveWindow.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a gyro sensor to make a
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.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>
|
||||
|
||||
@@ -92,10 +92,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a sample program that uses mecanum drive with a gyro sensor to
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -76,10 +76,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -76,10 +76,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -6,13 +6,13 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/MecanumDriveKinematics.h>
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <wpi/math>
|
||||
|
||||
/**
|
||||
|
||||
@@ -96,7 +96,7 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
|
||||
|
||||
[this](units::volt_t frontLeft, units::volt_t rearLeft,
|
||||
units::volt_t frontRight, units::volt_t rearRight) {
|
||||
m_drive.SetSpeedControllersVolts(frontLeft, rearLeft, frontRight,
|
||||
m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight,
|
||||
rearRight);
|
||||
},
|
||||
|
||||
|
||||
@@ -56,7 +56,7 @@ void DriveSubsystem::Drive(double xSpeed, double ySpeed, double rot,
|
||||
}
|
||||
}
|
||||
|
||||
void DriveSubsystem::SetSpeedControllersVolts(units::volt_t frontLeftPower,
|
||||
void DriveSubsystem::SetMotorControllersVolts(units::volt_t frontLeftPower,
|
||||
units::volt_t rearLeftPower,
|
||||
units::volt_t frontRightPower,
|
||||
units::volt_t rearRightPower) {
|
||||
|
||||
@@ -6,13 +6,13 @@
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/geometry/Pose2d.h>
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <frc/interfaces/Gyro.h>
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -82,9 +82,9 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::MecanumDriveWheelSpeeds getCurrentWheelSpeeds();
|
||||
|
||||
/**
|
||||
* Sets the drive SpeedControllers to a desired voltage.
|
||||
* Sets the drive MotorControllers to a desired voltage.
|
||||
*/
|
||||
void SetSpeedControllersVolts(units::volt_t frontLeftPower,
|
||||
void SetMotorControllersVolts(units::volt_t frontLeftPower,
|
||||
units::volt_t rearLeftPower,
|
||||
units::volt_t frontRightPower,
|
||||
units::volt_t rearRightPower);
|
||||
|
||||
@@ -3,9 +3,9 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a demo program showing how to use Mecanum control with the
|
||||
|
||||
@@ -6,7 +6,6 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/estimator/MecanumDrivePoseEstimator.h>
|
||||
@@ -14,6 +13,7 @@
|
||||
#include <frc/kinematics/MecanumDriveKinematics.h>
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <wpi/math>
|
||||
|
||||
/**
|
||||
|
||||
@@ -3,8 +3,8 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This sample program shows how to control a motor using a joystick. In the
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <wpi/math>
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/Solenoid.h>
|
||||
#include <frc/commands/Subsystem.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* The Collector subsystem has one motor for the rollers, a limit switch for
|
||||
|
||||
@@ -6,10 +6,10 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/commands/Subsystem.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
namespace frc {
|
||||
class Joystick;
|
||||
@@ -62,11 +62,11 @@ class DriveTrain : public frc::Subsystem {
|
||||
// Subsystem devices
|
||||
frc::PWMSparkMax m_frontLeftCIM{1};
|
||||
frc::PWMSparkMax m_rearLeftCIM{2};
|
||||
frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
|
||||
frc::MotorControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
|
||||
|
||||
frc::PWMSparkMax m_frontRightCIM{3};
|
||||
frc::PWMSparkMax m_rearRightCIM{4};
|
||||
frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
|
||||
frc::MotorControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
|
||||
|
||||
frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
|
||||
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/commands/PIDSubsystem.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* The Pivot subsystem contains the Van-door motor and the pot for PID control
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
|
||||
#include <frc/AnalogInput.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a soft potentiometer and a
|
||||
|
||||
@@ -6,11 +6,11 @@
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#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>
|
||||
|
||||
@@ -123,10 +123,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2;
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -6,12 +6,12 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#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>
|
||||
#include <wpi/math>
|
||||
@@ -57,8 +57,8 @@ class Drivetrain {
|
||||
frc::PWMSparkMax m_rightLeader{3};
|
||||
frc::PWMSparkMax m_rightFollower{4};
|
||||
|
||||
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
|
||||
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
|
||||
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};
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <frc/BuiltInAccelerometer.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Spark.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/Spark.h>
|
||||
#include <frc/romi/RomiGyro.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/length.h>
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#include <frc/AnalogPotentiometer.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/shuffleboard/Shuffleboard.h>
|
||||
#include <frc/shuffleboard/ShuffleboardLayout.h>
|
||||
#include <frc/shuffleboard/ShuffleboardTab.h>
|
||||
|
||||
@@ -6,12 +6,12 @@
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#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>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
@@ -73,8 +73,8 @@ class Drivetrain {
|
||||
frc::PWMSparkMax m_rightLeader{3};
|
||||
frc::PWMSparkMax m_rightFollower{4};
|
||||
|
||||
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
|
||||
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
|
||||
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};
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
@@ -12,6 +11,7 @@
|
||||
#include <frc/controller/LinearQuadraticRegulator.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/estimator/KalmanFilter.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/system/LinearSystemLoop.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
|
||||
@@ -6,11 +6,11 @@
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/SpeedControllerGroup.h>
|
||||
#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>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
@@ -134,10 +134,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
frc::PWMSparkMax m_right2{DriveConstants::kRightMotor2Port};
|
||||
|
||||
// The motors on the left side of the drive
|
||||
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
|
||||
|
||||
// The motors on the right side of the drive
|
||||
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
|
||||
|
||||
// The robot's drive
|
||||
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
||||
|
||||
@@ -4,13 +4,13 @@
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/controller/LinearQuadraticRegulator.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/estimator/KalmanFilter.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/system/LinearSystemLoop.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
|
||||
@@ -5,13 +5,13 @@
|
||||
#include <frc/DriverStation.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/controller/LinearQuadraticRegulator.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/estimator/KalmanFilter.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/system/LinearSystemLoop.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
|
||||
@@ -5,7 +5,6 @@
|
||||
#include <frc/DriverStation.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/StateSpaceUtil.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
@@ -13,6 +12,7 @@
|
||||
#include <frc/controller/LinearQuadraticRegulator.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/estimator/KalmanFilter.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc/system/LinearSystemLoop.h>
|
||||
#include <frc/system/plant/DCMotor.h>
|
||||
#include <frc/system/plant/LinearSystemId.h>
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/SwerveModuleState.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/angular_velocity.h>
|
||||
#include <units/time.h>
|
||||
#include <units/velocity.h>
|
||||
|
||||
@@ -6,7 +6,6 @@
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/geometry/Pose2d.h>
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
@@ -14,6 +13,7 @@
|
||||
#include <frc/kinematics/ChassisSpeeds.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/kinematics/SwerveDriveOdometry.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -51,7 +51,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
void ResetEncoders();
|
||||
|
||||
/**
|
||||
* Sets the drive SpeedControllers to a power from -1 to 1.
|
||||
* Sets the drive MotorControllers to a power from -1 to 1.
|
||||
*/
|
||||
void SetModuleStates(wpi::array<frc::SwerveModuleState, 4> desiredStates);
|
||||
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/Spark.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <frc/kinematics/SwerveModuleState.h>
|
||||
#include <frc/motorcontrol/Spark.h>
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
#include <wpi/math>
|
||||
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/SwerveModuleState.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <units/angular_velocity.h>
|
||||
#include <units/time.h>
|
||||
#include <units/velocity.h>
|
||||
|
||||
@@ -3,10 +3,10 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/GenericHID.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
#include <frc/AnalogInput.h>
|
||||
#include <frc/MedianFilter.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a sample program demonstrating how to use an ultrasonic sensor and
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
#include <frc/AnalogInput.h>
|
||||
#include <frc/MedianFilter.h>
|
||||
#include <frc/PWMSparkMax.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
|
||||
/**
|
||||
* This is a sample program demonstrating how to use an ultrasonic sensor and
|
||||
|
||||
Reference in New Issue
Block a user