mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[romi] Update Romi for parity with XRP (#7389)
This commit is contained in:
committed by
GitHub
parent
6eb652e10e
commit
1e545c38a8
@@ -63,27 +63,27 @@ units::meter_t Drivetrain::GetAverageDistance() {
|
||||
return (GetLeftDistance() + GetRightDistance()) / 2.0;
|
||||
}
|
||||
|
||||
double Drivetrain::GetAccelX() {
|
||||
return m_accelerometer.GetX();
|
||||
units::meters_per_second_squared_t Drivetrain::GetAccelX() {
|
||||
return units::meters_per_second_squared_t{m_accelerometer.GetX()};
|
||||
}
|
||||
|
||||
double Drivetrain::GetAccelY() {
|
||||
return m_accelerometer.GetY();
|
||||
units::meters_per_second_squared_t Drivetrain::GetAccelY() {
|
||||
return units::meters_per_second_squared_t{m_accelerometer.GetY()};
|
||||
}
|
||||
|
||||
double Drivetrain::GetAccelZ() {
|
||||
return m_accelerometer.GetZ();
|
||||
units::meters_per_second_squared_t Drivetrain::GetAccelZ() {
|
||||
return units::meters_per_second_squared_t{m_accelerometer.GetZ()};
|
||||
}
|
||||
|
||||
double Drivetrain::GetGyroAngleX() {
|
||||
units::radian_t Drivetrain::GetGyroAngleX() {
|
||||
return m_gyro.GetAngleX();
|
||||
}
|
||||
|
||||
double Drivetrain::GetGyroAngleY() {
|
||||
units::radian_t Drivetrain::GetGyroAngleY() {
|
||||
return m_gyro.GetAngleY();
|
||||
}
|
||||
|
||||
double Drivetrain::GetGyroAngleZ() {
|
||||
units::radian_t Drivetrain::GetGyroAngleZ() {
|
||||
return m_gyro.GetAngleZ();
|
||||
}
|
||||
|
||||
|
||||
@@ -15,6 +15,12 @@ class AutonomousDistance
|
||||
: public frc2::CommandHelper<frc2::SequentialCommandGroup,
|
||||
AutonomousDistance> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new Autonomous Drive based on distance. This will drive out for a
|
||||
* specified distance, turn around and drive back.
|
||||
*
|
||||
* @param drive The drivetrain subsystem on which this command will run
|
||||
*/
|
||||
explicit AutonomousDistance(Drivetrain* drive) {
|
||||
AddCommands(
|
||||
DriveDistance(-0.5, 10_in, drive), TurnDegrees(-0.5, 180_deg, drive),
|
||||
|
||||
@@ -14,6 +14,14 @@
|
||||
class AutonomousTime
|
||||
: public frc2::CommandHelper<frc2::SequentialCommandGroup, AutonomousTime> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new Autonomous Drive based on time. This will drive out for a
|
||||
* period of time, turn around for time (equivalent to time to turn around)
|
||||
* and drive forward again. This should mimic driving out, turning around and
|
||||
* driving back.
|
||||
*
|
||||
* @param drive The drive subsystem on which this command will run
|
||||
*/
|
||||
explicit AutonomousTime(Drivetrain* drive) {
|
||||
AddCommands(DriveTime(-0.6, 2_s, drive), TurnTime(-0.5, 1.3_s, drive),
|
||||
DriveTime(-0.6, 2_s, drive), TurnTime(0.5, 1.3_s, drive));
|
||||
|
||||
@@ -12,6 +12,14 @@
|
||||
|
||||
class DriveDistance : public frc2::CommandHelper<frc2::Command, DriveDistance> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new DriveDistance. This command will drive your your robot for a
|
||||
* desired distance at a desired speed.
|
||||
*
|
||||
* @param speed The speed at which the robot will drive
|
||||
* @param distance The distance the robot will drive
|
||||
* @param drive The drivetrain subsystem on which this command will run
|
||||
*/
|
||||
DriveDistance(double speed, units::meter_t distance, Drivetrain* drive)
|
||||
: m_speed(speed), m_distance(distance), m_drive(drive) {
|
||||
AddRequirements(m_drive);
|
||||
|
||||
@@ -13,6 +13,14 @@
|
||||
|
||||
class DriveTime : public frc2::CommandHelper<frc2::Command, DriveTime> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new DriveTime. This command will drive your robot for a desired
|
||||
* speed and time.
|
||||
*
|
||||
* @param speed The speed which the robot will drive. Negative is in reverse.
|
||||
* @param time How much time to drive
|
||||
* @param drive The drivetrain subsystem on which this command will run
|
||||
*/
|
||||
DriveTime(double speed, units::second_t time, Drivetrain* drive)
|
||||
: m_speed(speed), m_duration(time), m_drive(drive) {
|
||||
AddRequirements(m_drive);
|
||||
|
||||
@@ -14,6 +14,14 @@
|
||||
class TeleopArcadeDrive
|
||||
: public frc2::CommandHelper<frc2::Command, TeleopArcadeDrive> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new ArcadeDrive. This command will drive your robot according to
|
||||
* the speed suppliers. This command does not terminate.
|
||||
*
|
||||
* @param drivetrain The drivetrain subsystem on which this command will run
|
||||
* @param xaxisSpeedSupplier Supplier of forward/backward speed
|
||||
* @param zaxisRotateSupplier Supplier of rotational speed
|
||||
*/
|
||||
TeleopArcadeDrive(Drivetrain* subsystem,
|
||||
std::function<double()> xaxisSpeedSupplier,
|
||||
std::function<double()> zaxisRotateSupplier);
|
||||
|
||||
@@ -13,6 +13,14 @@
|
||||
|
||||
class TurnDegrees : public frc2::CommandHelper<frc2::Command, TurnDegrees> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new TurnDegrees. This command will turn your robot for a desired
|
||||
* rotation (in degrees) and rotational speed.
|
||||
*
|
||||
* @param speed The speed which the robot will drive. Negative is in reverse.
|
||||
* @param degrees Degrees to turn. Leverages encoders to compare distance.
|
||||
* @param drive The drive subsystem on which this command will run
|
||||
*/
|
||||
TurnDegrees(double speed, units::degree_t angle, Drivetrain* drive)
|
||||
: m_speed(speed), m_angle(angle), m_drive(drive) {
|
||||
AddRequirements(m_drive);
|
||||
|
||||
@@ -13,6 +13,13 @@
|
||||
|
||||
class TurnTime : public frc2::CommandHelper<frc2::Command, TurnTime> {
|
||||
public:
|
||||
/**
|
||||
* Creates a new TurnTime.
|
||||
*
|
||||
* @param speed The speed which the robot will turn. Negative is in reverse.
|
||||
* @param time How much time to turn
|
||||
* @param drive The drive subsystem on which this command will run
|
||||
*/
|
||||
TurnTime(double speed, units::second_t time, Drivetrain* drive)
|
||||
: m_speed(speed), m_duration(time), m_drive(drive) {
|
||||
AddRequirements(m_drive);
|
||||
|
||||
@@ -10,6 +10,8 @@
|
||||
#include <frc/motorcontrol/Spark.h>
|
||||
#include <frc/romi/RomiGyro.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/acceleration.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/length.h>
|
||||
|
||||
class Drivetrain : public frc2::SubsystemBase {
|
||||
@@ -73,34 +75,46 @@ class Drivetrain : public frc2::SubsystemBase {
|
||||
units::meter_t GetAverageDistance();
|
||||
|
||||
/**
|
||||
* Returns the acceleration along the X-axis, in Gs.
|
||||
* The acceleration in the X-axis.
|
||||
*
|
||||
* @return The acceleration of the Romi along the X-axis.
|
||||
*/
|
||||
double GetAccelX();
|
||||
units::meters_per_second_squared_t GetAccelX();
|
||||
|
||||
/**
|
||||
* Returns the acceleration along the Y-axis, in Gs.
|
||||
* The acceleration in the Y-axis.
|
||||
*
|
||||
* @return The acceleration of the Romi along the Y-axis.
|
||||
*/
|
||||
double GetAccelY();
|
||||
units::meters_per_second_squared_t GetAccelY();
|
||||
|
||||
/**
|
||||
* Returns the acceleration along the Z-axis, in Gs.
|
||||
* The acceleration in the Z-axis.
|
||||
*
|
||||
* @return The acceleration of the Romi along the Z-axis.
|
||||
*/
|
||||
double GetAccelZ();
|
||||
units::meters_per_second_squared_t GetAccelZ();
|
||||
|
||||
/**
|
||||
* Returns the current angle of the Romi around the X-axis, in degrees.
|
||||
* Current angle of the Romi around the X-axis.
|
||||
*
|
||||
* @return The current angle of the Romi.
|
||||
*/
|
||||
double GetGyroAngleX();
|
||||
units::radian_t GetGyroAngleX();
|
||||
|
||||
/**
|
||||
* Returns the current angle of the Romi around the Y-axis, in degrees.
|
||||
* Current angle of the Romi around the Y-axis.
|
||||
*
|
||||
* @return The current angle of the Romi.
|
||||
*/
|
||||
double GetGyroAngleY();
|
||||
units::radian_t GetGyroAngleY();
|
||||
|
||||
/**
|
||||
* Returns the current angle of the Romi around the Z-axis, in degrees.
|
||||
* Current angle of the Romi around the Z-axis.
|
||||
*
|
||||
* @return The current angle of the Romi.
|
||||
*/
|
||||
double GetGyroAngleZ();
|
||||
units::radian_t GetGyroAngleZ();
|
||||
|
||||
/**
|
||||
* Reset the gyro.
|
||||
|
||||
Reference in New Issue
Block a user