Add holonomic follower examples (#2052)

This commit is contained in:
CTT
2019-11-21 19:52:56 -08:00
committed by Peter Johnson
parent 9a8067465c
commit a58dbec8aa
51 changed files with 4793 additions and 5 deletions

View File

@@ -0,0 +1,71 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
/**
* This function is called every robot packet, no matter the mode. Use
* this for items like diagnostics that you want to run during disabled,
* autonomous, teleoperated and test.
*
* <p> This runs after the mode specific periodic functions, but before
* LiveWindow and SmartDashboard integrated updating.
*/
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
/**
* This autonomous runs the autonomous command selected by your {@link
* RobotContainer} class.
*/
void Robot::AutonomousInit() {
m_autonomousCommand = m_container.GetAutonomousCommand();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Schedule();
}
}
void Robot::AutonomousPeriodic() {}
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
/**
* This function is called periodically during operator control.
*/
void Robot::TeleopPeriodic() {}
/**
* This function is called periodically during test mode.
*/
void Robot::TestPeriodic() {}
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,91 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "RobotContainer.h"
#include <frc/controller/PIDController.h>
#include <frc/geometry/Translation2d.h>
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc/trajectory/Trajectory.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/SwerveControllerCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/units.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
using namespace DriveConstants;
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Configure the button bindings
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.Drive(units::meters_per_second_t(
m_driverController.GetY(frc::GenericHID::kLeftHand)),
units::meters_per_second_t(
m_driverController.GetY(frc::GenericHID::kRightHand)),
units::radians_per_second_t(
m_driverController.GetX(frc::GenericHID::kLeftHand)),
false);
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Set up config for trajectory
frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
AutoConstants::kMaxAcceleration);
// Add kinematics to ensure max speed is actually obeyed
config.SetKinematics(m_drive.kDriveKinematics);
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
// Pass the config
config);
frc2::SwerveControllerCommand<4> swerveControllerCommand(
exampleTrajectory, [this]() { return m_drive.GetPose(); },
m_drive.kDriveKinematics,
frc2::PIDController(AutoConstants::kPXController, 0, 0),
frc2::PIDController(AutoConstants::kPYController, 0, 0),
frc::ProfiledPIDController<units::radians>(
AutoConstants::kPThetaController, 0, 0,
AutoConstants::kThetaControllerConstraints),
[this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },
{&m_drive});
// no auto
return new frc2::SequentialCommandGroup(
std::move(swerveControllerCommand), std::move(swerveControllerCommand),
frc2::InstantCommand(
[this]() {
m_drive.Drive(units::meters_per_second_t(0),
units::meters_per_second_t(0),
units::radians_per_second_t(0), false);
},
{}));
}

View File

