mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib] Add Gyro::GetRotation2d() (#2555)
This commit is contained in:
@@ -25,6 +25,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(GetAngle(), units::meter_t(m_leftEncoder.GetDistance()),
|
||||
m_odometry.Update(m_gyro.GetRotation2d(),
|
||||
units::meter_t(m_leftEncoder.GetDistance()),
|
||||
units::meter_t(m_rightEncoder.GetDistance()));
|
||||
}
|
||||
|
||||
@@ -37,14 +37,6 @@ class Drivetrain {
|
||||
m_rightEncoder.Reset();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the robot angle as a Rotation2d.
|
||||
*/
|
||||
frc::Rotation2d GetAngle() const {
|
||||
// Negating the angle because WPILib Gyros are CW positive.
|
||||
return frc::Rotation2d(units::degree_t(-m_gyro.GetAngle()));
|
||||
}
|
||||
|
||||
static constexpr units::meters_per_second_t kMaxSpeed =
|
||||
3.0_mps; // 3 meters per second
|
||||
static constexpr units::radians_per_second_t kMaxAngularSpeed{
|
||||
@@ -77,7 +69,7 @@ class Drivetrain {
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{GetAngle()};
|
||||
frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
// robot!
|
||||
|
||||
@@ -48,12 +48,12 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot, bool fieldRelative) {
|
||||
auto wheelSpeeds = m_kinematics.ToWheelSpeeds(
|
||||
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, GetAngle())
|
||||
xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
|
||||
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
|
||||
wheelSpeeds.Normalize(kMaxSpeed);
|
||||
SetSpeeds(wheelSpeeds);
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(GetAngle(), GetCurrentState());
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), GetCurrentState());
|
||||
}
|
||||
|
||||
@@ -25,14 +25,6 @@ class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
|
||||
/**
|
||||
* Get the robot angle as a Rotation2d
|
||||
*/
|
||||
frc::Rotation2d GetAngle() const {
|
||||
// Negating the angle because WPILib Gyros are CW positive.
|
||||
return frc::Rotation2d(units::degree_t(-m_gyro.GetAngle()));
|
||||
}
|
||||
|
||||
frc::MecanumDriveWheelSpeeds GetCurrentState() const;
|
||||
void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
@@ -72,7 +64,7 @@ class Drivetrain {
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
m_backRightLocation};
|
||||
|
||||
frc::MecanumDriveOdometry m_odometry{m_kinematics, GetAngle()};
|
||||
frc::MecanumDriveOdometry m_odometry{m_kinematics, m_gyro.GetRotation2d()};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
// robot!
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -7,7 +7,6 @@
|
||||
|
||||
#include "subsystems/DriveSubsystem.h"
|
||||
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <units/units.h>
|
||||
|
||||
#include "Constants.h"
|
||||
@@ -30,9 +29,7 @@ DriveSubsystem::DriveSubsystem()
|
||||
m_rearRightEncoder{kRearRightEncoderPorts[0], kRearRightEncoderPorts[1],
|
||||
kRearRightEncoderReversed},
|
||||
|
||||
m_odometry{kDriveKinematics,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
frc::Pose2d()} {
|
||||
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d()} {
|
||||
// Set the distance per pulse for the encoders
|
||||
m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
@@ -43,7 +40,7 @@ DriveSubsystem::DriveSubsystem()
|
||||
void DriveSubsystem::Periodic() {
|
||||
// Implementation of subsystem periodic method goes here.
|
||||
m_odometry.Update(
|
||||
frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
m_gyro.GetRotation2d(),
|
||||
frc::MecanumDriveWheelSpeeds{
|
||||
units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
|
||||
@@ -103,19 +100,16 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
m_drive.SetMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
double DriveSubsystem::GetHeading() {
|
||||
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
|
||||
units::degree_t DriveSubsystem::GetHeading() const {
|
||||
return m_gyro.GetRotation2d().Degrees();
|
||||
}
|
||||
|
||||
void DriveSubsystem::ZeroHeading() { m_gyro.Reset(); }
|
||||
|
||||
double DriveSubsystem::GetTurnRate() {
|
||||
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
|
||||
}
|
||||
double DriveSubsystem::GetTurnRate() { return -m_gyro.GetRate(); }
|
||||
|
||||
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
|
||||
|
||||
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
|
||||
m_odometry.ResetPosition(pose,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())));
|
||||
m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
|
||||
}
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -50,8 +50,6 @@ constexpr double kEncoderDistancePerPulse =
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterMeters * wpi::math::pi) / static_cast<double>(kEncoderCPR);
|
||||
|
||||
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
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -103,9 +103,9 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
/**
|
||||
* Returns the heading of the robot.
|
||||
*
|
||||
* @return the robot's heading in degrees, from 180 to 180
|
||||
* @return the robot's heading in degrees, from -180 to 180
|
||||
*/
|
||||
double GetHeading();
|
||||
units::degree_t GetHeading() const;
|
||||
|
||||
/**
|
||||
* Zeroes the heading of the robot.
|
||||
|
||||
@@ -19,7 +19,7 @@ DriveSubsystem::DriveSubsystem()
|
||||
m_right2{kRightMotor2Port},
|
||||
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
|
||||
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]},
|
||||
m_odometry{frc::Rotation2d(units::degree_t(GetHeading()))} {
|
||||
m_odometry{m_gyro.GetRotation2d()} {
|
||||
// Set the distance per pulse for the encoders
|
||||
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
@@ -29,7 +29,7 @@ DriveSubsystem::DriveSubsystem()
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
// Implementation of subsystem periodic method goes here.
|
||||
m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
m_odometry.Update(m_gyro.GetRotation2d(),
|
||||
units::meter_t(m_leftEncoder.GetDistance()),
|
||||
units::meter_t(m_rightEncoder.GetDistance()));
|
||||
}
|
||||
@@ -61,13 +61,11 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
m_drive.SetMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
double DriveSubsystem::GetHeading() {
|
||||
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
|
||||
units::degree_t DriveSubsystem::GetHeading() const {
|
||||
return m_gyro.GetRotation2d().Degrees();
|
||||
}
|
||||
|
||||
double DriveSubsystem::GetTurnRate() {
|
||||
return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0);
|
||||
}
|
||||
double DriveSubsystem::GetTurnRate() { return -m_gyro.GetRate(); }
|
||||
|
||||
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
|
||||
|
||||
@@ -78,6 +76,5 @@ frc::DifferentialDriveWheelSpeeds DriveSubsystem::GetWheelSpeeds() {
|
||||
|
||||
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
|
||||
ResetEncoders();
|
||||
m_odometry.ResetPosition(pose,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())));
|
||||
m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
|
||||
}
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -41,8 +41,6 @@ constexpr double kEncoderDistancePerPulse =
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterInches * wpi::math::pi) / static_cast<double>(kEncoderCPR);
|
||||
|
||||
constexpr bool kGyroReversed = true;
|
||||
|
||||
// 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 Robot Characterization
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -83,9 +83,9 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
/**
|
||||
* Returns the heading of the robot.
|
||||
*
|
||||
* @return the robot's heading in degrees, from 180 to 180
|
||||
* @return the robot's heading in degrees, from -180 to 180
|
||||
*/
|
||||
double GetHeading();
|
||||
units::degree_t GetHeading() const;
|
||||
|
||||
/**
|
||||
* Returns the turn rate of the robot.
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -12,7 +12,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot, bool fieldRelative) {
|
||||
auto states = m_kinematics.ToSwerveModuleStates(
|
||||
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, GetAngle())
|
||||
xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
|
||||
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
|
||||
|
||||
m_kinematics.NormalizeWheelSpeeds(&states, kMaxSpeed);
|
||||
@@ -26,6 +26,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(GetAngle(), m_frontLeft.GetState(), m_frontRight.GetState(),
|
||||
m_backLeft.GetState(), m_backRight.GetState());
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
|
||||
m_frontRight.GetState(), m_backLeft.GetState(),
|
||||
m_backRight.GetState());
|
||||
}
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -22,14 +22,6 @@ class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
|
||||
/**
|
||||
* Get the robot angle as a Rotation2d.
|
||||
*/
|
||||
frc::Rotation2d GetAngle() const {
|
||||
// Negating the angle because WPILib Gyros are CW positive.
|
||||
return frc::Rotation2d(units::degree_t(-m_gyro.GetAngle()));
|
||||
}
|
||||
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
|
||||
bool fieldRelative);
|
||||
@@ -57,5 +49,5 @@ class Drivetrain {
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
m_backRightLocation};
|
||||
|
||||
frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, GetAngle()};
|
||||
frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, m_gyro.GetRotation2d()};
|
||||
};
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -37,15 +37,13 @@ DriveSubsystem::DriveSubsystem()
|
||||
kRearRightDriveEncoderPorts, kRearRightTurningEncoderPorts,
|
||||
kRearRightDriveEncoderReversed, kRearRightTurningEncoderReversed},
|
||||
|
||||
m_odometry{kDriveKinematics,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
frc::Pose2d()} {}
|
||||
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), 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());
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
|
||||
m_rearLeft.GetState(), m_frontRight.GetState(),
|
||||
m_rearRight.GetState());
|
||||
}
|
||||
|
||||
void DriveSubsystem::Drive(units::meters_per_second_t xSpeed,
|
||||
@@ -54,8 +52,7 @@ void DriveSubsystem::Drive(units::meters_per_second_t xSpeed,
|
||||
bool fieldRelative) {
|
||||
auto states = kDriveKinematics.ToSwerveModuleStates(
|
||||
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())))
|
||||
xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
|
||||
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
|
||||
|
||||
kDriveKinematics.NormalizeWheelSpeeds(&states, AutoConstants::kMaxSpeed);
|
||||
@@ -85,15 +82,13 @@ void DriveSubsystem::ResetEncoders() {
|
||||
m_rearRight.ResetEncoders();
|
||||
}
|
||||
|
||||
double DriveSubsystem::GetHeading() {
|
||||
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
|
||||
units::degree_t DriveSubsystem::GetHeading() const {
|
||||
return m_gyro.GetRotation2d().Degrees();
|
||||
}
|
||||
|
||||
void DriveSubsystem::ZeroHeading() { m_gyro.Reset(); }
|
||||
|
||||
double DriveSubsystem::GetTurnRate() {
|
||||
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
|
||||
}
|
||||
double DriveSubsystem::GetTurnRate() { return -m_gyro.GetRate(); }
|
||||
|
||||
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -53,8 +53,6 @@ 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
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 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. */
|
||||
@@ -63,7 +63,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*
|
||||
* @return the robot's heading in degrees, from 180 to 180
|
||||
*/
|
||||
double GetHeading();
|
||||
units::degree_t GetHeading() const;
|
||||
|
||||
/**
|
||||
* Zeroes the heading of the robot.
|
||||
|
||||
Reference in New Issue
Block a user