diff --git a/docs/allclasses-index.html b/docs/allclasses-index.html index f8825ed..124f19a 100644 --- a/docs/allclasses-index.html +++ b/docs/allclasses-index.html @@ -1,11 +1,11 @@
- +Canandcoder from ReduxRobotics absolute encoder, attached through the CAN bus.Canandmag from ReduxRobotics absolute encoder, attached through the CAN bus.Canandcoder from ReduxRobotics absolute encoder, attached through the CAN bus.Canandmag from ReduxRobotics absolute encoder, attached through the CAN bus.CanandcoderCanandmagCanandcoder representing the CANandCoder on the CAN bus.Canandmag representing the CANandCoder on the CAN bus.ADXRS450_Gyro device to read the current headings from.voidsetVisionMeasurementStdDevs(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> visionMeasurementStdDevs) voidvoidvoidvoidupdateCacheValidityPeriods(long imu,
+void
+updateCacheValidityPeriods(long imu,
long driveMotor,
long absoluteEncoder)
-
+
Update the cache validity period for the robot.
-void
-
-
+void
+
+
Update odometry should be run every loop.
-void
-zeroGyro()
-
+void
+zeroGyro()
+
Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
@@ -1360,6 +1365,20 @@ loadScripts(document, 'script');
+
+setVisionMeasurementStdDevs
+public void setVisionMeasurementStdDevs(edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> visionMeasurementStdDevs)
+Sets the pose estimator's trust of global measurements. This might be used to change trust in vision measurements
+ after the autonomous period, or to change trust as distance to a vision target increases.
+
+- Parameters:
+visionMeasurementStdDevs - Standard deviations of the vision measurements. Increase these numbers to trust
+ global measurements from vision less. This matrix is in the form [x, y, theta],
+ with units in meters and radians.
+
+
+
+
addVisionMeasurement
public void addVisionMeasurement(edu.wpi.first.math.geometry.Pose2d robotPose,
diff --git a/docs/swervelib/SwerveDriveTest.html b/docs/swervelib/SwerveDriveTest.html
index 3d1343d..9f6ceae 100644
--- a/docs/swervelib/SwerveDriveTest.html
+++ b/docs/swervelib/SwerveDriveTest.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveTest
-
+
diff --git a/docs/swervelib/SwerveModule.html b/docs/swervelib/SwerveModule.html
index b39a9c3..68169d9 100644
--- a/docs/swervelib/SwerveModule.html
+++ b/docs/swervelib/SwerveModule.html
@@ -1,11 +1,11 @@
-
+
SwerveModule
-
+
@@ -425,6 +425,13 @@ loadScripts(document, 'script');
+
+moduleNumber
+public final int moduleNumber
+Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
+
+
+
angleMotor
@@ -502,13 +509,6 @@ loadScripts(document, 'script');
-
-moduleNumber
-public final int moduleNumber
-Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
-
-
-
maxSpeed
public double maxSpeed
diff --git a/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html b/docs/swervelib/encoders/AnalogAbsoluteEncoderSwerve.html
index 844de42..a6d0b15 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 445030b..08f7db9 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 1131506..5d33121 100644
--- a/docs/swervelib/encoders/CanAndCoderSwerve.html
+++ b/docs/swervelib/encoders/CanAndCoderSwerve.html
@@ -1,11 +1,11 @@
-
+
CanAndCoderSwerve
-
+
@@ -80,7 +80,7 @@ loadScripts(document, 'script');
-HELIUM Canandcoder from ReduxRobotics absolute encoder, attached through the CAN bus.
+HELIUM Canandmag from ReduxRobotics absolute encoder, attached through the CAN bus.
@@ -93,10 +93,10 @@ loadScripts(document, 'script');
Modifier and Type
Field
Description
-com.reduxrobotics.sensors.canandcoder.Canandcoder
+com.reduxrobotics.sensors.canandmag.Canandmag
-The Canandcoder representing the CANandCoder on the CAN bus.
+The Canandmag representing the CANandCoder on the CAN bus.
@@ -114,7 +114,7 @@ loadScripts(document, 'script');
Description
CanAndCoderSwerve(int canid)
-Create the Canandcoder
+Create the Canandmag
@@ -185,8 +185,8 @@ loadScripts(document, 'script');
encoder
-public com.reduxrobotics.sensors.canandcoder.Canandcoder encoder
-The Canandcoder representing the CANandCoder on the CAN bus.
+public com.reduxrobotics.sensors.canandmag.Canandmag encoder
+The Canandmag representing the CANandCoder on the CAN bus.
@@ -201,7 +201,7 @@ loadScripts(document, 'script');
CanAndCoderSwerve
public CanAndCoderSwerve(int canid)
-Create the Canandcoder
+Create the Canandmag
- Parameters:
canid - The CAN ID whenever the CANandCoder is operating on the CANBus.
diff --git a/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html b/docs/swervelib/encoders/PWMDutyCycleEncoderSwerve.html
index bb9dc3c..7efad6c 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 572dc2d..248c2dc 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 8f31f43..aded2db 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 543fd53..06594fb 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 5221ba1..e39e21b 100644
--- a/docs/swervelib/encoders/package-summary.html
+++ b/docs/swervelib/encoders/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.encoders
-
+
@@ -90,7 +90,7 @@ loadScripts(document, 'script');
-HELIUM Canandcoder from ReduxRobotics absolute encoder, attached through the CAN bus.
+HELIUM Canandmag from ReduxRobotics absolute encoder, attached through the CAN bus.
diff --git a/docs/swervelib/encoders/package-tree.html b/docs/swervelib/encoders/package-tree.html
index 1038f40..511b033 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 878fcb3..836a1f9 100644
--- a/docs/swervelib/imu/ADIS16448Swerve.html
+++ b/docs/swervelib/imu/ADIS16448Swerve.html
@@ -1,11 +1,11 @@
-
+
ADIS16448Swerve
-
+
@@ -157,24 +157,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -327,6 +332,19 @@ loadScripts(document, 'script');
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+
getIMU
diff --git a/docs/swervelib/imu/ADIS16470Swerve.html b/docs/swervelib/imu/ADIS16470Swerve.html
index f198bc3..26351b9 100644
--- a/docs/swervelib/imu/ADIS16470Swerve.html
+++ b/docs/swervelib/imu/ADIS16470Swerve.html
@@ -1,11 +1,11 @@
-
+
ADIS16470Swerve
-
+
@@ -157,24 +157,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -327,6 +332,19 @@ loadScripts(document, 'script');
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+
getIMU
diff --git a/docs/swervelib/imu/ADXRS450Swerve.html b/docs/swervelib/imu/ADXRS450Swerve.html
index 8439f7e..c42114b 100644
--- a/docs/swervelib/imu/ADXRS450Swerve.html
+++ b/docs/swervelib/imu/ADXRS450Swerve.html
@@ -1,11 +1,11 @@
-
+
ADXRS450Swerve
-
+
@@ -157,24 +157,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -327,6 +332,19 @@ loadScripts(document, 'script');
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+
getIMU
diff --git a/docs/swervelib/imu/AnalogGyroSwerve.html b/docs/swervelib/imu/AnalogGyroSwerve.html
index 8e7ec41..1970099 100644
--- a/docs/swervelib/imu/AnalogGyroSwerve.html
+++ b/docs/swervelib/imu/AnalogGyroSwerve.html
@@ -1,11 +1,11 @@
-
+
AnalogGyroSwerve
-
+
@@ -94,7 +94,7 @@ loadScripts(document, 'script');
Field
Description
private final edu.wpi.first.wpilibj.AnalogGyro
-
+
Gyroscope object.
@@ -157,24 +157,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -195,9 +200,9 @@ loadScripts(document, 'script');
Field Details
-
-
-gyro
-private final edu.wpi.first.wpilibj.AnalogGyro gyro
+
+imu
+private final edu.wpi.first.wpilibj.AnalogGyro imu
Gyroscope object.
@@ -331,6 +336,19 @@ loadScripts(document, 'script');
-
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+-
getIMU
diff --git a/docs/swervelib/imu/NavXSwerve.html b/docs/swervelib/imu/NavXSwerve.html
index b4afc1c..38f53bf 100644
--- a/docs/swervelib/imu/NavXSwerve.html
+++ b/docs/swervelib/imu/NavXSwerve.html
@@ -1,11 +1,11 @@
-
+
NavXSwerve
-
+
@@ -94,7 +94,7 @@ loadScripts(document, 'script');
Field
Description
private com.kauailabs.navx.frc.AHRS
-
+
NavX IMU.
@@ -170,24 +170,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -208,9 +213,9 @@ loadScripts(document, 'script');
Field Details
-
-
-gyro
-private com.kauailabs.navx.frc.AHRS gyro
+
+imu
+private com.kauailabs.navx.frc.AHRS imu
NavX IMU.
@@ -373,6 +378,19 @@ loadScripts(document, 'script');
-
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+-
getIMU
diff --git a/docs/swervelib/imu/Pigeon2Swerve.html b/docs/swervelib/imu/Pigeon2Swerve.html
index 355eebb..7f84746 100644
--- a/docs/swervelib/imu/Pigeon2Swerve.html
+++ b/docs/swervelib/imu/Pigeon2Swerve.html
@@ -1,11 +1,11 @@
-
+
Pigeon2Swerve
-
+
@@ -167,24 +167,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -361,6 +366,19 @@ loadScripts(document, 'script');
-
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+-
getIMU
diff --git a/docs/swervelib/imu/PigeonSwerve.html b/docs/swervelib/imu/PigeonSwerve.html
index 23e10d7..10cf863 100644
--- a/docs/swervelib/imu/PigeonSwerve.html
+++ b/docs/swervelib/imu/PigeonSwerve.html
@@ -1,11 +1,11 @@
-
+
PigeonSwerve
-
+
@@ -157,24 +157,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-edu.wpi.first.math.geometry.Rotation3d
-
+double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-void
-setInverted(boolean invertIMU)
-
+void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction
-void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -331,6 +336,19 @@ loadScripts(document, 'script');
-
+
+getRate
+public double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+-
getIMU
diff --git a/docs/swervelib/imu/SwerveIMU.html b/docs/swervelib/imu/SwerveIMU.html
index 6d861ee..675cf0c 100644
--- a/docs/swervelib/imu/SwerveIMU.html
+++ b/docs/swervelib/imu/SwerveIMU.html
@@ -1,11 +1,11 @@
-
+
SwerveIMU
-
+
@@ -130,24 +130,29 @@ loadScripts(document, 'script');
Get the instantiated IMU object.
-abstract edu.wpi.first.math.geometry.Rotation3d
-
+abstract double
+getRate()
-Fetch the Rotation3d from the IMU without any zeroing.
+Fetch the rotation rate from the IMU in degrees per second.
abstract edu.wpi.first.math.geometry.Rotation3d
-
+
+Fetch the Rotation3d from the IMU without any zeroing.
+
+abstract edu.wpi.first.math.geometry.Rotation3d
+
+
Fetch the Rotation3d from the IMU.
-abstract void
-setInverted(boolean invertIMU)
-
+abstract void
+setInverted(boolean invertIMU)
+
Set the gyro to invert its default direction.
-abstract void
-setOffset(edu.wpi.first.math.geometry.Rotation3d offset)
-
@@ -252,6 +257,17 @@ loadScripts(document, 'script');
-
+
+getRate
+public abstract double getRate()
+Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+
+
+
+-
getIMU
diff --git a/docs/swervelib/imu/package-summary.html b/docs/swervelib/imu/package-summary.html
index 3510973..7245e95 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 4e761bc..328a52a 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 5fa69e7..21355ea 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 99a995c..84594b6 100644
--- a/docs/swervelib/math/SwerveMath.html
+++ b/docs/swervelib/math/SwerveMath.html
@@ -1,11 +1,11 @@
-
+
SwerveMath
-
+
@@ -505,7 +505,7 @@ loadScripts(document, 'script');
double newAngle)
Put an angle within the 360 deg scope of a reference. For example, given a scope reference of 756 degrees, assumes
the full scope is (720-1080), and places an angle of 22 degrees into it, returning 742 deg.
-
+
A more formal definition: returns the closest angle n to scopeReference such that n is
congruent to newAngle.
diff --git a/docs/swervelib/math/package-summary.html b/docs/swervelib/math/package-summary.html
index bfe2d16..ab4749d 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 eb379d6..798fffd 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 3c3eb62..2642abc 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 63984d8..37447f6 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 d1cc3e1..9455d16 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 d19d250..d887e5d 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 89d5f3a..1976914 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 f27ff7e..bdc398f 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 069b1f6..b7df862 100644
--- a/docs/swervelib/motors/TalonFXSwerve.html
+++ b/docs/swervelib/motors/TalonFXSwerve.html
@@ -1,11 +1,11 @@
-
+
TalonFXSwerve
-
+
diff --git a/docs/swervelib/motors/TalonSRXSwerve.html b/docs/swervelib/motors/TalonSRXSwerve.html
index 78beac7..01a38da 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 19940c5..29ac69e 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 f0b9993..6deb9b1 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 49ef38b..6fb2879 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 2155559..e11d940 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/Cache.html b/docs/swervelib/parser/Cache.html
index 493c949..354056d 100644
--- a/docs/swervelib/parser/Cache.html
+++ b/docs/swervelib/parser/Cache.html
@@ -1,11 +1,11 @@
-
+
Cache
-
+
diff --git a/docs/swervelib/parser/PIDFConfig.html b/docs/swervelib/parser/PIDFConfig.html
index 15517fc..9ba1551 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 07195b6..451cb00 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 32395de..07db490 100644
--- a/docs/swervelib/parser/SwerveDriveConfiguration.html
+++ b/docs/swervelib/parser/SwerveDriveConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveConfiguration
-
+
@@ -178,6 +178,13 @@ loadScripts(document, 'script');
Field Details
-
+
+moduleCount
+public final int moduleCount
+Number of modules on the robot.
+
+
+-
moduleLocationsMeters
public edu.wpi.first.math.geometry.Translation2d[] moduleLocationsMeters
@@ -192,13 +199,6 @@ loadScripts(document, 'script');
-
-
-moduleCount
-public final int moduleCount
-Number of modules on the robot.
-
-
--
modules
diff --git a/docs/swervelib/parser/SwerveModuleConfiguration.html b/docs/swervelib/parser/SwerveModuleConfiguration.html
index 19a6181..08031a5 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 9559a93..402515b 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 33cf411..e1bd760 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 f60e329..408791c 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 3c10a73..b5fc302 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 b042ed1..4a7d9fc 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 170b454..cade3c9 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 9efe62c..eb4fe72 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 044086e..317fd0f 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 5adbb05..2fdaaed 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 177dfd4..ecaee49 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 f9cfb4c..bf64682 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 02e71de..543022b 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 d952828..307e321 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/AngleConversionFactorsJson.html b/docs/swervelib/parser/json/modules/AngleConversionFactorsJson.html
index adda0f2..c3c04ca 100644
--- a/docs/swervelib/parser/json/modules/AngleConversionFactorsJson.html
+++ b/docs/swervelib/parser/json/modules/AngleConversionFactorsJson.html
@@ -1,11 +1,11 @@
-
+
AngleConversionFactorsJson
-
+
diff --git a/docs/swervelib/parser/json/modules/BoolMotorJson.html b/docs/swervelib/parser/json/modules/BoolMotorJson.html
index 0878f3a..539eb43 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/ConversionFactorsJson.html b/docs/swervelib/parser/json/modules/ConversionFactorsJson.html
index b4abcd9..9284251 100644
--- a/docs/swervelib/parser/json/modules/ConversionFactorsJson.html
+++ b/docs/swervelib/parser/json/modules/ConversionFactorsJson.html
@@ -1,11 +1,11 @@
-
+
ConversionFactorsJson
-
+
diff --git a/docs/swervelib/parser/json/modules/DriveConversionFactorsJson.html b/docs/swervelib/parser/json/modules/DriveConversionFactorsJson.html
index 9b00da9..bcc97c9 100644
--- a/docs/swervelib/parser/json/modules/DriveConversionFactorsJson.html
+++ b/docs/swervelib/parser/json/modules/DriveConversionFactorsJson.html
@@ -1,11 +1,11 @@
-
+
DriveConversionFactorsJson
-
+
diff --git a/docs/swervelib/parser/json/modules/LocationJson.html b/docs/swervelib/parser/json/modules/LocationJson.html
index 707441d..ec3f9df 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 e249216..56dd2a3 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 bfd565a..055b0cc 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 f4cc8f4..d3d3e00 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 a1f8d9a..ffad497 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 ecaa788..2ab7e25 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 4631dd9..b9798a7 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 e50b735..f2e0ea6 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 60966fd..d57beca 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 88fe309..22004d4 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 d522275..7031dac 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 330b4fa..53e0b79 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 4708168..76ce9e8 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 aa9d6ad..56cb256 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 49c01fe..d121433 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 540de87..7ef8ce7 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 adfcf9d..3109f04 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 a1e4b0a..04f9108 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 dfbb82c..c6460e9 100644
--- a/swervelib/SwerveDrive.java
+++ b/swervelib/SwerveDrive.java
@@ -1064,6 +1064,21 @@ public class SwerveDrive
odometryLock.unlock();
}
+ /**
+ * Sets the pose estimator's trust of global measurements. This might be used to change trust in vision measurements
+ * after the autonomous period, or to change trust as distance to a vision target increases.
+ *
+ * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these numbers to trust
+ * global measurements from vision less. This matrix is in the form [x, y, theta],
+ * with units in meters and radians.
+ */
+ public void setVisionMeasurementStdDevs(Matrix visionMeasurementStdDevs)
+ {
+ odometryLock.lock();
+ swerveDrivePoseEstimator.setVisionMeasurementStdDevs(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.
diff --git a/swervelib/SwerveModule.java b/swervelib/SwerveModule.java
index 2e04383..202a64d 100644
--- a/swervelib/SwerveModule.java
+++ b/swervelib/SwerveModule.java
@@ -1,5 +1,7 @@
package swervelib;
+import com.revrobotics.CANSparkMax;
+import com.revrobotics.MotorFeedbackSensor;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
@@ -38,6 +40,10 @@ public class SwerveModule
* Drive motor velocity cache.
*/
public final Cache driveVelocityCache;
+ /**
+ * Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
+ */
+ public final int moduleNumber;
/**
* Swerve Motors.
*/
@@ -78,10 +84,6 @@ public class SwerveModule
* NT3 Raw drive motor.
*/
private final String rawDriveVelName;
- /**
- * Module number for kinematics, usually 0 to 3. front left -> front right -> back left -> back right.
- */
- public final int moduleNumber;
/**
* Maximum speed of the drive motors in meters per second.
*/
@@ -591,13 +593,23 @@ public class SwerveModule
{
if (absoluteEncoder != null && angleOffset == configuration.angleOffset)
{
- if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
+ // If the absolute encoder is attached.
+ if (angleMotor.getMotor() instanceof CANSparkMax)
{
- angleOffset = 0;
- } else
- {
- encoderOffsetWarning.set(true);
+ if (absoluteEncoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
+ {
+ angleMotor.setAbsoluteEncoder(absoluteEncoder);
+ if (absoluteEncoder.setAbsoluteEncoderOffset(angleOffset))
+ {
+ angleOffset = 0;
+ } else
+ {
+ angleMotor.setAbsoluteEncoder(null);
+ encoderOffsetWarning.set(true);
+ }
+ }
}
+
} else
{
noEncoderWarning.set(true);
diff --git a/swervelib/encoders/CanAndCoderSwerve.java b/swervelib/encoders/CanAndCoderSwerve.java
index 1c6b7b1..ba97797 100644
--- a/swervelib/encoders/CanAndCoderSwerve.java
+++ b/swervelib/encoders/CanAndCoderSwerve.java
@@ -1,26 +1,26 @@
package swervelib.encoders;
-import com.reduxrobotics.sensors.canandcoder.Canandcoder;
+import com.reduxrobotics.sensors.canandmag.Canandmag;
/**
- * HELIUM {@link Canandcoder} from ReduxRobotics absolute encoder, attached through the CAN bus.
+ * HELIUM {@link Canandmag} from ReduxRobotics absolute encoder, attached through the CAN bus.
*/
public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
{
/**
- * The {@link Canandcoder} representing the CANandCoder on the CAN bus.
+ * The {@link Canandmag} representing the CANandCoder on the CAN bus.
*/
- public Canandcoder encoder;
+ public Canandmag encoder;
/**
- * Create the {@link Canandcoder}
+ * Create the {@link Canandmag}
*
* @param canid The CAN ID whenever the CANandCoder is operating on the CANBus.
*/
public CanAndCoderSwerve(int canid)
{
- encoder = new Canandcoder(canid);
+ encoder = new Canandmag(canid);
}
/**
@@ -51,7 +51,7 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
@Override
public void configure(boolean inverted)
{
- encoder.setSettings(new Canandcoder.Settings().setInvertDirection(inverted));
+ encoder.setSettings(new Canandmag.Settings().setInvertDirection(inverted));
}
/**
@@ -85,7 +85,7 @@ public class CanAndCoderSwerve extends SwerveAbsoluteEncoder
@Override
public boolean setAbsoluteEncoderOffset(double offset)
{
- return encoder.setSettings(new Canandcoder.Settings().setZeroOffset(offset));
+ return encoder.setSettings(new Canandmag.Settings().setZeroOffset(offset));
}
/**
diff --git a/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java b/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java
index 3024787..2ef7197 100644
--- a/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java
+++ b/swervelib/encoders/SparkMaxAnalogEncoderSwerve.java
@@ -108,7 +108,7 @@ public class SparkMaxAnalogEncoderSwerve extends SwerveAbsoluteEncoder
@Override
public double getAbsolutePosition()
{
- return encoder.getPosition();
+ return encoder.getPosition() * (360 / 3.3);
}
/**
diff --git a/swervelib/imu/ADIS16448Swerve.java b/swervelib/imu/ADIS16448Swerve.java
index 4295d48..531b30d 100644
--- a/swervelib/imu/ADIS16448Swerve.java
+++ b/swervelib/imu/ADIS16448Swerve.java
@@ -110,6 +110,14 @@ public class ADIS16448Swerve extends SwerveIMU
return Optional.of(new Translation3d(imu.getAccelX(), imu.getAccelY(), imu.getAccelZ()));
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/ADIS16470Swerve.java b/swervelib/imu/ADIS16470Swerve.java
index 94a31b7..fd01a3d 100644
--- a/swervelib/imu/ADIS16470Swerve.java
+++ b/swervelib/imu/ADIS16470Swerve.java
@@ -110,6 +110,14 @@ public class ADIS16470Swerve extends SwerveIMU
return Optional.of(new Translation3d(imu.getAccelX(), imu.getAccelY(), imu.getAccelZ()));
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/ADXRS450Swerve.java b/swervelib/imu/ADXRS450Swerve.java
index 718a896..dd9a72d 100644
--- a/swervelib/imu/ADXRS450Swerve.java
+++ b/swervelib/imu/ADXRS450Swerve.java
@@ -108,6 +108,14 @@ public class ADXRS450Swerve extends SwerveIMU
return Optional.empty();
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/AnalogGyroSwerve.java b/swervelib/imu/AnalogGyroSwerve.java
index d104a0f..e789d97 100644
--- a/swervelib/imu/AnalogGyroSwerve.java
+++ b/swervelib/imu/AnalogGyroSwerve.java
@@ -15,7 +15,7 @@ public class AnalogGyroSwerve extends SwerveIMU
/**
* Gyroscope object.
*/
- private final AnalogGyro gyro;
+ private final AnalogGyro imu;
/**
* Offset for the analog gyro.
*/
@@ -37,9 +37,9 @@ public class AnalogGyroSwerve extends SwerveIMU
throw new RuntimeException(
"Analog Gyroscope must be attached to port 0 or 1 on the roboRIO.\n");
}
- gyro = new AnalogGyro(channel);
+ imu = new AnalogGyro(channel);
factoryDefault();
- SmartDashboard.putData(gyro);
+ SmartDashboard.putData(imu);
}
/**
@@ -48,7 +48,7 @@ public class AnalogGyroSwerve extends SwerveIMU
@Override
public void factoryDefault()
{
- gyro.calibrate();
+ imu.calibrate();
offset = new Rotation3d(0, 0, 0);
}
@@ -88,7 +88,7 @@ public class AnalogGyroSwerve extends SwerveIMU
*/
public Rotation3d getRawRotation3d()
{
- Rotation3d reading = new Rotation3d(0, 0, Math.toRadians(-gyro.getAngle()));
+ Rotation3d reading = new Rotation3d(0, 0, Math.toRadians(-imu.getAngle()));
return invertedIMU ? reading.unaryMinus() : reading;
}
@@ -115,6 +115,14 @@ public class AnalogGyroSwerve extends SwerveIMU
return Optional.empty();
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
@@ -123,6 +131,6 @@ public class AnalogGyroSwerve extends SwerveIMU
@Override
public Object getIMU()
{
- return gyro;
+ return imu;
}
}
diff --git a/swervelib/imu/NavXSwerve.java b/swervelib/imu/NavXSwerve.java
index 8b2b239..05c50a3 100644
--- a/swervelib/imu/NavXSwerve.java
+++ b/swervelib/imu/NavXSwerve.java
@@ -19,7 +19,7 @@ public class NavXSwerve extends SwerveIMU
/**
* NavX IMU.
*/
- private AHRS gyro;
+ private AHRS imu;
/**
* Offset for the NavX.
*/
@@ -46,9 +46,9 @@ public class NavXSwerve extends SwerveIMU
/* Communicate w/navX-MXP via the MXP SPI Bus. */
/* Alternatively: I2C.Port.kMXP, SerialPort.Port.kMXP or SerialPort.Port.kUSB */
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
- gyro = new AHRS(port);
+ imu = new AHRS(port);
factoryDefault();
- SmartDashboard.putData(gyro);
+ SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
@@ -68,9 +68,9 @@ public class NavXSwerve extends SwerveIMU
/* Communicate w/navX-MXP via the MXP SPI Bus. */
/* Alternatively: I2C.Port.kMXP, SerialPort.Port.kMXP or SerialPort.Port.kUSB */
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
- gyro = new AHRS(port);
+ imu = new AHRS(port);
factoryDefault();
- SmartDashboard.putData(gyro);
+ SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
@@ -90,9 +90,9 @@ public class NavXSwerve extends SwerveIMU
/* Communicate w/navX-MXP via the MXP SPI Bus. */
/* Alternatively: I2C.Port.kMXP, SerialPort.Port.kMXP or SerialPort.Port.kUSB */
/* See http://navx-mxp.kauailabs.com/guidance/selecting-an-interface/ for details. */
- gyro = new AHRS(port);
+ imu = new AHRS(port);
factoryDefault();
- SmartDashboard.putData(gyro);
+ SmartDashboard.putData(imu);
} catch (RuntimeException ex)
{
navXError.setText("Error instantiating NavX: " + ex.getMessage());
@@ -107,7 +107,7 @@ public class NavXSwerve extends SwerveIMU
public void factoryDefault()
{
// gyro.reset(); // Reported to be slow
- offset = gyro.getRotation3d();
+ offset = imu.getRotation3d();
}
/**
@@ -146,7 +146,7 @@ public class NavXSwerve extends SwerveIMU
@Override
public Rotation3d getRawRotation3d()
{
- return invertedIMU ? gyro.getRotation3d().unaryMinus() : gyro.getRotation3d();
+ return invertedIMU ? imu.getRotation3d().unaryMinus() : imu.getRotation3d();
}
/**
@@ -171,12 +171,20 @@ public class NavXSwerve extends SwerveIMU
{
return Optional.of(
new Translation3d(
- gyro.getWorldLinearAccelX(),
- gyro.getWorldLinearAccelY(),
- gyro.getWorldLinearAccelZ())
+ imu.getWorldLinearAccelX(),
+ imu.getWorldLinearAccelY(),
+ imu.getWorldLinearAccelZ())
.times(9.81));
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
@@ -185,6 +193,6 @@ public class NavXSwerve extends SwerveIMU
@Override
public Object getIMU()
{
- return gyro;
+ return imu;
}
}
diff --git a/swervelib/imu/Pigeon2Swerve.java b/swervelib/imu/Pigeon2Swerve.java
index bc89264..6498dba 100644
--- a/swervelib/imu/Pigeon2Swerve.java
+++ b/swervelib/imu/Pigeon2Swerve.java
@@ -138,6 +138,14 @@ public class Pigeon2Swerve extends SwerveIMU
zAcc.waitForUpdate(STATUS_TIMEOUT_SECONDS).getValue()).times(9.81 / 16384.0));
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/PigeonSwerve.java b/swervelib/imu/PigeonSwerve.java
index b9bbcc5..25e12fb 100644
--- a/swervelib/imu/PigeonSwerve.java
+++ b/swervelib/imu/PigeonSwerve.java
@@ -115,6 +115,14 @@ public class PigeonSwerve extends SwerveIMU
return Optional.of(new Translation3d(initial[0], initial[1], initial[2]).times(9.81 / 16384.0));
}
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public double getRate() {
+ return imu.getRate();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/SwerveIMU.java b/swervelib/imu/SwerveIMU.java
index dd9a727..ca2b234 100644
--- a/swervelib/imu/SwerveIMU.java
+++ b/swervelib/imu/SwerveIMU.java
@@ -56,6 +56,12 @@ public abstract class SwerveIMU
*/
public abstract Optional getAccel();
+ /**
+ * Fetch the rotation rate from the IMU in degrees per second. If rotation rate isn't supported returns empty.
+ * @return {@link Double} of the rotation rate as an {@link Optional}.
+ */
+ public abstract double getRate();
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/math/SwerveMath.java b/swervelib/math/SwerveMath.java
index d78e587..ca278a9 100644
--- a/swervelib/math/SwerveMath.java
+++ b/swervelib/math/SwerveMath.java
@@ -359,7 +359,7 @@ public class SwerveMath
/**
* Put an angle within the 360 deg scope of a reference. For example, given a scope reference of 756 degrees, assumes
* the full scope is (720-1080), and places an angle of 22 degrees into it, returning 742 deg.
- *
+ *
* A more formal definition: returns the closest angle {@code n} to {@code scopeReference} such that {@code n} is
* congruent to {@code newAngle}.
*
diff --git a/swervelib/motors/SparkFlexSwerve.java b/swervelib/motors/SparkFlexSwerve.java
index 0c96826..40a2770 100644
--- a/swervelib/motors/SparkFlexSwerve.java
+++ b/swervelib/motors/SparkFlexSwerve.java
@@ -200,7 +200,11 @@ public class SparkFlexSwerve extends SwerveMotor
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
- if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
+ if (encoder == null)
+ {
+ absoluteEncoder = null;
+ configureSparkFlex(() -> pid.setFeedbackDevice(this.encoder));
+ } else if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
absoluteEncoderOffsetWarning.set(true);
absoluteEncoder = encoder;
diff --git a/swervelib/motors/SparkMaxBrushedMotorSwerve.java b/swervelib/motors/SparkMaxBrushedMotorSwerve.java
index bb33fc4..d8fb2a8 100644
--- a/swervelib/motors/SparkMaxBrushedMotorSwerve.java
+++ b/swervelib/motors/SparkMaxBrushedMotorSwerve.java
@@ -237,7 +237,11 @@ public class SparkMaxBrushedMotorSwerve extends SwerveMotor
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
- if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
+ if (encoder == null)
+ {
+ absoluteEncoder = null;
+ configureSparkMax(() -> pid.setFeedbackDevice(this.encoder));
+ } else if (encoder.getAbsoluteEncoder() instanceof AbsoluteEncoder)
{
absoluteEncoder = (AbsoluteEncoder) encoder.getAbsoluteEncoder();
configureSparkMax(() -> pid.setFeedbackDevice(absoluteEncoder));
diff --git a/swervelib/motors/SparkMaxSwerve.java b/swervelib/motors/SparkMaxSwerve.java
index aa19a0c..a2c421e 100644
--- a/swervelib/motors/SparkMaxSwerve.java
+++ b/swervelib/motors/SparkMaxSwerve.java
@@ -192,10 +192,16 @@ public class SparkMaxSwerve extends SwerveMotor
@Override
public SwerveMotor setAbsoluteEncoder(SwerveAbsoluteEncoder encoder)
{
- if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
+ if (encoder == null)
+ {
+ absoluteEncoder = null;
+ configureSparkMax(() -> pid.setFeedbackDevice(this.encoder));
+ velocity = this.encoder::getVelocity;
+ position = this.encoder::getPosition;
+ } else if (encoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
{
DriverStation.reportWarning(
- "IF possible configure the duty cycle encoder offset in the REV Hardware Client instead of using the" +
+ "IF possible configure the encoder offset in the REV Hardware Client instead of using the" +
" absoluteEncoderOffset in the Swerve Module JSON!",
false);
absoluteEncoder = encoder;
diff --git a/swervelib/parser/SwerveDriveConfiguration.java b/swervelib/parser/SwerveDriveConfiguration.java
index d3bcf0c..347b187 100644
--- a/swervelib/parser/SwerveDriveConfiguration.java
+++ b/swervelib/parser/SwerveDriveConfiguration.java
@@ -11,6 +11,10 @@ import swervelib.imu.SwerveIMU;
public class SwerveDriveConfiguration
{
+ /**
+ * Number of modules on the robot.
+ */
+ public final int moduleCount;
/**
* Swerve Module locations.
*/
@@ -19,10 +23,6 @@ public class SwerveDriveConfiguration
* Swerve IMU
*/
public SwerveIMU imu;
- /**
- * Number of modules on the robot.
- */
- public final int moduleCount;
/**
* Swerve Modules.
*/
diff --git a/swervelib/parser/json/ModuleJson.java b/swervelib/parser/json/ModuleJson.java
index 5eb3471..4e89652 100644
--- a/swervelib/parser/json/ModuleJson.java
+++ b/swervelib/parser/json/ModuleJson.java
@@ -81,15 +81,6 @@ public class ModuleJson
SwerveMotor angleMotor = angle.createMotor(false);
SwerveAbsoluteEncoder absEncoder = encoder.createEncoder(angleMotor);
- // If the absolute encoder is attached.
- if (absEncoder != null && angleMotor.getMotor() instanceof CANSparkMax)
- {
- if (absEncoder.getAbsoluteEncoder() instanceof MotorFeedbackSensor)
- {
- angleMotor.setAbsoluteEncoder(absEncoder);
- }
- }
-
// Setup deprecation notice.
// if (this.conversionFactor.drive != 0 && this.conversionFactor.angle != 0)
// {
diff --git a/swervelib/parser/json/PhysicalPropertiesJson.java b/swervelib/parser/json/PhysicalPropertiesJson.java
index 7715d9d..60be9d2 100644
--- a/swervelib/parser/json/PhysicalPropertiesJson.java
+++ b/swervelib/parser/json/PhysicalPropertiesJson.java
@@ -2,8 +2,6 @@ package swervelib.parser.json;
import swervelib.parser.SwerveModulePhysicalCharacteristics;
import swervelib.parser.json.modules.ConversionFactorsJson;
-import swervelib.telemetry.Alert;
-import swervelib.telemetry.Alert.AlertType;
/**
* {@link swervelib.parser.SwerveModulePhysicalCharacteristics} parsed data. Used to configure the SwerveModule.