@@ -0,0 +1,103 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/DriveSubsystem.h"
#include <frc/geometry/Rotation2d.h>
#include <units/units.h>
#include "Constants.h"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_frontLeft{kFrontLeftDriveMotorPort,
kFrontLeftTurningMotorPort,
kFrontLeftDriveEncoderPorts,
kFrontLeftTurningEncoderPorts,
kFrontLeftDriveEncoderReversed,
kFrontLeftTurningEncoderReversed},
m_rearLeft{
kRearLeftDriveMotorPort, kRearLeftTurningMotorPort,
kRearLeftDriveEncoderPorts, kRearLeftTurningEncoderPorts,
kRearLeftDriveEncoderReversed, kRearLeftTurningEncoderReversed},
m_frontRight{
kFrontRightDriveMotorPort, kFrontRightTurningMotorPort,
kFrontRightDriveEncoderPorts, kFrontRightTurningEncoderPorts,
kFrontRightDriveEncoderReversed, kFrontRightTurningEncoderReversed},
m_rearRight{
kRearRightDriveMotorPort, kRearRightTurningMotorPort,
kRearRightDriveEncoderPorts, kRearRightTurningEncoderPorts,
kRearRightDriveEncoderReversed, kRearRightTurningEncoderReversed},
m_odometry{kDriveKinematics,
frc::Rotation2d(units::degree_t(GetHeading())),
frc::Pose2d()} {}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())),
m_frontLeft.GetState(), m_rearLeft.GetState(),
m_frontRight.GetState(), m_rearRight.GetState());
}
void DriveSubsystem::Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed,
units::radians_per_second_t rot,
bool fieldRelative) {
auto states = kDriveKinematics.ToSwerveModuleStates(
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
xSpeed, ySpeed, rot,
frc::Rotation2d(units::degree_t(GetHeading())))
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
kDriveKinematics.NormalizeWheelSpeeds(&states, AutoConstants::kMaxSpeed);
auto [fl, fr, bl, br] = states;
m_frontLeft.SetDesiredState(fl);
m_frontRight.SetDesiredState(fr);
m_rearLeft.SetDesiredState(bl);
m_rearRight.SetDesiredState(br);
}
void DriveSubsystem::SetModuleStates(
std::array<frc::SwerveModuleState, 4> desiredStates) {
kDriveKinematics.NormalizeWheelSpeeds(&desiredStates,
AutoConstants::kMaxSpeed);
m_frontLeft.SetDesiredState(desiredStates[0]);
m_rearLeft.SetDesiredState(desiredStates[1]);
m_frontRight.SetDesiredState(desiredStates[2]);
m_rearRight.SetDesiredState(desiredStates[3]);
}
void DriveSubsystem::ResetEncoders() {
m_frontLeft.ResetEncoders();
m_rearLeft.ResetEncoders();
m_frontRight.ResetEncoders();
m_rearRight.ResetEncoders();
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
}
void DriveSubsystem::ZeroHeading() { m_gyro.Reset(); }
double DriveSubsystem::GetTurnRate() {
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
}
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
m_odometry.ResetPosition(pose,
frc::Rotation2d(units::degree_t(GetHeading())));
}

View File

@@ -0,0 +1,66 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include "subsystems/SwerveModule.h"
#include <frc/geometry/Rotation2d.h>
#include <wpi/math>
#include "Constants.h"
SwerveModule::SwerveModule(int driveMotorChannel, int turningMotorChannel,
const int driveEncoderPorts[],
const int turningEncoderPorts[],
bool driveEncoderReversed,
bool turningEncoderReversed)
: m_driveMotor(driveMotorChannel),
m_turningMotor(turningMotorChannel),
m_driveEncoder(driveEncoderPorts[0], driveEncoderPorts[1]),
m_turningEncoder(turningEncoderPorts[0], turningEncoderPorts[1]),
m_reverseDriveEncoder(driveEncoderReversed),
m_reverseTurningEncoder(turningEncoderReversed) {
// Set the distance per pulse for the drive encoder. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.
m_driveEncoder.SetDistancePerPulse(
ModuleConstants::kDriveEncoderDistancePerPulse);
// Set the distance (in this case, angle) per pulse for the turning encoder.
// This is the the angle through an entire rotation (2 * wpi::math::pi)
// divided by the encoder resolution.
m_turningEncoder.SetDistancePerPulse(
ModuleConstants::kTurningEncoderDistancePerPulse);
// Limit the PID Controller's input range between -pi and pi and set the input
// to be continuous.
m_turningPIDController.EnableContinuousInput(units::radian_t(-wpi::math::pi),
units::radian_t(wpi::math::pi));
}
frc::SwerveModuleState SwerveModule::GetState() {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
}
void SwerveModule::SetDesiredState(frc::SwerveModuleState& state) {
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
m_driveEncoder.GetRate(), state.speed.to<double>());
// Calculate the turning motor output from the turning PID controller.
auto turnOutput = m_turningPIDController.Calculate(
units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
// Set the motor outputs.
m_driveMotor.Set(driveOutput);
m_turningMotor.Set(turnOutput);
}
void SwerveModule::ResetEncoders() {
m_driveEncoder.Reset();
m_turningEncoder.Reset();
}

View File

