mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Add Gyro::GetRotation2d() (#2555)
This commit is contained in:
@@ -14,7 +14,6 @@ import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
@@ -73,17 +72,7 @@ public class Drivetrain {
|
||||
m_leftEncoder.reset();
|
||||
m_rightEncoder.reset();
|
||||
|
||||
m_odometry = new DifferentialDriveOdometry(getAngle());
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the angle of the robot as a Rotation2d.
|
||||
*
|
||||
* @return The angle of the robot.
|
||||
*/
|
||||
public Rotation2d getAngle() {
|
||||
// Negating the angle because WPILib gyros are CW positive.
|
||||
return Rotation2d.fromDegrees(-m_gyro.getAngle());
|
||||
m_odometry = new DifferentialDriveOdometry(m_gyro.getRotation2d());
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -119,6 +108,7 @@ public class Drivetrain {
|
||||
* Updates the field-relative position.
|
||||
*/
|
||||
public void updateOdometry() {
|
||||
m_odometry.update(getAngle(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
|
||||
m_odometry.update(m_gyro.getRotation2d(), m_leftEncoder.getDistance(),
|
||||
m_rightEncoder.getDistance());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -13,7 +13,6 @@ import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveKinematics;
|
||||
@@ -55,7 +54,7 @@ public class Drivetrain {
|
||||
);
|
||||
|
||||
private final MecanumDriveOdometry m_odometry = new MecanumDriveOdometry(m_kinematics,
|
||||
getAngle());
|
||||
m_gyro.getRotation2d());
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own robot!
|
||||
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
|
||||
@@ -67,16 +66,6 @@ public class Drivetrain {
|
||||
m_gyro.reset();
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the angle of the robot as a Rotation2d.
|
||||
*
|
||||
* @return The angle of the robot.
|
||||
*/
|
||||
public Rotation2d getAngle() {
|
||||
// Negating the angle because WPILib gyros are CW positive.
|
||||
return Rotation2d.fromDegrees(-m_gyro.getAngle());
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the current state of the drivetrain.
|
||||
*
|
||||
@@ -133,7 +122,7 @@ public class Drivetrain {
|
||||
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||
var mecanumDriveWheelSpeeds = m_kinematics.toWheelSpeeds(
|
||||
fieldRelative ? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, getAngle()
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d()
|
||||
) : new ChassisSpeeds(xSpeed, ySpeed, rot)
|
||||
);
|
||||
mecanumDriveWheelSpeeds.normalize(kMaxSpeed);
|
||||
@@ -144,6 +133,6 @@ public class Drivetrain {
|
||||
* Updates the field relative position of the robot.
|
||||
*/
|
||||
public void updateOdometry() {
|
||||
m_odometry.update(getAngle(), getCurrentState());
|
||||
m_odometry.update(m_gyro.getRotation2d(), getCurrentState());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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. */
|
||||
@@ -55,8 +55,6 @@ public final class Constants {
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR;
|
||||
|
||||
public static final boolean 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.
|
||||
|
||||
@@ -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,6 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveMotorVoltages;
|
||||
import edu.wpi.first.wpilibj.kinematics.MecanumDriveOdometry;
|
||||
@@ -62,7 +61,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
MecanumDriveOdometry m_odometry =
|
||||
new MecanumDriveOdometry(DriveConstants.kDriveKinematics, getAngle());
|
||||
new MecanumDriveOdometry(DriveConstants.kDriveKinematics, m_gyro.getRotation2d());
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
@@ -75,20 +74,10 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_rearRightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the angle of the robot as a Rotation2d.
|
||||
*
|
||||
* @return The angle of the robot.
|
||||
*/
|
||||
public Rotation2d getAngle() {
|
||||
// Negating the angle because WPILib gyros are CW positive.
|
||||
return Rotation2d.fromDegrees(m_gyro.getAngle() * (DriveConstants.kGyroReversed ? 1.0 : -1.0));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// Update the odometry in the periodic block
|
||||
m_odometry.update(getAngle(),
|
||||
m_odometry.update(m_gyro.getRotation2d(),
|
||||
new MecanumDriveWheelSpeeds(
|
||||
m_frontLeftEncoder.getRate(),
|
||||
m_rearLeftEncoder.getRate(),
|
||||
@@ -111,7 +100,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, getAngle());
|
||||
m_odometry.resetPosition(pose, m_gyro.getRotation2d());
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -227,10 +216,10 @@ public class DriveSubsystem extends 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
|
||||
*/
|
||||
public double getHeading() {
|
||||
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return m_gyro.getRotation2d().getDegrees();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -239,6 +228,6 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @return The turn rate of the robot, in degrees per second
|
||||
*/
|
||||
public double getTurnRate() {
|
||||
return m_gyro.getRate() * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return -m_gyro.getRate();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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. */
|
||||
@@ -39,8 +39,6 @@ public final class Constants {
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR;
|
||||
|
||||
public static final boolean 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.
|
||||
|
||||
@@ -13,7 +13,6 @@ import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
@@ -60,13 +59,13 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_rightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
|
||||
resetEncoders();
|
||||
m_odometry = new DifferentialDriveOdometry(Rotation2d.fromDegrees(getHeading()));
|
||||
m_odometry = new DifferentialDriveOdometry(m_gyro.getRotation2d());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// Update the odometry in the periodic block
|
||||
m_odometry.update(Rotation2d.fromDegrees(getHeading()), m_leftEncoder.getDistance(),
|
||||
m_odometry.update(m_gyro.getRotation2d(), m_leftEncoder.getDistance(),
|
||||
m_rightEncoder.getDistance());
|
||||
}
|
||||
|
||||
@@ -95,7 +94,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
*/
|
||||
public void resetOdometry(Pose2d pose) {
|
||||
resetEncoders();
|
||||
m_odometry.resetPosition(pose, Rotation2d.fromDegrees(getHeading()));
|
||||
m_odometry.resetPosition(pose, m_gyro.getRotation2d());
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -177,7 +176,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @return the robot's heading in degrees, from -180 to 180
|
||||
*/
|
||||
public double getHeading() {
|
||||
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return m_gyro.getRotation2d().getDegrees();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -186,6 +185,6 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @return The turn rate of the robot, in degrees per second
|
||||
*/
|
||||
public double getTurnRate() {
|
||||
return m_gyro.getRate() * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return -m_gyro.getRate();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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. */
|
||||
@@ -8,7 +8,6 @@
|
||||
package edu.wpi.first.wpilibj.examples.swervebot;
|
||||
|
||||
import edu.wpi.first.wpilibj.AnalogGyro;
|
||||
import edu.wpi.first.wpilibj.geometry.Rotation2d;
|
||||
import edu.wpi.first.wpilibj.geometry.Translation2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.SwerveDriveKinematics;
|
||||
@@ -37,22 +36,13 @@ public class Drivetrain {
|
||||
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
|
||||
);
|
||||
|
||||
private final SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(m_kinematics, getAngle());
|
||||
private final SwerveDriveOdometry m_odometry = new SwerveDriveOdometry(m_kinematics,
|
||||
m_gyro.getRotation2d());
|
||||
|
||||
public Drivetrain() {
|
||||
m_gyro.reset();
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the angle of the robot as a Rotation2d.
|
||||
*
|
||||
* @return The angle of the robot.
|
||||
*/
|
||||
public Rotation2d getAngle() {
|
||||
// Negating the angle because WPILib gyros are CW positive.
|
||||
return Rotation2d.fromDegrees(-m_gyro.getAngle());
|
||||
}
|
||||
|
||||
/**
|
||||
* Method to drive the robot using joystick info.
|
||||
*
|
||||
@@ -65,7 +55,7 @@ public class Drivetrain {
|
||||
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||
var swerveModuleStates = m_kinematics.toSwerveModuleStates(
|
||||
fieldRelative ? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, getAngle())
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot)
|
||||
);
|
||||
SwerveDriveKinematics.normalizeWheelSpeeds(swerveModuleStates, kMaxSpeed);
|
||||
@@ -80,7 +70,7 @@ public class Drivetrain {
|
||||
*/
|
||||
public void updateOdometry() {
|
||||
m_odometry.update(
|
||||
getAngle(),
|
||||
m_gyro.getRotation2d(),
|
||||
m_frontLeft.getState(),
|
||||
m_frontRight.getState(),
|
||||
m_backLeft.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. */
|
||||
@@ -60,7 +60,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
SwerveDriveOdometry m_odometry =
|
||||
new SwerveDriveOdometry(DriveConstants.kDriveKinematics, getAngle());
|
||||
new SwerveDriveOdometry(DriveConstants.kDriveKinematics, m_gyro.getRotation2d());
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
@@ -68,16 +68,6 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
public DriveSubsystem() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the angle of the robot as a Rotation2d.
|
||||
*
|
||||
* @return The angle of the robot.
|
||||
*/
|
||||
public Rotation2d getAngle() {
|
||||
// Negating the angle because WPILib gyros are CW positive.
|
||||
return Rotation2d.fromDegrees(m_gyro.getAngle() * (DriveConstants.kGyroReversed ? 1.0 : -1.0));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
// Update the odometry in the periodic block
|
||||
@@ -104,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, getAngle());
|
||||
m_odometry.resetPosition(pose, m_gyro.getRotation2d());
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -119,7 +109,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
|
||||
var swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates(
|
||||
fieldRelative ? ChassisSpeeds.fromFieldRelativeSpeeds(
|
||||
xSpeed, ySpeed, rot, getAngle())
|
||||
xSpeed, ySpeed, rot, m_gyro.getRotation2d())
|
||||
: new ChassisSpeeds(xSpeed, ySpeed, rot)
|
||||
);
|
||||
SwerveDriveKinematics.normalizeWheelSpeeds(swerveModuleStates,
|
||||
@@ -164,10 +154,10 @@ public class DriveSubsystem extends 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
|
||||
*/
|
||||
public double getHeading() {
|
||||
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (DriveConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return m_gyro.getRotation2d().getDegrees();
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
Reference in New Issue
Block a user