+
private int
+
+
Counter to synchronize the modules relative encoder with absolute encoder when not moving.
-
-
-
+
+
+
Odometry lock to ensure thread safety.
-
private final edu.wpi.first.wpilibj.Notifier
-
-
+
private final edu.wpi.first.wpilibj.Notifier
+
+
WPILib Notifier to keep odometry up to date.
-
-
-
-
Simulation of the swerve drive.
-
-
edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1>
-
+
+
-
Standard deviation of encoders and gyroscopes, usually should not change.
+
Simulation of the swerve drive.
@@ -202,13 +192,6 @@ loadScripts(document, 'script');
Alert to recommend Tuner X if the configuration is compatible.
-
edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1>
-
-
-
The standard deviation of the vision measurement, for best accuracy calculate the standard deviation at 2 or more
- points and fit a line to it and modify this using
addVisionMeasurement(Pose2d, double, Matrix)
- with the calculated optimal standard deviation.
-
@@ -344,182 +327,187 @@ loadScripts(document, 'script');
edu.wpi.first.math.geometry.Rotation2d
-
+
-
Gets the current pitch angle of the robot, as reported by the imu.
-
-
edu.wpi.first.math.geometry.Pose2d
-
-
-
Gets the current pose (position and rotation) of the robot, as reported by odometry.
-
-
edu.wpi.first.math.kinematics.ChassisSpeeds
-
-
-
Gets the current robot-relative velocity (x, y and omega) of the robot
+
Fetch the latest odometry heading, should be trusted over
getYaw().
edu.wpi.first.math.geometry.Rotation2d
-
+
+
Gets the current pitch angle of the robot, as reported by the imu.
+
+
edu.wpi.first.math.geometry.Pose2d
+
+
+
Gets the current pose (position and rotation) of the robot, as reported by odometry.
+
+
edu.wpi.first.math.kinematics.ChassisSpeeds
+
+
+
Gets the current robot-relative velocity (x, y and omega) of the robot
+
+
edu.wpi.first.math.geometry.Rotation2d
+
+
Gets the current roll angle of the robot, as reported by the imu.
-
edu.wpi.first.math.kinematics.SwerveModuleState[]
-
-
+
edu.wpi.first.math.kinematics.SwerveModuleState[]
+
+
Gets the current module states (azimuth and velocity)
-
-
-
+
+
+
Helper function to get the
swerveController for the
SwerveDrive which can be used to
generate
ChassisSpeeds for the robot to orient it correctly given axis or angles, and apply
SlewRateLimiter to given inputs.
-
edu.wpi.first.math.geometry.Pose2d[]
-
-
+
edu.wpi.first.math.geometry.Pose2d[]
+
+
Get the swerve module poses and on the field relative to the robot.
-
edu.wpi.first.math.geometry.Rotation2d
-
-
+
edu.wpi.first.math.geometry.Rotation2d
+
+
Gets the current yaw angle of the robot, as reported by the imu.
-
void
-
-
+
void
+
+
Point all modules toward the robot center, thus making the robot very difficult to move.
-
void
-
-
+
void
+
+
Post the trajectory to the field
-
void
-
-
+
void
+
+
Pushes the Absolute Encoder offsets to the Encoder or Motor Controller, depending on type.
-
void
-
-
+
void
+
+
Setup the swerve module feedforward.
-
void
-
-
+
void
+
+
Reset the drive encoders on the robot, useful when manually resetting the robot without a reboot, like in
autonomous.
-
void
-
-
+
void
+
+
Resets odometry to the given pose.
-
void
-
-
+
void
+
+
Restores Internal YAGSL Encoder offsets and sets the Encoder stored offset back to 0
-
void
-
-
+
void
+
+
Set the conversion factor for the angle/azimuth motor controller.
-
void
-
-
+
void
+
+
Set chassis speeds with closed-loop velocity control.
-
void
-
-
+
void
+
+
Set the conversion factor for the drive motor controller.
-
void
-
setGyro (edu.wpi.first.math.geometry.Rotation3d gyro)
-
+
void
+
setGyro (edu.wpi.first.math.geometry.Rotation3d gyro)
+
Set the expected gyroscope angle using a Rotation3d object.
-
void
-
-
+
void
+
+
Set the gyro scope offset to a desired known rotation.
-
void
-
-
-
Set the heading correction capabilities of YAGSL.
-
void
-
+
Set the heading correction capabilities of YAGSL.
void
-
+
+
Set the heading correction capabilities of YAGSL.
+
+
void
+
+
-
void
-
setMaximumSpeed (double maximumSpeed,
+void
+setMaximumSpeed (double maximumSpeed,
boolean updateModuleFeedforward,
double optimalVoltage)
-
+
-
void
-
setMaximumSpeeds (double attainableMaxModuleSpeedMetersPerSecond,
+void
+setMaximumSpeeds (double attainableMaxModuleSpeedMetersPerSecond,
double attainableMaxTranslationalSpeedMetersPerSecond,
double attainableMaxRotationalVelocityRadiansPerSecond)
-
+
Set the maximum speeds for desaturation.
-
void
-
setModuleStates (edu.wpi.first.math.kinematics.SwerveModuleState[] desiredStates,
+void
+setModuleStates (edu.wpi.first.math.kinematics.SwerveModuleState[] desiredStates,
boolean isOpenLoop)
-
+
Set the module states (azimuth and velocity) directly.
-
void
-
-
+
void
+
+
Sets the drive motors to brake/coast mode.
-
void
-
-
+
void
+
+
Set the odometry update period in seconds.
-
private void
-
setRawModuleStates (edu.wpi.first.math.kinematics.SwerveModuleState[] desiredStates,
+private void
+setRawModuleStates (edu.wpi.first.math.kinematics.SwerveModuleState[] desiredStates,
boolean isOpenLoop)
-
+
Set the module states (azimuth and velocity) directly.
-
void
-
-
+
void
+
+
Stop the odometry thread in favor of manually updating odometry.
-
void
-
-
+
void
+
+
Synchronize angle motor integrated encoders with data from absolute encoders.
-
void
-
-
+
void
+
+
Update odometry should be run every loop.
-
void
-
-
+
void
+
+
Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
@@ -582,10 +570,10 @@ loadScripts(document, 'script');
-
-HEADING_CORRECTION_DEADBAND
-private double HEADING_CORRECTION_DEADBAND
-Deadband for speeds in heading correction.
+
+tunerXRecommendation
+private final Alert tunerXRecommendation
+Alert to recommend Tuner X if the configuration is compatible.
@@ -603,31 +591,6 @@ loadScripts(document, 'script');
-
-stateStdDevs
-public edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> stateStdDevs
-Standard deviation of encoders and gyroscopes, usually should not change. (meters of position and degrees of
- rotation)
-
-
-
-
-visionMeasurementStdDevs
-public edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> visionMeasurementStdDevs
-The standard deviation of the vision measurement, for best accuracy calculate the standard deviation at 2 or more
- points and fit a line to it and modify this using
addVisionMeasurement(Pose2d, double, Matrix)
- with the calculated optimal standard deviation. (Units should be meters per pixel). By optimizing this you can get
- vision accurate to inches instead of feet.
-
-
-
-
-invertOdometry
-public boolean invertOdometry
-Invert odometry readings of drive motor positions, used as a patch for debugging currently.
-
-
-
chassisVelocityCorrection
public boolean chassisVelocityCorrection
@@ -643,6 +606,13 @@ loadScripts(document, 'script');
+
+HEADING_CORRECTION_DEADBAND
+private double HEADING_CORRECTION_DEADBAND
+Deadband for speeds in heading correction.
+
+
+
correctionEnabled
private boolean correctionEnabled
@@ -698,13 +668,6 @@ loadScripts(document, 'script');
Maximum speed of the robot in meters per second.
-
-
-tunerXRecommendation
-private final Alert tunerXRecommendation
-Alert to recommend Tuner X if the configuration is compatible.
-
-
@@ -792,6 +755,17 @@ loadScripts(document, 'script');
+
+getOdometryHeading
+public edu.wpi.first.math.geometry.Rotation2d getOdometryHeading ()
+Fetch the latest odometry heading, should be trusted over
getYaw().
+
+Returns:
+Rotation2d of the robot heading.
+
+
+
+
setHeadingCorrection
public void setHeadingCorrection (boolean state)
@@ -1083,8 +1057,7 @@ loadScripts(document, 'script');
getModulePositions
public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions ()
-Gets the current module positions (azimuth and wheel position (meters)). Inverts the distance from each module if
-
invertOdometry is true.
+Gets the current module positions (azimuth and wheel position (meters)).
Returns:
A list of SwerveModulePositions containg the current module positions
@@ -1260,23 +1233,6 @@ loadScripts(document, 'script');
-
-addVisionMeasurement
-public void addVisionMeasurement (edu.wpi.first.math.geometry.Pose2d robotPose,
- double timestamp)
-Add a vision measurement to the
SwerveDrivePoseEstimator and update the
SwerveIMU gyro reading with
- the given timestamp of the vision measurement.
IT IS HIGHLY RECOMMENDED TO UPDATE YOUR GYROSCOPE OFFSET
- AFTER USING THIS FUNCTION! To update your gyroscope readings directly use
-
setGyroOffset(Rotation3d).
-
-Parameters:
-robotPose - Robot Pose2d as measured by vision.
-timestamp - Timestamp the measurement was taken as time since startup, should be taken from
- Timer.getFPGATimestamp() or similar sources.
-
-
-
-
addVisionMeasurement
public void addVisionMeasurement (edu.wpi.first.math.geometry.Pose2d robotPose,
@@ -1299,6 +1255,23 @@ loadScripts(document, 'script');
+
+addVisionMeasurement
+public void addVisionMeasurement (edu.wpi.first.math.geometry.Pose2d robotPose,
+ double timestamp)
+Add a vision measurement to the
SwerveDrivePoseEstimator and update the
SwerveIMU gyro reading with
+ the given timestamp of the vision measurement.
IT IS HIGHLY RECOMMENDED TO UPDATE YOUR GYROSCOPE OFFSET
+ AFTER USING THIS FUNCTION! To update your gyroscope readings directly use
+
setGyroOffset(Rotation3d).
+
+Parameters:
+robotPose - Robot Pose2d as measured by vision.
+timestamp - Timestamp the measurement was taken as time since startup, should be taken from
+ Timer.getFPGATimestamp() or similar sources.
+
+
+
+
setGyro
public void setGyro (edu.wpi.first.math.geometry.Rotation3d gyro)
diff --git a/docs/swervelib/SwerveModule.html b/docs/swervelib/SwerveModule.html
index de3cdc5..b96aa37 100644
--- a/docs/swervelib/SwerveModule.html
+++ b/docs/swervelib/SwerveModule.html
@@ -1,11 +1,11 @@
-
+
SwerveModule
-
+
diff --git a/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html b/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html
index 4e02aa5..bc69ebc 100644
--- a/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html
+++ b/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html
@@ -1,11 +1,11 @@
-
+
AnalogAbsoluteEncoderSwerve
-
+
diff --git a/docs/swervelib/encoders/CANCoderSwerve.html b/docs/swervelib/encoders/CANCoderSwerve.html
index 6507b46..c5aaa82 100644
--- a/docs/swervelib/encoders/CANCoderSwerve.html
+++ b/docs/swervelib/encoders/CANCoderSwerve.html
@@ -1,11 +1,11 @@
-
+
CANCoderSwerve
-
+
diff --git a/docs/swervelib/encoders/CanAndCoderSwerve.html b/docs/swervelib/encoders/CanAndCoderSwerve.html
index 64fa51d..8cda091 100644
--- a/docs/swervelib/encoders/CanAndCoderSwerve.html
+++ b/docs/swervelib/encoders/CanAndCoderSwerve.html
@@ -1,11 +1,11 @@
-
+
CanAndCoderSwerve
-
+
diff --git a/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html b/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html
index 802c817..92924c6 100644
--- a/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html
+++ b/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html
@@ -1,11 +1,11 @@
-
+
PWMDutyCycleEncoderSwerve
-
+
diff --git a/docs/swervelib/encoders/SparkMaxAnalogEncoderSwerve.html b/docs/swervelib/encoders/SparkMaxAnalogEncoderSwerve.html
index fa15445..93bf7fe 100644
--- a/docs/swervelib/encoders/SparkMaxAnalogEncoderSwerve.html
+++ b/docs/swervelib/encoders/SparkMaxAnalogEncoderSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkMaxAnalogEncoderSwerve
-
+
diff --git a/docs/swervelib/encoders/SparkMaxEncoderSwerve.html b/docs/swervelib/encoders/SparkMaxEncoderSwerve.html
index 9b6d053..cef16cb 100644
--- a/docs/swervelib/encoders/SparkMaxEncoderSwerve.html
+++ b/docs/swervelib/encoders/SparkMaxEncoderSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkMaxEncoderSwerve
-
+
diff --git a/docs/swervelib/encoders/SwerveAbsoluteEncoder.html b/docs/swervelib/encoders/SwerveAbsoluteEncoder.html
index 354b49c..2332dff 100644
--- a/docs/swervelib/encoders/SwerveAbsoluteEncoder.html
+++ b/docs/swervelib/encoders/SwerveAbsoluteEncoder.html
@@ -1,11 +1,11 @@
-
+
SwerveAbsoluteEncoder
-
+
diff --git a/docs/swervelib/encoders/package-summary.html b/docs/swervelib/encoders/package-summary.html
index e4d1e1d..074df6f 100644
--- a/docs/swervelib/encoders/package-summary.html
+++ b/docs/swervelib/encoders/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.encoders
-
+
diff --git a/docs/swervelib/encoders/package-tree.html b/docs/swervelib/encoders/package-tree.html
index cc9c2d3..52b89ef 100644
--- a/docs/swervelib/encoders/package-tree.html
+++ b/docs/swervelib/encoders/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.encoders Class Hierarchy
-
+
diff --git a/docs/swervelib/imu/ADIS16448Swerve.html b/docs/swervelib/imu/ADIS16448Swerve.html
index 8c371e4..bcc1338 100644
--- a/docs/swervelib/imu/ADIS16448Swerve.html
+++ b/docs/swervelib/imu/ADIS16448Swerve.html
@@ -1,11 +1,11 @@
-
+
ADIS16448Swerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
ADIS16448_IMU device to read the current headings from.
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
Offset for the ADIS16448.
@@ -163,8 +168,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+
void
+
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -198,6 +208,13 @@ loadScripts(document, 'script');
Offset for the ADIS16448.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -257,6 +274,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/ADIS16470Swerve.html b/docs/swervelib/imu/ADIS16470Swerve.html
index ecb877d..bfc358e 100644
--- a/docs/swervelib/imu/ADIS16470Swerve.html
+++ b/docs/swervelib/imu/ADIS16470Swerve.html
@@ -1,11 +1,11 @@
-
+
ADIS16470Swerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
ADIS16470_IMU device to read the current headings from.
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
Offset for the ADIS16470.
@@ -163,8 +168,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+void
+setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -198,6 +208,13 @@ loadScripts(document, 'script');
Offset for the ADIS16470.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -257,6 +274,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/ADXRS450Swerve.html b/docs/swervelib/imu/ADXRS450Swerve.html
index 9d694ea..3e689aa 100644
--- a/docs/swervelib/imu/ADXRS450Swerve.html
+++ b/docs/swervelib/imu/ADXRS450Swerve.html
@@ -1,11 +1,11 @@
-
+
ADXRS450Swerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
ADXRS450_Gyro device to read the current headings from.
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
@@ -163,8 +168,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+
void
+
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -198,6 +208,13 @@ loadScripts(document, 'script');
Offset for the ADXRS450.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -257,6 +274,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/AnalogGyroSwerve.html b/docs/swervelib/imu/AnalogGyroSwerve.html
index 89974a7..47f4dfb 100644
--- a/docs/swervelib/imu/AnalogGyroSwerve.html
+++ b/docs/swervelib/imu/AnalogGyroSwerve.html
@@ -1,11 +1,11 @@
-
+
AnalogGyroSwerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
Offset for the analog gyro.
@@ -163,8 +168,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+void
+setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -198,6 +208,13 @@ loadScripts(document, 'script');
Offset for the analog gyro.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -261,6 +278,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/NavXSwerve.html b/docs/swervelib/imu/NavXSwerve.html
index addadf3..63f4dff 100644
--- a/docs/swervelib/imu/NavXSwerve.html
+++ b/docs/swervelib/imu/NavXSwerve.html
@@ -1,11 +1,11 @@
-
+
NavXSwerve
-
+
@@ -98,14 +98,19 @@ loadScripts(document, 'script');
-
-
+private boolean
+
+
Inversion for the gyro
+
+
+
+
An
Alert for if there is an error instantiating the NavX.
-private edu.wpi.first.math.geometry.Rotation3d
-
-
+
private edu.wpi.first.math.geometry.Rotation3d
+
+
@@ -176,8 +181,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+void
+setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -212,6 +222,13 @@ loadScripts(document, 'script');
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
+
navXError
@@ -303,6 +320,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/Pigeon2Swerve.html b/docs/swervelib/imu/Pigeon2Swerve.html
index 0a09769..6a147da 100644
--- a/docs/swervelib/imu/Pigeon2Swerve.html
+++ b/docs/swervelib/imu/Pigeon2Swerve.html
@@ -1,11 +1,11 @@
-
+
Pigeon2Swerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
@@ -168,8 +173,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+
void
+
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -203,6 +213,13 @@ loadScripts(document, 'script');
Offset for the Pigeon 2.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -279,6 +296,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/PigeonSwerve.html b/docs/swervelib/imu/PigeonSwerve.html
index 0dcb7dd..f01a245 100644
--- a/docs/swervelib/imu/PigeonSwerve.html
+++ b/docs/swervelib/imu/PigeonSwerve.html
@@ -1,11 +1,11 @@
-
+
PigeonSwerve
-
+
@@ -98,9 +98,14 @@ loadScripts(document, 'script');
-private edu.wpi.first.math.geometry.Rotation3d
-
+private boolean
+
+
Inversion for the gyro
+
+private edu.wpi.first.math.geometry.Rotation3d
+
+
@@ -163,8 +168,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
void
-
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction
+
+
void
+
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -198,6 +208,13 @@ loadScripts(document, 'script');
Offset for the Pigeon.
+
+
+invertedIMU
+private boolean invertedIMU
+Inversion for the gyro
+
+
@@ -261,6 +278,19 @@ loadScripts(document, 'script');
+
+setInverted
+public void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction
+
+Specified by:
+setInverted in class SwerveIMU
+Parameters:
+invertIMU - invert gyro direction
+
+
+
+
getRawRotation3d
public edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/SwerveIMU.html b/docs/swervelib/imu/SwerveIMU.html
index 4cc8291..1320268 100644
--- a/docs/swervelib/imu/SwerveIMU.html
+++ b/docs/swervelib/imu/SwerveIMU.html
@@ -1,11 +1,11 @@
-
+
SwerveIMU
-
+
@@ -141,8 +141,13 @@ loadScripts(document, 'script');
Fetch the Rotation3d from the IMU.
abstract void
-
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
+
Set the gyro to invert its default direction.
+
+
abstract void
+
setOffset (edu.wpi.first.math.geometry.Rotation3d offset)
+
@@ -202,6 +207,17 @@ loadScripts(document, 'script');
+
+setInverted
+public abstract void setInverted (boolean invertIMU)
+Set the gyro to invert its default direction.
+
+Parameters:
+invertIMU - gyro direction
+
+
+
+
getRawRotation3d
public abstract edu.wpi.first.math.geometry.Rotation3d getRawRotation3d ()
diff --git a/docs/swervelib/imu/package-summary.html b/docs/swervelib/imu/package-summary.html
index 398b6c6..47da48f 100644
--- a/docs/swervelib/imu/package-summary.html
+++ b/docs/swervelib/imu/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.imu
-
+
diff --git a/docs/swervelib/imu/package-tree.html b/docs/swervelib/imu/package-tree.html
index 6748f69..9437dcc 100644
--- a/docs/swervelib/imu/package-tree.html
+++ b/docs/swervelib/imu/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.imu Class Hierarchy
-
+
diff --git a/docs/swervelib/math/Matter.html b/docs/swervelib/math/Matter.html
index fa78262..f9768e8 100644
--- a/docs/swervelib/math/Matter.html
+++ b/docs/swervelib/math/Matter.html
@@ -1,11 +1,11 @@
-
+
Matter
-
+
diff --git a/docs/swervelib/math/SwerveMath.html b/docs/swervelib/math/SwerveMath.html
index 07d1564..d86ea17 100644
--- a/docs/swervelib/math/SwerveMath.html
+++ b/docs/swervelib/math/SwerveMath.html
@@ -1,11 +1,11 @@
-
+
SwerveMath
-
+
diff --git a/docs/swervelib/math/package-summary.html b/docs/swervelib/math/package-summary.html
index 1792363..51b0958 100644
--- a/docs/swervelib/math/package-summary.html
+++ b/docs/swervelib/math/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.math
-
+
diff --git a/docs/swervelib/math/package-tree.html b/docs/swervelib/math/package-tree.html
index d671a29..722c93b 100644
--- a/docs/swervelib/math/package-tree.html
+++ b/docs/swervelib/math/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.math Class Hierarchy
-
+
diff --git a/docs/swervelib/motors/SparkFlexSwerve.SparkMAX_slotIdx.html b/docs/swervelib/motors/SparkFlexSwerve.SparkMAX_slotIdx.html
index a7e9d48..f809eb6 100644
--- a/docs/swervelib/motors/SparkFlexSwerve.SparkMAX_slotIdx.html
+++ b/docs/swervelib/motors/SparkFlexSwerve.SparkMAX_slotIdx.html
@@ -1,11 +1,11 @@
-
+
SparkFlexSwerve.SparkMAX_slotIdx
-
+
diff --git a/docs/swervelib/motors/SparkFlexSwerve.html b/docs/swervelib/motors/SparkFlexSwerve.html
index 556937e..4e20f49 100644
--- a/docs/swervelib/motors/SparkFlexSwerve.html
+++ b/docs/swervelib/motors/SparkFlexSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkFlexSwerve
-
+
diff --git a/docs/swervelib/motors/SparkMaxBrushedMotorSwerve.html b/docs/swervelib/motors/SparkMaxBrushedMotorSwerve.html
index d131f6b..05712ba 100644
--- a/docs/swervelib/motors/SparkMaxBrushedMotorSwerve.html
+++ b/docs/swervelib/motors/SparkMaxBrushedMotorSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkMaxBrushedMotorSwerve
-
+
diff --git a/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html b/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html
index 921958f..f65e07d 100644
--- a/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html
+++ b/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html
@@ -1,11 +1,11 @@
-
+
SparkMaxSwerve.SparkMAX_slotIdx
-
+
diff --git a/docs/swervelib/motors/SparkMaxSwerve.html b/docs/swervelib/motors/SparkMaxSwerve.html
index 824ba8b..94d5f58 100644
--- a/docs/swervelib/motors/SparkMaxSwerve.html
+++ b/docs/swervelib/motors/SparkMaxSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkMaxSwerve
-
+
diff --git a/docs/swervelib/motors/SwerveMotor.html b/docs/swervelib/motors/SwerveMotor.html
index e6a1fad..77b0a5f 100644
--- a/docs/swervelib/motors/SwerveMotor.html
+++ b/docs/swervelib/motors/SwerveMotor.html
@@ -1,11 +1,11 @@
-
+
SwerveMotor
-
+
diff --git a/docs/swervelib/motors/TalonFXSwerve.html b/docs/swervelib/motors/TalonFXSwerve.html
index 7f1582c..ff84aaf 100644
--- a/docs/swervelib/motors/TalonFXSwerve.html
+++ b/docs/swervelib/motors/TalonFXSwerve.html
@@ -1,11 +1,11 @@
-
+
TalonFXSwerve
-
+
@@ -359,13 +359,6 @@ loadScripts(document, 'script');
-
-conversionFactor
-private double conversionFactor
-Conversion factor for the motor.
-
-
-
motor
com.ctre.phoenix6.hardware.TalonFX motor
@@ -373,6 +366,13 @@ loadScripts(document, 'script');
+
+conversionFactor
+private double conversionFactor
+Conversion factor for the motor.
+
+
+
configuration
private com.ctre.phoenix6.configs.TalonFXConfiguration configuration
diff --git a/docs/swervelib/motors/TalonSRXSwerve.html b/docs/swervelib/motors/TalonSRXSwerve.html
index 7d0ebc6..bb0b839 100644
--- a/docs/swervelib/motors/TalonSRXSwerve.html
+++ b/docs/swervelib/motors/TalonSRXSwerve.html
@@ -1,11 +1,11 @@
-
+
TalonSRXSwerve
-
+
diff --git a/docs/swervelib/motors/package-summary.html b/docs/swervelib/motors/package-summary.html
index d2330c7..20ff16d 100644
--- a/docs/swervelib/motors/package-summary.html
+++ b/docs/swervelib/motors/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.motors
-
+
diff --git a/docs/swervelib/motors/package-tree.html b/docs/swervelib/motors/package-tree.html
index 4206f60..f2f691f 100644
--- a/docs/swervelib/motors/package-tree.html
+++ b/docs/swervelib/motors/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.motors Class Hierarchy
-
+
diff --git a/docs/swervelib/package-summary.html b/docs/swervelib/package-summary.html
index e3da96d..7e633ef 100644
--- a/docs/swervelib/package-summary.html
+++ b/docs/swervelib/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib
-
+
diff --git a/docs/swervelib/package-tree.html b/docs/swervelib/package-tree.html
index 483cf65..56eff0e 100644
--- a/docs/swervelib/package-tree.html
+++ b/docs/swervelib/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib Class Hierarchy
-
+
diff --git a/docs/swervelib/parser/PIDFConfig.html b/docs/swervelib/parser/PIDFConfig.html
index af38b8e..8be7e19 100644
--- a/docs/swervelib/parser/PIDFConfig.html
+++ b/docs/swervelib/parser/PIDFConfig.html
@@ -1,11 +1,11 @@
-
+
PIDFConfig
-
+
diff --git a/docs/swervelib/parser/SwerveControllerConfiguration.html b/docs/swervelib/parser/SwerveControllerConfiguration.html
index 3119510..d72f808 100644
--- a/docs/swervelib/parser/SwerveControllerConfiguration.html
+++ b/docs/swervelib/parser/SwerveControllerConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveControllerConfiguration
-
+
diff --git a/docs/swervelib/parser/SwerveDriveConfiguration.html b/docs/swervelib/parser/SwerveDriveConfiguration.html
index 317aef5..e6503cb 100644
--- a/docs/swervelib/parser/SwerveDriveConfiguration.html
+++ b/docs/swervelib/parser/SwerveDriveConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveConfiguration
-
+
@@ -96,29 +96,24 @@ loadScripts(document, 'script');
-boolean
-
+int
+
-
Invert the imu measurements.
-
-int
-
-
Number of modules on the robot.
-edu.wpi.first.math.geometry.Translation2d[]
-
-
+
edu.wpi.first.math.geometry.Translation2d[]
+
+
-
-
-
+
+
+
-
-
-
+
+
+
Physical characteristics of the swerve drive from physicalproperties.json.
@@ -197,13 +192,6 @@ loadScripts(document, 'script');
-
-invertedIMU
-public boolean invertedIMU
-Invert the imu measurements.
-
-
-
moduleCount
public int moduleCount
diff --git a/docs/swervelib/parser/SwerveModuleConfiguration.html b/docs/swervelib/parser/SwerveModuleConfiguration.html
index 799a5ee..96bfda3 100644
--- a/docs/swervelib/parser/SwerveModuleConfiguration.html
+++ b/docs/swervelib/parser/SwerveModuleConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveModuleConfiguration
-
+
diff --git a/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html b/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html
index f9eb4a6..290ceea 100644
--- a/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html
+++ b/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html
@@ -1,11 +1,11 @@
-
+
SwerveModulePhysicalCharacteristics
-
+
diff --git a/docs/swervelib/parser/SwerveParser.html b/docs/swervelib/parser/SwerveParser.html
index 744795e..575f233 100644
--- a/docs/swervelib/parser/SwerveParser.html
+++ b/docs/swervelib/parser/SwerveParser.html
@@ -1,11 +1,11 @@
-
+
SwerveParser
-
+
diff --git a/docs/swervelib/parser/deserializer/PIDFRange.html b/docs/swervelib/parser/deserializer/PIDFRange.html
index 81fefd1..8abed05 100644
--- a/docs/swervelib/parser/deserializer/PIDFRange.html
+++ b/docs/swervelib/parser/deserializer/PIDFRange.html
@@ -1,11 +1,11 @@
-
+
PIDFRange
-
+
diff --git a/docs/swervelib/parser/deserializer/package-summary.html b/docs/swervelib/parser/deserializer/package-summary.html
index 69df7d2..5bc31b7 100644
--- a/docs/swervelib/parser/deserializer/package-summary.html
+++ b/docs/swervelib/parser/deserializer/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.deserializer
-
+
diff --git a/docs/swervelib/parser/deserializer/package-tree.html b/docs/swervelib/parser/deserializer/package-tree.html
index 052334e..3652089 100644
--- a/docs/swervelib/parser/deserializer/package-tree.html
+++ b/docs/swervelib/parser/deserializer/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.deserializer Class Hierarchy
-
+
diff --git a/docs/swervelib/parser/json/ControllerPropertiesJson.html b/docs/swervelib/parser/json/ControllerPropertiesJson.html
index 5929ab2..dadd8a1 100644
--- a/docs/swervelib/parser/json/ControllerPropertiesJson.html
+++ b/docs/swervelib/parser/json/ControllerPropertiesJson.html
@@ -1,11 +1,11 @@
-
+
ControllerPropertiesJson
-
+
diff --git a/docs/swervelib/parser/json/DeviceJson.html b/docs/swervelib/parser/json/DeviceJson.html
index 34ef88b..3b2c005 100644
--- a/docs/swervelib/parser/json/DeviceJson.html
+++ b/docs/swervelib/parser/json/DeviceJson.html
@@ -1,11 +1,11 @@
-
+
DeviceJson
-
+
diff --git a/docs/swervelib/parser/json/ModuleJson.html b/docs/swervelib/parser/json/ModuleJson.html
index 3b82299..778f372 100644
--- a/docs/swervelib/parser/json/ModuleJson.html
+++ b/docs/swervelib/parser/json/ModuleJson.html
@@ -1,11 +1,11 @@
-
+
ModuleJson
-
+
diff --git a/docs/swervelib/parser/json/MotorConfigDouble.html b/docs/swervelib/parser/json/MotorConfigDouble.html
index 28a0d43..6db66ec 100644
--- a/docs/swervelib/parser/json/MotorConfigDouble.html
+++ b/docs/swervelib/parser/json/MotorConfigDouble.html
@@ -1,11 +1,11 @@
-
+
MotorConfigDouble
-
+
diff --git a/docs/swervelib/parser/json/MotorConfigInt.html b/docs/swervelib/parser/json/MotorConfigInt.html
index cfe25cf..c1de910 100644
--- a/docs/swervelib/parser/json/MotorConfigInt.html
+++ b/docs/swervelib/parser/json/MotorConfigInt.html
@@ -1,11 +1,11 @@
-
+
MotorConfigInt
-
+
diff --git a/docs/swervelib/parser/json/PIDFPropertiesJson.html b/docs/swervelib/parser/json/PIDFPropertiesJson.html
index 2c93f2a..d1c613c 100644
--- a/docs/swervelib/parser/json/PIDFPropertiesJson.html
+++ b/docs/swervelib/parser/json/PIDFPropertiesJson.html
@@ -1,11 +1,11 @@
-
+
PIDFPropertiesJson
-
+
diff --git a/docs/swervelib/parser/json/PhysicalPropertiesJson.html b/docs/swervelib/parser/json/PhysicalPropertiesJson.html
index b19a270..6e49834 100644
--- a/docs/swervelib/parser/json/PhysicalPropertiesJson.html
+++ b/docs/swervelib/parser/json/PhysicalPropertiesJson.html
@@ -1,11 +1,11 @@
-
+
PhysicalPropertiesJson
-
+
diff --git a/docs/swervelib/parser/json/SwerveDriveJson.html b/docs/swervelib/parser/json/SwerveDriveJson.html
index ccf0e30..523b150 100644
--- a/docs/swervelib/parser/json/SwerveDriveJson.html
+++ b/docs/swervelib/parser/json/SwerveDriveJson.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveJson
-
+
diff --git a/docs/swervelib/parser/json/modules/BoolMotorJson.html b/docs/swervelib/parser/json/modules/BoolMotorJson.html
index 49c2057..de12bcb 100644
--- a/docs/swervelib/parser/json/modules/BoolMotorJson.html
+++ b/docs/swervelib/parser/json/modules/BoolMotorJson.html
@@ -1,11 +1,11 @@
-
+
BoolMotorJson
-
+
diff --git a/docs/swervelib/parser/json/modules/LocationJson.html b/docs/swervelib/parser/json/modules/LocationJson.html
index d855ee4..cbfc8f7 100644
--- a/docs/swervelib/parser/json/modules/LocationJson.html
+++ b/docs/swervelib/parser/json/modules/LocationJson.html
@@ -1,11 +1,11 @@
-
+
LocationJson
-
+
diff --git a/docs/swervelib/parser/json/modules/package-summary.html b/docs/swervelib/parser/json/modules/package-summary.html
index 905fd84..96640f1 100644
--- a/docs/swervelib/parser/json/modules/package-summary.html
+++ b/docs/swervelib/parser/json/modules/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.json.modules
-
+
diff --git a/docs/swervelib/parser/json/modules/package-tree.html b/docs/swervelib/parser/json/modules/package-tree.html
index e7da081..3f50049 100644
--- a/docs/swervelib/parser/json/modules/package-tree.html
+++ b/docs/swervelib/parser/json/modules/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.json.modules Class Hierarchy
-
+
diff --git a/docs/swervelib/parser/json/package-summary.html b/docs/swervelib/parser/json/package-summary.html
index 6806a9d..1438ef9 100644
--- a/docs/swervelib/parser/json/package-summary.html
+++ b/docs/swervelib/parser/json/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.json
-
+
diff --git a/docs/swervelib/parser/json/package-tree.html b/docs/swervelib/parser/json/package-tree.html
index 9ac0bde..fbd5c21 100644
--- a/docs/swervelib/parser/json/package-tree.html
+++ b/docs/swervelib/parser/json/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser.json Class Hierarchy
-
+
diff --git a/docs/swervelib/parser/package-summary.html b/docs/swervelib/parser/package-summary.html
index d442b77..6727b5a 100644
--- a/docs/swervelib/parser/package-summary.html
+++ b/docs/swervelib/parser/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser
-
+
diff --git a/docs/swervelib/parser/package-tree.html b/docs/swervelib/parser/package-tree.html
index 592a051..48acb1a 100644
--- a/docs/swervelib/parser/package-tree.html
+++ b/docs/swervelib/parser/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.parser Class Hierarchy
-
+
diff --git a/docs/swervelib/simulation/SwerveIMUSimulation.html b/docs/swervelib/simulation/SwerveIMUSimulation.html
index 7392438..9dd5092 100644
--- a/docs/swervelib/simulation/SwerveIMUSimulation.html
+++ b/docs/swervelib/simulation/SwerveIMUSimulation.html
@@ -1,11 +1,11 @@
-
+
SwerveIMUSimulation
-
+
diff --git a/docs/swervelib/simulation/SwerveModuleSimulation.html b/docs/swervelib/simulation/SwerveModuleSimulation.html
index b364c97..1146b63 100644
--- a/docs/swervelib/simulation/SwerveModuleSimulation.html
+++ b/docs/swervelib/simulation/SwerveModuleSimulation.html
@@ -1,11 +1,11 @@
-
+
SwerveModuleSimulation
-
+
diff --git a/docs/swervelib/simulation/package-summary.html b/docs/swervelib/simulation/package-summary.html
index 5c26d7d..cf0912c 100644
--- a/docs/swervelib/simulation/package-summary.html
+++ b/docs/swervelib/simulation/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.simulation
-
+
diff --git a/docs/swervelib/simulation/package-tree.html b/docs/swervelib/simulation/package-tree.html
index 88d6162..1f11d1a 100644
--- a/docs/swervelib/simulation/package-tree.html
+++ b/docs/swervelib/simulation/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.simulation Class Hierarchy
-
+
diff --git a/docs/swervelib/telemetry/Alert.AlertType.html b/docs/swervelib/telemetry/Alert.AlertType.html
index 7ccdbab..8868173 100644
--- a/docs/swervelib/telemetry/Alert.AlertType.html
+++ b/docs/swervelib/telemetry/Alert.AlertType.html
@@ -1,11 +1,11 @@
-
+
Alert.AlertType
-
+
diff --git a/docs/swervelib/telemetry/Alert.SendableAlerts.html b/docs/swervelib/telemetry/Alert.SendableAlerts.html
index 9fdf144..7222983 100644
--- a/docs/swervelib/telemetry/Alert.SendableAlerts.html
+++ b/docs/swervelib/telemetry/Alert.SendableAlerts.html
@@ -1,11 +1,11 @@
-
+
Alert.SendableAlerts
-
+
diff --git a/docs/swervelib/telemetry/Alert.html b/docs/swervelib/telemetry/Alert.html
index 2114971..97dd514 100644
--- a/docs/swervelib/telemetry/Alert.html
+++ b/docs/swervelib/telemetry/Alert.html
@@ -1,11 +1,11 @@
-
+
Alert
-
+
diff --git a/docs/swervelib/telemetry/SwerveDriveTelemetry.TelemetryVerbosity.html b/docs/swervelib/telemetry/SwerveDriveTelemetry.TelemetryVerbosity.html
index d8cda4b..e425238 100644
--- a/docs/swervelib/telemetry/SwerveDriveTelemetry.TelemetryVerbosity.html
+++ b/docs/swervelib/telemetry/SwerveDriveTelemetry.TelemetryVerbosity.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveTelemetry.TelemetryVerbosity
-
+
diff --git a/docs/swervelib/telemetry/SwerveDriveTelemetry.html b/docs/swervelib/telemetry/SwerveDriveTelemetry.html
index 323fc1c..a693275 100644
--- a/docs/swervelib/telemetry/SwerveDriveTelemetry.html
+++ b/docs/swervelib/telemetry/SwerveDriveTelemetry.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveTelemetry
-
+
diff --git a/docs/swervelib/telemetry/package-summary.html b/docs/swervelib/telemetry/package-summary.html
index 6619ce7..56a37f9 100644
--- a/docs/swervelib/telemetry/package-summary.html
+++ b/docs/swervelib/telemetry/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.telemetry
-
+
diff --git a/docs/swervelib/telemetry/package-tree.html b/docs/swervelib/telemetry/package-tree.html
index 5f987a8..b257599 100644
--- a/docs/swervelib/telemetry/package-tree.html
+++ b/docs/swervelib/telemetry/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.telemetry Class Hierarchy
-
+
diff --git a/swervelib/SwerveDrive.java b/swervelib/SwerveDrive.java
index 9f6d17d..9ee2352 100644
--- a/swervelib/SwerveDrive.java
+++ b/swervelib/SwerveDrive.java
@@ -1,7 +1,6 @@
package swervelib;
import edu.wpi.first.math.Matrix;
-import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
@@ -72,9 +71,12 @@ public class SwerveDrive
*/
private final Lock odometryLock = new ReentrantLock();
/**
- * Deadband for speeds in heading correction.
+ * Alert to recommend Tuner X if the configuration is compatible.
*/
- private double HEADING_CORRECTION_DEADBAND = 0.01;
+ private final Alert tunerXRecommendation = new Alert("Swerve Drive",
+ "Your Swerve Drive is compatible with Tuner X swerve generator, please consider using that instead of YAGSL. More information here!\n" +
+ "https://pro.docs.ctr-electronics.com/en/latest/docs/tuner/tuner-swerve/index.html",
+ AlertType.WARNING);
/**
* Field object.
*/
@@ -83,26 +85,6 @@ public class SwerveDrive
* Swerve controller for controlling heading of the robot.
*/
public SwerveController swerveController;
- /**
- * Standard deviation of encoders and gyroscopes, usually should not change. (meters of position and degrees of
- * rotation)
- */
- public Matrix stateStdDevs = VecBuilder.fill(0.1,
- 0.1,
- 0.1);
- /**
- * The standard deviation of the vision measurement, for best accuracy calculate the standard deviation at 2 or more
- * points and fit a line to it and modify this using {@link SwerveDrive#addVisionMeasurement(Pose2d, double, Matrix)}
- * with the calculated optimal standard deviation. (Units should be meters per pixel). By optimizing this you can get
- * vision accurate to inches instead of feet.
- */
- public Matrix visionMeasurementStdDevs = VecBuilder.fill(0.9,
- 0.9,
- 0.9);
- /**
- * Invert odometry readings of drive motor positions, used as a patch for debugging currently.
- */
- public boolean invertOdometry = false;
/**
* Correct chassis velocity in {@link SwerveDrive#drive(Translation2d, double, boolean, boolean)} using 254's
* correction.
@@ -112,6 +94,10 @@ public class SwerveDrive
* Whether to correct heading when driving translationally. Set to true to enable.
*/
public boolean headingCorrection = false;
+ /**
+ * Deadband for speeds in heading correction.
+ */
+ private double HEADING_CORRECTION_DEADBAND = 0.01;
/**
* Whether heading correction PID is currently active.
*/
@@ -144,13 +130,6 @@ public class SwerveDrive
* Maximum speed of the robot in meters per second.
*/
private double maxSpeedMPS;
- /**
- * Alert to recommend Tuner X if the configuration is compatible.
- */
- private final Alert tunerXRecommendation = new Alert("Swerve Drive",
- "Your Swerve Drive is compatible with Tuner X swerve generator, please consider using that instead of YAGSL. More information here!\n" +
- "https://pro.docs.ctr-electronics.com/en/latest/docs/tuner/tuner-swerve/index.html",
- AlertType.WARNING);
/**
* Creates a new swerve drivebase subsystem. Robot is controlled via the {@link SwerveDrive#drive} method, or via the
@@ -194,9 +173,8 @@ public class SwerveDrive
kinematics,
getYaw(),
getModulePositions(),
- new Pose2d(new Translation2d(0, 0), Rotation2d.fromDegrees(0)),
- stateStdDevs,
- visionMeasurementStdDevs); // x,y,heading in radians; Vision measurement std dev, higher=less weight
+ new Pose2d(new Translation2d(0, 0),
+ Rotation2d.fromDegrees(0))); // x,y,heading in radians; Vision measurement std dev, higher=less weight
zeroGyro();
@@ -308,6 +286,16 @@ public class SwerveDrive
}
}
+ /**
+ * Fetch the latest odometry heading, should be trusted over {@link SwerveDrive#getYaw()}.
+ *
+ * @return {@link Rotation2d} of the robot heading.
+ */
+ public Rotation2d getOdometryHeading()
+ {
+ return swerveDrivePoseEstimator.getEstimatedPosition().getRotation();
+ }
+
/**
* Set the heading correction capabilities of YAGSL.
*
@@ -337,7 +325,7 @@ public class SwerveDrive
*/
public void driveFieldOriented(ChassisSpeeds velocity)
{
- ChassisSpeeds fieldOrientedVelocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getYaw());
+ ChassisSpeeds fieldOrientedVelocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getOdometryHeading());
drive(fieldOrientedVelocity);
}
@@ -349,7 +337,7 @@ public class SwerveDrive
*/
public void driveFieldOriented(ChassisSpeeds velocity, Translation2d centerOfRotationMeters)
{
- ChassisSpeeds fieldOrientedVelocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getYaw());
+ ChassisSpeeds fieldOrientedVelocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getOdometryHeading());
drive(fieldOrientedVelocity, centerOfRotationMeters);
}
@@ -401,7 +389,7 @@ public class SwerveDrive
ChassisSpeeds velocity =
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(
- translation.getX(), translation.getY(), rotation, getYaw())
+ translation.getX(), translation.getY(), rotation, getOdometryHeading())
: new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
drive(velocity, isOpenLoop, centerOfRotationMeters);
@@ -430,7 +418,7 @@ public class SwerveDrive
ChassisSpeeds velocity =
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(
- translation.getX(), translation.getY(), rotation, getYaw())
+ translation.getX(), translation.getY(), rotation, getOdometryHeading())
: new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
drive(velocity, isOpenLoop, new Translation2d());
@@ -466,11 +454,11 @@ public class SwerveDrive
{
if (!correctionEnabled)
{
- lastHeadingRadians = getYaw().getRadians();
+ lastHeadingRadians = getOdometryHeading().getRadians();
correctionEnabled = true;
}
velocity.omegaRadiansPerSecond =
- swerveController.headingCalculate(lastHeadingRadians, getYaw().getRadians());
+ swerveController.headingCalculate(lastHeadingRadians, getOdometryHeading().getRadians());
} else
{
correctionEnabled = false;
@@ -623,7 +611,7 @@ public class SwerveDrive
// angle
// given as the robot angle reverses the direction of rotation, and the conversion is reversed.
return ChassisSpeeds.fromFieldRelativeSpeeds(
- kinematics.toChassisSpeeds(getStates()), getYaw().unaryMinus());
+ kinematics.toChassisSpeeds(getStates()), getOdometryHeading().unaryMinus());
}
/**
@@ -646,7 +634,7 @@ public class SwerveDrive
public void resetOdometry(Pose2d pose)
{
odometryLock.lock();
- swerveDrivePoseEstimator.resetPosition(pose.getRotation(), getModulePositions(), pose);
+ swerveDrivePoseEstimator.resetPosition(getYaw(), getModulePositions(), pose);
odometryLock.unlock();
kinematics.toSwerveModuleStates(ChassisSpeeds.fromFieldRelativeSpeeds(0, 0, 0, pose.getRotation()));
}
@@ -680,8 +668,7 @@ public class SwerveDrive
}
/**
- * Gets the current module positions (azimuth and wheel position (meters)). Inverts the distance from each module if
- * {@link #invertOdometry} is true.
+ * Gets the current module positions (azimuth and wheel position (meters)).
*
* @return A list of SwerveModulePositions containg the current module positions
*/
@@ -692,10 +679,6 @@ public class SwerveDrive
for (SwerveModule module : swerveModules)
{
positions[module.moduleNumber] = module.getPosition();
- if (invertOdometry)
- {
- positions[module.moduleNumber].distanceMeters *= -1;
- }
}
return positions;
}
@@ -729,9 +712,7 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- return swerveDriveConfiguration.invertedIMU
- ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getZ())
- : Rotation2d.fromRadians(imu.getRotation3d().getZ());
+ return Rotation2d.fromRadians(imu.getRotation3d().getZ());
} else
{
return simIMU.getYaw();
@@ -748,9 +729,7 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- return swerveDriveConfiguration.invertedIMU
- ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getY())
- : Rotation2d.fromRadians(imu.getRotation3d().getY());
+ return Rotation2d.fromRadians(imu.getRotation3d().getY());
} else
{
return simIMU.getPitch();
@@ -767,9 +746,7 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- return swerveDriveConfiguration.invertedIMU
- ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getX())
- : Rotation2d.fromRadians(imu.getRotation3d().getX());
+ return Rotation2d.fromRadians(imu.getRotation3d().getX());
} else
{
return simIMU.getRoll();
@@ -786,9 +763,7 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- return swerveDriveConfiguration.invertedIMU
- ? imu.getRotation3d().unaryMinus()
- : imu.getRotation3d();
+ return imu.getRotation3d();
} else
{
return simIMU.getGyroRotation3d();
@@ -953,7 +928,7 @@ public class SwerveDrive
SwerveDriveTelemetry.measuredChassisSpeeds[1] = measuredChassisSpeeds.vyMetersPerSecond;
SwerveDriveTelemetry.measuredChassisSpeeds[0] = measuredChassisSpeeds.vxMetersPerSecond;
SwerveDriveTelemetry.measuredChassisSpeeds[2] = Math.toDegrees(measuredChassisSpeeds.omegaRadiansPerSecond);
- SwerveDriveTelemetry.robotRotation = getYaw().getDegrees();
+ SwerveDriveTelemetry.robotRotation = getOdometryHeading().getDegrees();
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
@@ -969,7 +944,8 @@ public class SwerveDrive
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
module.updateTelemetry();
- SmartDashboard.putNumber("Adjusted IMU Yaw", getYaw().getDegrees());
+ SmartDashboard.putNumber("Raw IMU Yaw", getYaw().getDegrees());
+ SmartDashboard.putNumber("Adjusted IMU Yaw", getOdometryHeading().getDegrees());
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
@@ -1027,28 +1003,6 @@ public class SwerveDrive
}
}
- /**
- * Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
- * the given timestamp of the vision measurement. IT IS HIGHLY RECOMMENDED TO UPDATE YOUR GYROSCOPE OFFSET
- * AFTER USING THIS FUNCTION! To update your gyroscope readings directly use
- * {@link SwerveDrive#setGyroOffset(Rotation3d)}.
- *
- * @param robotPose Robot {@link Pose2d} as measured by vision.
- * @param timestamp Timestamp the measurement was taken as time since startup, should be taken from
- * {@link Timer#getFPGATimestamp()} or similar sources.
- */
- public void addVisionMeasurement(Pose2d robotPose, double timestamp)
- {
- odometryLock.lock();
- swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp);
- Pose2d newOdometry = new Pose2d(swerveDrivePoseEstimator.getEstimatedPosition().getTranslation(),
- robotPose.getRotation());
- odometryLock.unlock();
-
- setGyroOffset(new Rotation3d(0, 0, robotPose.getRotation().getRadians()));
- resetOdometry(newOdometry);
- }
-
/**
* Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
* the given timestamp of the vision measurement.
@@ -1066,8 +1020,31 @@ public class SwerveDrive
public void addVisionMeasurement(Pose2d robotPose, double timestamp,
Matrix visionMeasurementStdDevs)
{
- this.visionMeasurementStdDevs = visionMeasurementStdDevs;
- addVisionMeasurement(robotPose, timestamp);
+ odometryLock.lock();
+ swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp, visionMeasurementStdDevs);
+ odometryLock.unlock();
+ }
+
+ /**
+ * Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
+ * the given timestamp of the vision measurement. IT IS HIGHLY RECOMMENDED TO UPDATE YOUR GYROSCOPE OFFSET
+ * AFTER USING THIS FUNCTION! To update your gyroscope readings directly use
+ * {@link SwerveDrive#setGyroOffset(Rotation3d)}.
+ *
+ * @param robotPose Robot {@link Pose2d} as measured by vision.
+ * @param timestamp Timestamp the measurement was taken as time since startup, should be taken from
+ * {@link Timer#getFPGATimestamp()} or similar sources.
+ */
+ public void addVisionMeasurement(Pose2d robotPose, double timestamp)
+ {
+ odometryLock.lock();
+ swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp);
+// Pose2d newOdometry = new Pose2d(swerveDrivePoseEstimator.getEstimatedPosition().getTranslation(),
+// robotPose.getRotation());
+ odometryLock.unlock();
+
+// setGyroOffset(new Rotation3d(0, 0, robotPose.getRotation().getRadians()));
+// resetOdometry(newOdometry);
}
diff --git a/swervelib/imu/ADIS16448Swerve.java b/swervelib/imu/ADIS16448Swerve.java
index d60f8c6..4295d48 100644
--- a/swervelib/imu/ADIS16448Swerve.java
+++ b/swervelib/imu/ADIS16448Swerve.java
@@ -19,7 +19,11 @@ public class ADIS16448Swerve extends SwerveIMU
/**
* Offset for the ADIS16448.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Construct the ADIS16448 imu and reset default configurations. Publish the gyro to the SmartDashboard.
@@ -60,6 +64,16 @@ public class ADIS16448Swerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -67,9 +81,10 @@ public class ADIS16448Swerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
- return new Rotation3d(Math.toRadians(-imu.getGyroAngleX()),
- Math.toRadians(-imu.getGyroAngleY()),
- Math.toRadians(-imu.getGyroAngleZ()));
+ Rotation3d reading = new Rotation3d(Math.toRadians(-imu.getGyroAngleX()),
+ Math.toRadians(-imu.getGyroAngleY()),
+ Math.toRadians(-imu.getGyroAngleZ()));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/ADIS16470Swerve.java b/swervelib/imu/ADIS16470Swerve.java
index 562bbd1..94a31b7 100644
--- a/swervelib/imu/ADIS16470Swerve.java
+++ b/swervelib/imu/ADIS16470Swerve.java
@@ -20,7 +20,11 @@ public class ADIS16470Swerve extends SwerveIMU
/**
* Offset for the ADIS16470.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Construct the ADIS16470 imu and reset default configurations. Publish the gyro to the SmartDashboard.
@@ -62,6 +66,16 @@ public class ADIS16470Swerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -69,7 +83,8 @@ public class ADIS16470Swerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
- return new Rotation3d(0, 0, Math.toRadians(-imu.getAngle(IMUAxis.kYaw)));
+ Rotation3d reading = new Rotation3d(0, 0, Math.toRadians(-imu.getAngle(IMUAxis.kYaw)));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/ADXRS450Swerve.java b/swervelib/imu/ADXRS450Swerve.java
index f313fb0..718a896 100644
--- a/swervelib/imu/ADXRS450Swerve.java
+++ b/swervelib/imu/ADXRS450Swerve.java
@@ -19,7 +19,11 @@ public class ADXRS450Swerve extends SwerveIMU
/**
* Offset for the ADXRS450.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Construct the ADXRS450 imu and reset default configurations. Publish the gyro to the SmartDashboard.
@@ -60,6 +64,16 @@ public class ADXRS450Swerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -67,7 +81,8 @@ public class ADXRS450Swerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
- return new Rotation3d(0, 0, Math.toRadians(-imu.getAngle()));
+ Rotation3d reading = new Rotation3d(0, 0, Math.toRadians(-imu.getAngle()));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/AnalogGyroSwerve.java b/swervelib/imu/AnalogGyroSwerve.java
index 590666f..d104a0f 100644
--- a/swervelib/imu/AnalogGyroSwerve.java
+++ b/swervelib/imu/AnalogGyroSwerve.java
@@ -19,7 +19,11 @@ public class AnalogGyroSwerve extends SwerveIMU
/**
* Offset for the analog gyro.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Analog port in which the gyroscope is connected. Can only be attached to analog ports 0 or 1.
@@ -67,6 +71,16 @@ public class AnalogGyroSwerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -74,7 +88,8 @@ public class AnalogGyroSwerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
- return new Rotation3d(0, 0, Math.toRadians(-gyro.getAngle()));
+ Rotation3d reading = new Rotation3d(0, 0, Math.toRadians(-gyro.getAngle()));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/NavXSwerve.java b/swervelib/imu/NavXSwerve.java
index 339c0e9..790d6b2 100644
--- a/swervelib/imu/NavXSwerve.java
+++ b/swervelib/imu/NavXSwerve.java
@@ -23,7 +23,11 @@ public class NavXSwerve extends SwerveIMU
/**
* Offset for the NavX.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* An {@link Alert} for if there is an error instantiating the NavX.
*/
@@ -124,6 +128,16 @@ public class NavXSwerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -132,7 +146,7 @@ public class NavXSwerve extends SwerveIMU
@Override
public Rotation3d getRawRotation3d()
{
- return gyro.getRotation3d();
+ return invertedIMU ? gyro.getRotation3d().unaryMinus() : gyro.getRotation3d();
}
/**
diff --git a/swervelib/imu/Pigeon2Swerve.java b/swervelib/imu/Pigeon2Swerve.java
index 25a41ea..d68e4f7 100644
--- a/swervelib/imu/Pigeon2Swerve.java
+++ b/swervelib/imu/Pigeon2Swerve.java
@@ -23,7 +23,11 @@ public class Pigeon2Swerve extends SwerveIMU
/**
* Offset for the Pigeon 2.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Generate the SwerveIMU for pigeon.
@@ -79,6 +83,16 @@ public class Pigeon2Swerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -88,14 +102,15 @@ public class Pigeon2Swerve extends SwerveIMU
public Rotation3d getRawRotation3d()
{
// TODO: Switch to suppliers.
- StatusSignal w = imu.getQuatW();
- StatusSignal x = imu.getQuatX();
- StatusSignal y = imu.getQuatY();
- StatusSignal z = imu.getQuatZ();
- return new Rotation3d(new Quaternion(w.refresh().getValue(),
- x.refresh().getValue(),
- y.refresh().getValue(),
- z.refresh().getValue()));
+ StatusSignal w = imu.getQuatW();
+ StatusSignal x = imu.getQuatX();
+ StatusSignal y = imu.getQuatY();
+ StatusSignal z = imu.getQuatZ();
+ Rotation3d reading = new Rotation3d(new Quaternion(w.refresh().getValue(),
+ x.refresh().getValue(),
+ y.refresh().getValue(),
+ z.refresh().getValue()));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/PigeonSwerve.java b/swervelib/imu/PigeonSwerve.java
index 44fafcc..b9bbcc5 100644
--- a/swervelib/imu/PigeonSwerve.java
+++ b/swervelib/imu/PigeonSwerve.java
@@ -20,7 +20,11 @@ public class PigeonSwerve extends SwerveIMU
/**
* Offset for the Pigeon.
*/
- private Rotation3d offset = new Rotation3d();
+ private Rotation3d offset = new Rotation3d();
+ /**
+ * Inversion for the gyro
+ */
+ private boolean invertedIMU = false;
/**
* Generate the SwerveIMU for pigeon.
@@ -62,6 +66,16 @@ public class PigeonSwerve extends SwerveIMU
this.offset = offset;
}
+ /**
+ * Set the gyro to invert its default direction
+ *
+ * @param invertIMU invert gyro direction
+ */
+ public void setInverted(boolean invertIMU)
+ {
+ invertedIMU = invertIMU;
+ }
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
@@ -72,7 +86,8 @@ public class PigeonSwerve extends SwerveIMU
{
double[] wxyz = new double[4];
imu.get6dQuaternion(wxyz);
- return new Rotation3d(new Quaternion(wxyz[0], wxyz[1], wxyz[2], wxyz[3]));
+ Rotation3d reading = new Rotation3d(new Quaternion(wxyz[0], wxyz[1], wxyz[2], wxyz[3]));
+ return invertedIMU ? reading.unaryMinus() : reading;
}
/**
diff --git a/swervelib/imu/SwerveIMU.java b/swervelib/imu/SwerveIMU.java
index 11b39da..dd9a727 100644
--- a/swervelib/imu/SwerveIMU.java
+++ b/swervelib/imu/SwerveIMU.java
@@ -27,6 +27,13 @@ public abstract class SwerveIMU
*/
public abstract void setOffset(Rotation3d offset);
+ /**
+ * Set the gyro to invert its default direction.
+ *
+ * @param invertIMU gyro direction
+ */
+ public abstract void setInverted(boolean invertIMU);
+
/**
* Fetch the {@link Rotation3d} from the IMU without any zeroing. Robot relative.
*
diff --git a/swervelib/motors/TalonFXSwerve.java b/swervelib/motors/TalonFXSwerve.java
index 29cdf97..cf7effb 100644
--- a/swervelib/motors/TalonFXSwerve.java
+++ b/swervelib/motors/TalonFXSwerve.java
@@ -33,14 +33,14 @@ public class TalonFXSwerve extends SwerveMotor
* Velocity voltage setter for controlling drive motor.
*/
private final VelocityVoltage m_velocityVoltageSetter = new VelocityVoltage(0);
- /**
- * Conversion factor for the motor.
- */
- private double conversionFactor;
/**
* TalonFX motor controller.
*/
TalonFX motor;
+ /**
+ * Conversion factor for the motor.
+ */
+ private double conversionFactor;
/**
* Current TalonFX configuration.
*/
diff --git a/swervelib/parser/SwerveDriveConfiguration.java b/swervelib/parser/SwerveDriveConfiguration.java
index 4cebfb8..e5434de 100644
--- a/swervelib/parser/SwerveDriveConfiguration.java
+++ b/swervelib/parser/SwerveDriveConfiguration.java
@@ -19,10 +19,6 @@ public class SwerveDriveConfiguration
* Swerve IMU
*/
public SwerveIMU imu;
- /**
- * Invert the imu measurements.
- */
- public boolean invertedIMU = false;
/**
* Number of modules on the robot.
*/
@@ -54,7 +50,7 @@ public class SwerveDriveConfiguration
{
this.moduleCount = moduleConfigs.length;
this.imu = swerveIMU;
- this.invertedIMU = invertedIMU;
+ swerveIMU.setInverted(invertedIMU);
this.modules = createModules(moduleConfigs, driveFeedforward);
this.moduleLocationsMeters = new Translation2d[moduleConfigs.length];
for (SwerveModule module : modules)
@@ -92,10 +88,11 @@ public class SwerveDriveConfiguration
Translation2d centerOfModules = moduleLocationsMeters[0];
//Calculate the Center by adding all module offsets together.
- for(int i=1; i groups = new HashMap();
+ private static Map groups = new HashMap();
/**
* Type of the Alert to raise.
*/
- private final AlertType type;
+ private final AlertType type;
/**
* Activation state of alert.
*/
- private boolean active = false;
+ private boolean active = false;
/**
* When the alert was raised.
*/
- private double activeStartTime = 0.0;
+ private double activeStartTime = 0.0;
/**
* Text of the alert.
*/
- private String text;
+ private String text;
/**
* Creates a new Alert in the default group - "Alerts". If this is the first to be instantiated, the appropriate
@@ -213,6 +213,7 @@ public class Alert
/**
* Get alerts based off of type.
+ *
* @param type Type of alert to fetch.
* @return Active alert strings.
*/