@@ -0,0 +1,113 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include <frc/geometry/Translation2d.h>
#include <frc/kinematics/SwerveDriveKinematics.h>
#include <frc/trajectory/TrapezoidProfile.h>
#include <units/units.h>
#include <wpi/math>
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
constexpr int kFrontLeftDriveMotorPort = 0;
constexpr int kRearLeftDriveMotorPort = 2;
constexpr int kFrontRightDriveMotorPort = 4;
constexpr int kRearRightDriveMotorPort = 6;
constexpr int kFrontLeftTurningMotorPort = 1;
constexpr int kRearLeftTurningMotorPort = 3;
constexpr int kFrontRightTurningMotorPort = 5;
constexpr int kRearRightTurningMotorPort = 7;
constexpr int kFrontLeftTurningEncoderPorts[2]{0, 1};
constexpr int kRearLeftTurningEncoderPorts[2]{2, 3};
constexpr int kFrontRightTurningEncoderPorts[2]{4, 5};
constexpr int kRearRightTurningEncoderPorts[2]{5, 6};
constexpr bool kFrontLeftTurningEncoderReversed = false;
constexpr bool kRearLeftTurningEncoderReversed = true;
constexpr bool kFrontRightTurningEncoderReversed = false;
constexpr bool kRearRightTurningEncoderReversed = true;
constexpr int kFrontLeftDriveEncoderPorts[2]{0, 1};
constexpr int kRearLeftDriveEncoderPorts[2]{2, 3};
constexpr int kFrontRightDriveEncoderPorts[2]{4, 5};
constexpr int kRearRightDriveEncoderPorts[2]{5, 6};
constexpr bool kFrontLeftDriveEncoderReversed = false;
constexpr bool kRearLeftDriveEncoderReversed = true;
constexpr bool kFrontRightDriveEncoderReversed = false;
constexpr bool kRearRightDriveEncoderReversed = true;
constexpr bool kGyroReversed = false;
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
// These characterization values MUST be determined either experimentally or
// theoretically for *your* robot's drive. The RobotPy Characterization
// Toolsuite provides a convenient tool for obtaining these values for your
// robot.
constexpr auto ks = 1_V;
constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
// Example value only - as above, this must be tuned for your drive!
constexpr double kPFrontLeftVel = 0.5;
constexpr double kPRearLeftVel = 0.5;
constexpr double kPFrontRightVel = 0.5;
constexpr double kPRearRightVel = 0.5;
} // namespace DriveConstants
namespace ModuleConstants {
constexpr int kEncoderCPR = 1024;
constexpr double kWheelDiameterMeters = .15;
constexpr double kDriveEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterMeters * wpi::math::pi) / static_cast<double>(kEncoderCPR);
constexpr double kTurningEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(wpi::math::pi * 2) / static_cast<double>(kEncoderCPR);
constexpr double kPModuleTurningController = 1;
constexpr double kPModuleDriveController = 1;
} // namespace ModuleConstants
namespace AutoConstants {
using radians_per_second_squared_t =
units::compound_unit<units::radians,
units::inverse<units::squared<units::second>>>;
constexpr auto kMaxSpeed = units::meters_per_second_t(3);
constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3.142);
constexpr auto kMaxAngularAcceleration =
units::unit_t<radians_per_second_squared_t>(3.142);
constexpr double kPXController = 0.5;
constexpr double kPYController = 0.5;
constexpr double kPThetaController = 0.5;
//
constexpr frc::TrapezoidProfile<units::radians>::Constraints
kThetaControllerConstraints{kMaxAngularSpeed, kMaxAngularAcceleration};
} // namespace AutoConstants
namespace OIConstants {
constexpr int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,33 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/TimedRobot.h>
#include <frc2/command/Command.h>
#include "RobotContainer.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc2::Command* m_autonomousCommand = nullptr;
RobotContainer m_container;
};

View File

