mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
149 lines
3.8 KiB
C++
149 lines
3.8 KiB
C++
/*----------------------------------------------------------------------------*/
|
|
/* 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/SpeedControllerGroup.h>
|
|
#include <frc/drive/DifferentialDrive.h>
|
|
#include <frc/geometry/Pose2d.h>
|
|
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
|
#include <frc2/command/SubsystemBase.h>
|
|
#include <units/units.h>
|
|
|
|
#include "Constants.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 using arcade controls.
|
|
*
|
|
* @param fwd the commanded forward movement
|
|
* @param rot the commanded rotation
|
|
*/
|
|
void ArcadeDrive(double fwd, double rot);
|
|
|
|
/**
|
|
* Controls each side of the drive directly with a voltage.
|
|
*
|
|
* @param left the commanded left output
|
|
* @param right the commanded right output
|
|
*/
|
|
void TankDriveVolts(units::volt_t left, units::volt_t right);
|
|
|
|
/**
|
|
* Resets the drive encoders to currently read a position of 0.
|
|
*/
|
|
void ResetEncoders();
|
|
|
|
/**
|
|
* Gets the average distance of the TWO encoders.
|
|
*
|
|
* @return the average of the TWO encoder readings
|
|
*/
|
|
double GetAverageEncoderDistance();
|
|
|
|
/**
|
|
* Gets the left drive encoder.
|
|
*
|
|
* @return the left drive encoder
|
|
*/
|
|
frc::Encoder& GetLeftEncoder();
|
|
|
|
/**
|
|
* Gets the right drive encoder.
|
|
*
|
|
* @return the right drive encoder
|
|
*/
|
|
frc::Encoder& GetRightEncoder();
|
|
|
|
/**
|
|
* Sets the max output of the drive. Useful for scaling the drive to drive
|
|
* more slowly.
|
|
*
|
|
* @param maxOutput the maximum output to which the drive will be constrained
|
|
*/
|
|
void SetMaxOutput(double maxOutput);
|
|
|
|
/**
|
|
* Returns the heading of the robot.
|
|
*
|
|
* @return the robot's heading in degrees, from 180 to 180
|
|
*/
|
|
double GetHeading();
|
|
|
|
/**
|
|
* 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();
|
|
|
|
/**
|
|
* Returns the current wheel speeds of the robot.
|
|
*
|
|
* @return The current wheel speeds.
|
|
*/
|
|
frc::DifferentialDriveWheelSpeeds GetWheelSpeeds();
|
|
|
|
/**
|
|
* Resets the odometry to the specified pose.
|
|
*
|
|
* @param pose The pose to which to set the odometry.
|
|
*/
|
|
void ResetOdometry(frc::Pose2d pose);
|
|
|
|
private:
|
|
// Components (e.g. motor controllers and sensors) should generally be
|
|
// declared private and exposed only through public methods.
|
|
|
|
// The motor controllers
|
|
frc::PWMVictorSPX m_left1;
|
|
frc::PWMVictorSPX m_left2;
|
|
frc::PWMVictorSPX m_right1;
|
|
frc::PWMVictorSPX m_right2;
|
|
|
|
// The motors on the left side of the drive
|
|
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
|
|
|
|
// The motors on the right side of the drive
|
|
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
|
|
|
|
// The robot's drive
|
|
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
|
|
|
|
// The left-side drive encoder
|
|
frc::Encoder m_leftEncoder;
|
|
|
|
// The right-side drive encoder
|
|
frc::Encoder m_rightEncoder;
|
|
|
|
// The gyro sensor
|
|
frc::ADXRS450_Gyro m_gyro;
|
|
|
|
// Odometry class for tracking robot pose
|
|
frc::DifferentialDriveOdometry m_odometry;
|
|
};
|