mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib, examples] Remove AnalogGyro (#8205)
This commit is contained in:
@@ -22,7 +22,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(m_gyro.GetRotation2d(),
|
||||
m_odometry.Update(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()});
|
||||
}
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
@@ -32,7 +32,7 @@ class Drivetrain {
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightLeader.SetInverted(true);
|
||||
|
||||
m_gyro.Reset();
|
||||
m_imu.ResetYaw();
|
||||
// Set the distance per pulse for the drive encoders. We can simply use the
|
||||
// distance traveled for one rotation of the wheel divided by the encoder
|
||||
// resolution.
|
||||
@@ -71,11 +71,11 @@ class Drivetrain {
|
||||
frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
|
||||
frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{
|
||||
m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
|
||||
m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()}};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
|
||||
@@ -15,7 +15,7 @@ Drivetrain::Drivetrain() {
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
m_rightLeader.SetInverted(true);
|
||||
|
||||
m_gyro.Reset();
|
||||
m_imu.ResetYaw();
|
||||
|
||||
// Set the distance per pulse for the drive encoders. We can simply use the
|
||||
// distance traveled for one rotation of the wheel divided by the encoder
|
||||
@@ -84,7 +84,7 @@ frc::Pose3d Drivetrain::ObjectToRobotPose(
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_poseEstimator.Update(m_gyro.GetRotation2d(),
|
||||
m_poseEstimator.Update(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()});
|
||||
|
||||
@@ -125,6 +125,7 @@ void Drivetrain::SimulationPeriodic() {
|
||||
m_drivetrainSimulator.GetRightPosition().value());
|
||||
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetRightVelocity().value());
|
||||
// m_gyroSim.SetAngle(-m_drivetrainSimulator.GetHeading().Degrees().value());
|
||||
// // TODO(Ryan): fixup when sim implemented
|
||||
}
|
||||
|
||||
void Drivetrain::Periodic() {
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/ComputerVisionUtil.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/RobotController.h>
|
||||
#include <frc/Timer.h>
|
||||
#include <frc/apriltag/AprilTagFieldLayout.h>
|
||||
@@ -144,7 +144,7 @@ class Drivetrain {
|
||||
frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
|
||||
frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
|
||||
|
||||
@@ -152,7 +152,7 @@ class Drivetrain {
|
||||
// robot!
|
||||
frc::DifferentialDrivePoseEstimator m_poseEstimator{
|
||||
m_kinematics,
|
||||
m_gyro.GetRotation2d(),
|
||||
m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()},
|
||||
frc::Pose2d{},
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
@@ -18,7 +18,6 @@
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
Robot() {
|
||||
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
@@ -34,7 +33,8 @@ class Robot : public frc::TimedRobot {
|
||||
* angle.
|
||||
*/
|
||||
void TeleopPeriodic() override {
|
||||
double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
|
||||
double turningValue =
|
||||
(kAngleSetpoint - m_imu.GetRotation2d().Degrees().value()) * kP;
|
||||
m_drive.ArcadeDrive(-m_joystick.GetY(), -turningValue);
|
||||
}
|
||||
|
||||
@@ -42,13 +42,10 @@ class Robot : public frc::TimedRobot {
|
||||
static constexpr double kAngleSetpoint = 0.0;
|
||||
static constexpr double kP = 0.005; // Proportional turning constant
|
||||
|
||||
// Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
|
||||
// set to correspond to one full revolution.
|
||||
static constexpr double kVoltsPerDegreePerSecond = 0.0128;
|
||||
|
||||
static constexpr int kLeftMotorPort = 0;
|
||||
static constexpr int kRightMotorPort = 1;
|
||||
static constexpr int kGyroPort = 0;
|
||||
static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation =
|
||||
frc::OnboardIMU::kFlat;
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
frc::PWMSparkMax m_left{kLeftMotorPort};
|
||||
@@ -56,7 +53,7 @@ class Robot : public frc::TimedRobot {
|
||||
frc::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); },
|
||||
[&](double output) { m_right.Set(output); }};
|
||||
|
||||
frc::AnalogGyro m_gyro{kGyroPort};
|
||||
frc::OnboardIMU m_imu{kIMUMountOrientation};
|
||||
frc::Joystick m_joystick{kJoystickPort};
|
||||
};
|
||||
|
||||
|
||||
@@ -2,8 +2,8 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Joystick.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
@@ -25,8 +25,6 @@ class Robot : public frc::TimedRobot {
|
||||
// match your robot.
|
||||
m_frontRight.SetInverted(true);
|
||||
m_rearRight.SetInverted(true);
|
||||
|
||||
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -34,19 +32,16 @@ class Robot : public frc::TimedRobot {
|
||||
*/
|
||||
void TeleopPeriodic() override {
|
||||
m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
|
||||
-m_joystick.GetZ(), m_gyro.GetRotation2d());
|
||||
-m_joystick.GetZ(), m_imu.GetRotation2d());
|
||||
}
|
||||
|
||||
private:
|
||||
// Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
|
||||
// set to correspond to one full revolution.
|
||||
static constexpr double kVoltsPerDegreePerSecond = 0.0128;
|
||||
|
||||
static constexpr int kFrontLeftMotorPort = 0;
|
||||
static constexpr int kRearLeftMotorPort = 1;
|
||||
static constexpr int kFrontRightMotorPort = 2;
|
||||
static constexpr int kRearRightMotorPort = 3;
|
||||
static constexpr int kGyroPort = 0;
|
||||
static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation =
|
||||
frc::OnboardIMU::kFlat;
|
||||
static constexpr int kJoystickPort = 0;
|
||||
|
||||
frc::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
|
||||
@@ -59,7 +54,7 @@ class Robot : public frc::TimedRobot {
|
||||
[&](double output) { m_frontRight.Set(output); },
|
||||
[&](double output) { m_rearRight.Set(output); }};
|
||||
|
||||
frc::AnalogGyro m_gyro{kGyroPort};
|
||||
frc::OnboardIMU m_imu{kIMUMountOrientation};
|
||||
frc::Joystick m_joystick{kJoystickPort};
|
||||
};
|
||||
|
||||
|
||||
@@ -55,12 +55,12 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::second_t period) {
|
||||
frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_gyro.GetRotation2d());
|
||||
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d());
|
||||
}
|
||||
SetSpeeds(m_kinematics.ToWheelSpeeds(chassisSpeeds.Discretize(period))
|
||||
.Desaturate(kMaxSpeed));
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), GetCurrentWheelDistances());
|
||||
m_odometry.Update(m_imu.GetRotation2d(), GetCurrentWheelDistances());
|
||||
}
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
@@ -22,7 +22,7 @@
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
m_imu.ResetYaw();
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
@@ -64,13 +64,13 @@ class Drivetrain {
|
||||
frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
|
||||
frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::MecanumDriveKinematics m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
m_backRightLocation};
|
||||
|
||||
frc::MecanumDriveOdometry m_odometry{m_kinematics, m_gyro.GetRotation2d(),
|
||||
frc::MecanumDriveOdometry m_odometry{m_kinematics, m_imu.GetRotation2d(),
|
||||
GetCurrentWheelDistances()};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
|
||||
@@ -58,7 +58,9 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_poseEstimator.Update(m_gyro.GetRotation2d(), GetCurrentDistances());
|
||||
m_poseEstimator.Update(
|
||||
m_imu.GetRotation2d(),
|
||||
GetCurrentDistances()); // TODO(Ryan): fixup when sim implemented
|
||||
|
||||
// Also apply vision measurements. We use 0.3 seconds in the past as an
|
||||
// example -- on a real robot, this must be calculated based either on latency
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/estimator/MecanumDrivePoseEstimator.h>
|
||||
@@ -23,7 +23,7 @@
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
m_imu.ResetYaw();
|
||||
// We need to invert one side of the drivetrain so that positive voltages
|
||||
// result in both sides moving forward. Depending on how your robot's
|
||||
// gearbox is constructed, you might have to invert the left side instead.
|
||||
@@ -64,7 +64,7 @@ class Drivetrain {
|
||||
frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
|
||||
frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::MecanumDriveKinematics m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
@@ -77,6 +77,6 @@ class Drivetrain {
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
// robot!
|
||||
frc::MecanumDrivePoseEstimator m_poseEstimator{
|
||||
m_kinematics, m_gyro.GetRotation2d(), GetCurrentDistances(),
|
||||
frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.1, 0.1, 0.1}};
|
||||
m_kinematics, m_imu.GetRotation2d(), GetCurrentDistances(),
|
||||
frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.1, 0.1, 0.1}};
|
||||
};
|
||||
|
||||
@@ -62,10 +62,10 @@ frc2::CommandPtr Drive::DriveDistanceCommand(units::meter_t distance,
|
||||
|
||||
frc2::CommandPtr Drive::TurnToAngleCommand(units::degree_t angle) {
|
||||
return StartRun(
|
||||
[this] { m_controller.Reset(m_gyro.GetRotation2d().Degrees()); },
|
||||
[this] { m_controller.Reset(m_imu.GetRotation2d().Degrees()); },
|
||||
[this, angle] {
|
||||
m_drive.ArcadeDrive(
|
||||
0, m_controller.Calculate(m_gyro.GetRotation2d().Degrees(),
|
||||
0, m_controller.Calculate(m_imu.GetRotation2d().Degrees(),
|
||||
angle) +
|
||||
// Divide feedforward voltage by battery voltage to
|
||||
// normalize it to [-1, 1]
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <functional>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
@@ -65,7 +65,7 @@ class Drive : public frc2::SubsystemBase {
|
||||
DriveConstants::kRightEncoderPorts[1],
|
||||
DriveConstants::kRightEncoderReversed};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::ProfiledPIDController<units::radians> m_controller{
|
||||
DriveConstants::kTurnP,
|
||||
|
||||
@@ -24,14 +24,14 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(m_gyro.GetRotation2d(),
|
||||
m_odometry.Update(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()});
|
||||
}
|
||||
|
||||
void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {
|
||||
m_drivetrainSimulator.SetPose(pose);
|
||||
m_odometry.ResetPosition(m_gyro.GetRotation2d(),
|
||||
m_odometry.ResetPosition(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()}, pose);
|
||||
}
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/kinematics/DifferentialDriveKinematics.h>
|
||||
@@ -29,7 +29,7 @@
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
m_imu.ResetYaw();
|
||||
|
||||
m_leftLeader.AddFollower(m_leftFollower);
|
||||
m_rightLeader.AddFollower(m_rightFollower);
|
||||
@@ -87,11 +87,11 @@ class Drivetrain {
|
||||
frc::PIDController m_leftPIDController{8.5, 0.0, 0.0};
|
||||
frc::PIDController m_rightPIDController{8.5, 0.0, 0.0};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{
|
||||
m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
|
||||
m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()}};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
|
||||
@@ -10,7 +10,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::second_t period) {
|
||||
frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
|
||||
if (fieldRelative) {
|
||||
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_gyro.GetRotation2d());
|
||||
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d());
|
||||
}
|
||||
chassisSpeeds = chassisSpeeds.Discretize(period);
|
||||
|
||||
@@ -25,7 +25,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(m_gyro.GetRotation2d(),
|
||||
m_odometry.Update(m_imu.GetRotation2d(),
|
||||
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_backLeft.GetPosition(), m_backRight.GetPosition()});
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/kinematics/SwerveDriveOdometry.h>
|
||||
@@ -18,7 +18,7 @@
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
Drivetrain() { m_imu.ResetYaw(); }
|
||||
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
|
||||
@@ -41,7 +41,7 @@ class Drivetrain {
|
||||
SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
|
||||
SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::SwerveDriveKinematics<4> m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
@@ -49,7 +49,7 @@ class Drivetrain {
|
||||
|
||||
frc::SwerveDriveOdometry<4> m_odometry{
|
||||
m_kinematics,
|
||||
m_gyro.GetRotation2d(),
|
||||
m_imu.GetRotation2d(),
|
||||
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_backLeft.GetPosition(), m_backRight.GetPosition()}};
|
||||
};
|
||||
|
||||
@@ -30,7 +30,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_poseEstimator.Update(m_gyro.GetRotation2d(),
|
||||
m_poseEstimator.Update(m_imu.GetRotation2d(),
|
||||
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_backLeft.GetPosition(), m_backRight.GetPosition()});
|
||||
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include <frc/AnalogGyro.h>
|
||||
#include <frc/OnboardIMU.h>
|
||||
#include <frc/estimator/SwerveDrivePoseEstimator.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
@@ -19,7 +19,7 @@
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
Drivetrain() { m_imu.ResetYaw(); }
|
||||
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
|
||||
@@ -41,7 +41,7 @@ class Drivetrain {
|
||||
SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
|
||||
SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
|
||||
frc::SwerveDriveKinematics<4> m_kinematics{
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
|
||||
|
||||
Reference in New Issue
Block a user