@@ -0,0 +1,49 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/XboxController.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/PIDCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
* actually be handled in the {@link Robot} periodic methods (other than the
* scheduler calls). Instead, the structure of the robot (including subsystems,
* commands, and button mappings) should be declared here.
*/
class RobotContainer {
public:
RobotContainer();
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,120 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/ADXRS450_Gyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/drive/MecanumDrive.h>
#include <frc/geometry/Pose2d.h>
#include <frc/geometry/Rotation2d.h>
#include <frc/interfaces/Gyro.h>
#include <frc/kinematics/ChassisSpeeds.h>
#include <frc/kinematics/SwerveDriveKinematics.h>
#include <frc/kinematics/SwerveDriveOdometry.h>
#include <frc2/command/SubsystemBase.h>
#include "Constants.h"
#include "SwerveModule.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Drives the robot at given x, y and theta speeds. Speeds range from [-1, 1]
* and the linear speeds have no effect on the angular speed.
*
* @param xSpeed Speed of the robot in the x direction
* (forward/backwards).
* @param ySpeed Speed of the robot in the y direction (sideways).
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to
* the field.
*/
void Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
bool feildRelative);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Sets the drive SpeedControllers to a power from -1 to 1.
*/
void SetModuleStates(std::array<frc::SwerveModuleState, 4> desiredStates);
/**
* Returns the heading of the robot.
*
* @return the robot's heading in degrees, from 180 to 180
*/
double GetHeading();
/**
* Zeroes the heading of the robot.
*/
void ZeroHeading();
/**
* Returns the turn rate of the robot.
*
* @return The turn rate of the robot, in degrees per second
*/
double GetTurnRate();
/**
* Returns the currently-estimated pose of the robot.
*
* @return The pose.
*/
frc::Pose2d GetPose();
/**
* Resets the odometry to the specified pose.
*
* @param pose The pose to which to set the odometry.
*/
void ResetOdometry(frc::Pose2d pose);
units::meter_t kTrackWidth =
.5_m; // Distance between centers of right and left wheels on robot
units::meter_t kWheelBase =
.7_m; // Distance between centers of front and back wheels on robot
frc::SwerveDriveKinematics<4> kDriveKinematics{
frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
SwerveModule m_frontLeft;
SwerveModule m_rearLeft;
SwerveModule m_frontRight;
SwerveModule m_rearRight;
// The gyro sensor
frc::ADXRS450_Gyro m_gyro;
// Odometry class for tracking robot pose
// 4 defines the number of modules
frc::SwerveDriveOdometry<4> m_odometry;
};

View File

@@ -0,0 +1,65 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#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/trajectory/TrapezoidProfile.h>
#include <wpi/math>
#include "Constants.h"
class SwerveModule {
using radians_per_second_squared_t =
units::compound_unit<units::radians,
units::inverse<units::squared<units::second>>>;
public:
SwerveModule(int driveMotorChannel, int turningMotorChannel,
const int driveEncoderPorts[2], const int turningEncoderPorts[2],
bool driveEncoderReversed, bool turningEncoderReversed);
frc::SwerveModuleState GetState();
void SetDesiredState(frc::SwerveModuleState& state);
void ResetEncoders();
private:
// We have to use meters here instead of radians due to the fact that
// ProfiledPIDController's constraints only take in meters per second and
// meters per second squared.
static constexpr units::radians_per_second_t kModuleMaxAngularVelocity =
units::radians_per_second_t(wpi::math::pi); // radians per second
static constexpr units::unit_t<radians_per_second_squared_t>
kModuleMaxAngularAcceleration =
units::unit_t<radians_per_second_squared_t>(
wpi::math::pi * 2.0); // radians per second squared
frc::Spark m_driveMotor;
frc::Spark m_turningMotor;
frc::Encoder m_driveEncoder;
frc::Encoder m_turningEncoder;
bool m_reverseDriveEncoder;
bool m_reverseTurningEncoder;
frc2::PIDController m_drivePIDController{
ModuleConstants::kPModuleDriveController, 0, 0};
frc::ProfiledPIDController<units::radians> m_turningPIDController{
ModuleConstants::kPModuleTurningController,
0.0,
0.0,
{kModuleMaxAngularVelocity, kModuleMaxAngularAcceleration}};
};