Skip to content

Commit c433ee7

Browse files
committed
Remove AnalogGyro from examples
Some todos/fixups to address later
1 parent bd1dcc4 commit c433ee7

File tree

28 files changed

+107
-122
lines changed

28 files changed

+107
-122
lines changed

wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
2222
}
2323

2424
void Drivetrain::UpdateOdometry() {
25-
m_odometry.Update(m_gyro.GetRotation2d(),
25+
m_odometry.Update(m_imu.GetRotation2d(),
2626
units::meter_t{m_leftEncoder.GetDistance()},
2727
units::meter_t{m_rightEncoder.GetDistance()});
2828
}

wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66

77
#include <numbers>
88

9-
#include <frc/AnalogGyro.h>
109
#include <frc/Encoder.h>
10+
#include <frc/OnboardIMU.h>
1111
#include <frc/controller/PIDController.h>
1212
#include <frc/controller/SimpleMotorFeedforward.h>
1313
#include <frc/kinematics/DifferentialDriveKinematics.h>
@@ -32,7 +32,7 @@ class Drivetrain {
3232
// gearbox is constructed, you might have to invert the left side instead.
3333
m_rightLeader.SetInverted(true);
3434

35-
m_gyro.Reset();
35+
m_imu.ResetYaw();
3636
// Set the distance per pulse for the drive encoders. We can simply use the
3737
// distance traveled for one rotation of the wheel divided by the encoder
3838
// resolution.
@@ -71,11 +71,11 @@ class Drivetrain {
7171
frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
7272
frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
7373

74-
frc::AnalogGyro m_gyro{0};
74+
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
7575

7676
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
7777
frc::DifferentialDriveOdometry m_odometry{
78-
m_gyro.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
78+
m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
7979
units::meter_t{m_rightEncoder.GetDistance()}};
8080

8181
// Gains are for example purposes only - must be determined for your own

wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ Drivetrain::Drivetrain() {
1515
// gearbox is constructed, you might have to invert the left side instead.
1616
m_rightLeader.SetInverted(true);
1717

18-
m_gyro.Reset();
18+
m_imu.ResetYaw();
1919

2020
// Set the distance per pulse for the drive encoders. We can simply use the
2121
// distance traveled for one rotation of the wheel divided by the encoder
@@ -84,7 +84,7 @@ frc::Pose3d Drivetrain::ObjectToRobotPose(
8484
}
8585

8686
void Drivetrain::UpdateOdometry() {
87-
m_poseEstimator.Update(m_gyro.GetRotation2d(),
87+
m_poseEstimator.Update(m_imu.GetRotation2d(),
8888
units::meter_t{m_leftEncoder.GetDistance()},
8989
units::meter_t{m_rightEncoder.GetDistance()});
9090

@@ -125,6 +125,7 @@ void Drivetrain::SimulationPeriodic() {
125125
m_drivetrainSimulator.GetRightPosition().value());
126126
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetRightVelocity().value());
127127
// m_gyroSim.SetAngle(-m_drivetrainSimulator.GetHeading().Degrees().value());
128+
// // TODO(Ryan): fixup when sim implemented
128129
}
129130

130131
void Drivetrain::Periodic() {

wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,9 @@
66

77
#include <numbers>
88

9-
#include <frc/AnalogGyro.h>
109
#include <frc/ComputerVisionUtil.h>
1110
#include <frc/Encoder.h>
11+
#include <frc/OnboardIMU.h>
1212
#include <frc/RobotController.h>
1313
#include <frc/Timer.h>
1414
#include <frc/apriltag/AprilTagFieldLayout.h>
@@ -144,15 +144,15 @@ class Drivetrain {
144144
frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
145145
frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
146146

147-
frc::AnalogGyro m_gyro{0};
147+
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
148148

149149
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
150150

151151
// Gains are for example purposes only - must be determined for your own
152152
// robot!
153153
frc::DifferentialDrivePoseEstimator m_poseEstimator{
154154
m_kinematics,
155-
m_gyro.GetRotation2d(),
155+
m_imu.GetRotation2d(),
156156
units::meter_t{m_leftEncoder.GetDistance()},
157157
units::meter_t{m_rightEncoder.GetDistance()},
158158
frc::Pose2d{},

wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp

Lines changed: 5 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
44

55
#include <cmath>
66

7-
#include <frc/AnalogGyro.h>
87
#include <frc/Joystick.h>
8+
#include <frc/OnboardIMU.h>
99
#include <frc/TimedRobot.h>
1010
#include <frc/drive/DifferentialDrive.h>
1111
#include <frc/motorcontrol/PWMSparkMax.h>
@@ -18,7 +18,6 @@
1818
class Robot : public frc::TimedRobot {
1919
public:
2020
Robot() {
21-
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
2221
// We need to invert one side of the drivetrain so that positive voltages
2322
// result in both sides moving forward. Depending on how your robot's
2423
// gearbox is constructed, you might have to invert the left side instead.
@@ -34,29 +33,26 @@ class Robot : public frc::TimedRobot {
3433
* angle.
3534
*/
3635
void TeleopPeriodic() override {
37-
double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
36+
double turningValue =
37+
(kAngleSetpoint - m_imu.GetRotation2d().Degrees().value()) * kP;
3838
m_drive.ArcadeDrive(-m_joystick.GetY(), -turningValue);
3939
}
4040

4141
private:
4242
static constexpr double kAngleSetpoint = 0.0;
4343
static constexpr double kP = 0.005; // Proportional turning constant
4444

45-
// Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
46-
// set to correspond to one full revolution.
47-
static constexpr double kVoltsPerDegreePerSecond = 0.0128;
48-
4945
static constexpr int kLeftMotorPort = 0;
5046
static constexpr int kRightMotorPort = 1;
51-
static constexpr int kGyroPort = 0;
47+
static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation = frc::OnboardIMU::kFlat;
5248
static constexpr int kJoystickPort = 0;
5349

5450
frc::PWMSparkMax m_left{kLeftMotorPort};
5551
frc::PWMSparkMax m_right{kRightMotorPort};
5652
frc::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); },
5753
[&](double output) { m_right.Set(output); }};
5854

59-
frc::AnalogGyro m_gyro{kGyroPort};
55+
frc::OnboardIMU m_imu{kIMUMountOrientation};
6056
frc::Joystick m_joystick{kJoystickPort};
6157
};
6258

wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22
// Open Source Software; you can modify and/or share it under the terms of
33
// the WPILib BSD license file in the root directory of this project.
44

5-
#include <frc/AnalogGyro.h>
65
#include <frc/Joystick.h>
6+
#include <frc/OnboardIMU.h>
77
#include <frc/TimedRobot.h>
88
#include <frc/drive/MecanumDrive.h>
99
#include <frc/motorcontrol/PWMSparkMax.h>
@@ -25,28 +25,22 @@ class Robot : public frc::TimedRobot {
2525
// match your robot.
2626
m_frontRight.SetInverted(true);
2727
m_rearRight.SetInverted(true);
28-
29-
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
3028
}
3129

3230
/**
3331
* Mecanum drive is used with the gyro angle as an input.
3432
*/
3533
void TeleopPeriodic() override {
3634
m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
37-
-m_joystick.GetZ(), m_gyro.GetRotation2d());
35+
-m_joystick.GetZ(), m_imu.GetRotation2d());
3836
}
3937

4038
private:
41-
// Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
42-
// set to correspond to one full revolution.
43-
static constexpr double kVoltsPerDegreePerSecond = 0.0128;
44-
4539
static constexpr int kFrontLeftMotorPort = 0;
4640
static constexpr int kRearLeftMotorPort = 1;
4741
static constexpr int kFrontRightMotorPort = 2;
4842
static constexpr int kRearRightMotorPort = 3;
49-
static constexpr int kGyroPort = 0;
43+
static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation = frc::OnboardIMU::kFlat;
5044
static constexpr int kJoystickPort = 0;
5145

5246
frc::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
@@ -59,7 +53,7 @@ class Robot : public frc::TimedRobot {
5953
[&](double output) { m_frontRight.Set(output); },
6054
[&](double output) { m_rearRight.Set(output); }};
6155

62-
frc::AnalogGyro m_gyro{kGyroPort};
56+
frc::OnboardIMU m_imu{kIMUMountOrientation};
6357
frc::Joystick m_joystick{kJoystickPort};
6458
};
6559

wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -55,12 +55,12 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
5555
units::second_t period) {
5656
frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
5757
if (fieldRelative) {
58-
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_gyro.GetRotation2d());
58+
chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d());
5959
}
6060
SetSpeeds(m_kinematics.ToWheelSpeeds(chassisSpeeds.Discretize(period))
6161
.Desaturate(kMaxSpeed));
6262
}
6363

