mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Use gyro angle instead of robot angle for odometry (#2081)
The odometry classes previously took in the robot angle as an argument, meaning that users had to take care of offsetting the gyro themselves to accurately report the robot angle. This change will make it so that users will not have to worry about resetting gyros and adding offsets themselves, as this will be handled by the odometry classes.
This commit is contained in:
committed by
Peter Johnson
parent
1b66ead49d
commit
841ef91c0f
@@ -51,7 +51,7 @@ public class Drivetrain {
|
||||
= new DifferentialDriveKinematics(kTrackWidth);
|
||||
|
||||
private final DifferentialDriveOdometry m_odometry
|
||||
= new DifferentialDriveOdometry(m_kinematics);
|
||||
= new DifferentialDriveOdometry(m_kinematics, getAngle());
|
||||
|
||||
/**
|
||||
* Constructs a differential drive object.
|
||||
|
||||
@@ -52,7 +52,8 @@ public class Drivetrain {
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
|
||||
);
|
||||
|
||||
private final MecanumDriveOdometry m_odometry = new MecanumDriveOdometry(m_kinematics);
|
||||
private final MecanumDriveOdometry m_odometry = new MecanumDriveOdometry(m_kinematics,
|
||||
getAngle());
|
||||
|
||||
/**
|
||||
* Constructs a MecanumDrive and resets the gyro.
|
||||
|
||||
@@ -57,7 +57,8 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
private final Gyro m_gyro = new ADXRS450_Gyro();
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
DifferentialDriveOdometry m_odometry = new DifferentialDriveOdometry(kDriveKinematics);
|
||||
DifferentialDriveOdometry m_odometry = new DifferentialDriveOdometry(kDriveKinematics,
|
||||
Rotation2d.fromDegrees(getHeading()));
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
@@ -93,7 +94,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @param pose The pose to which to set the odometry.
|
||||
*/
|
||||
public void resetOdometry(Pose2d pose) {
|
||||
m_odometry.resetPosition(pose);
|
||||
m_odometry.resetPosition(pose, Rotation2d.fromDegrees(getHeading()));
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -37,7 +37,7 @@ public class Drivetrain {
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
|
||||
);
|
||||
|
||||
private final SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(m_kinematics);
|
||||
private final SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(m_kinematics, getAngle());
|
||||
|
||||
public Drivetrain() {
|
||||
m_gyro.reset();
|
||||
|
||||
Reference in New Issue
Block a user