mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Add holonomic follower examples (#2052)
This commit is contained in:
@@ -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;
|
||||
};
|
||||
@@ -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}};
|
||||
};
|
||||
Reference in New Issue
Block a user