6464
void Drivetrain::UpdateOdometry() {
65-
m_odometry.Update(m_gyro.GetRotation2d(), GetCurrentWheelDistances());
65+
m_odometry.Update(m_imu.GetRotation2d(), GetCurrentWheelDistances());
6666
}

wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66

77
#include <numbers>
88

9-
#include <frc/AnalogGyro.h>
109
#include <frc/Encoder.h>
10+
#include <frc/OnboardIMU.h>
1111
#include <frc/controller/PIDController.h>
1212
#include <frc/controller/SimpleMotorFeedforward.h>
1313
#include <frc/geometry/Translation2d.h>
@@ -22,7 +22,7 @@
2222
class Drivetrain {
2323
public:
2424
Drivetrain() {
25-
m_gyro.Reset();
25+
m_imu.ResetYaw();
2626
// We need to invert one side of the drivetrain so that positive voltages
2727
// result in both sides moving forward. Depending on how your robot's
2828
// gearbox is constructed, you might have to invert the left side instead.
@@ -64,13 +64,13 @@ class Drivetrain {
6464
frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
6565
frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
6666

67-
frc::AnalogGyro m_gyro{0};
67+
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
6868

6969
frc::MecanumDriveKinematics m_kinematics{
7070
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
7171
m_backRightLocation};
7272

73-
frc::MecanumDriveOdometry m_odometry{m_kinematics, m_gyro.GetRotation2d(),
73+
frc::MecanumDriveOdometry m_odometry{m_kinematics, m_imu.GetRotation2d(),
7474
GetCurrentWheelDistances()};
7575

7676
// Gains are for example purposes only - must be determined for your own

wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,9 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
5858
}
5959

6060
void Drivetrain::UpdateOdometry() {
61-
m_poseEstimator.Update(m_gyro.GetRotation2d(), GetCurrentDistances());
61+
m_poseEstimator.Update(
62+
m_imu.GetRotation2d(),
63+
GetCurrentDistances()); // TODO(Ryan): fixup when sim implemented
6264

6365
// Also apply vision measurements. We use 0.3 seconds in the past as an
6466
// example -- on a real robot, this must be calculated based either on latency

wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66

77
#include <numbers>
88

9-
#include <frc/AnalogGyro.h>
109
#include <frc/Encoder.h>
10+
#include <frc/OnboardIMU.h>
1111
#include <frc/controller/PIDController.h>
1212
#include <frc/controller/SimpleMotorFeedforward.h>
1313
#include <frc/estimator/MecanumDrivePoseEstimator.h>
@@ -23,7 +23,7 @@
2323
class Drivetrain {
2424
public:
2525
Drivetrain() {
26-
m_gyro.Reset();
26+
m_imu.ResetYaw();
2727
// We need to invert one side of the drivetrain so that positive voltages
2828
// result in both sides moving forward. Depending on how your robot's
2929
// gearbox is constructed, you might have to invert the left side instead.
@@ -64,7 +64,7 @@ class Drivetrain {
6464
frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
6565
frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
6666

67-
frc::AnalogGyro m_gyro{0};
67+
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
6868

6969
frc::MecanumDriveKinematics m_kinematics{
7070
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
@@ -77,6 +77,6 @@ class Drivetrain {
7777
// Gains are for example purposes only - must be determined for your own
7878
// robot!
7979
frc::MecanumDrivePoseEstimator m_poseEstimator{
80-
m_kinematics, m_gyro.GetRotation2d(), GetCurrentDistances(),
81-
frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.1, 0.1, 0.1}};
80+
m_kinematics, m_imu.GetRotation2d(), GetCurrentDistances(),
81+
frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.1, 0.1, 0.1}};
8282
};

0 commit comments

Comments
 (0)