diff --git a/docs/allclasses-index.html b/docs/allclasses-index.html index e649b76..f4fbff5 100644 --- a/docs/allclasses-index.html +++ b/docs/allclasses-index.html @@ -1,11 +1,11 @@
- +Rotation3d object.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.Rotation3d from the IMU.SwerveModuleState2 of the simulated module.edu.wpi.first.math.kinematics.ChassisSpeedsOptional<edu.wpi.first.math.geometry.Translation3d>getAccel()edu.wpi.first.math.geometry.Rotation3dRotation3d of the robot, as reported by the imu.edu.wpi.first.math.kinematics.SwerveModulePosition[]edu.wpi.first.math.geometry.Rotation2dgetPitch()edu.wpi.first.math.geometry.Pose2dgetPose()edu.wpi.first.math.kinematics.ChassisSpeedsedu.wpi.first.math.geometry.Rotation3dRotation3d of the robot, as reported by the imu.edu.wpi.first.math.kinematics.SwerveModulePosition[]edu.wpi.first.math.geometry.Rotation2dgetRoll()getPitch()edu.wpi.first.math.geometry.Pose2dgetPose()edu.wpi.first.math.geometry.Pose2d[]getSwerveModulePoses(edu.wpi.first.math.geometry.Pose2d robotPose) edu.wpi.first.math.kinematics.ChassisSpeedsedu.wpi.first.math.geometry.Rotation2dgetYaw()getRoll()edu.wpi.first.math.geometry.Pose2d[]getSwerveModulePoses(edu.wpi.first.math.geometry.Pose2d robotPose) edu.wpi.first.math.geometry.Rotation2dgetYaw()voidlockPose()voidlockPose()voidpostTrajectory(edu.wpi.first.math.trajectory.Trajectory trajectory) voidpostTrajectory(edu.wpi.first.math.trajectory.Trajectory trajectory) voidreplaceSwerveModuleFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward) voidreplaceSwerveModuleFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward) voidresetOdometry(edu.wpi.first.math.geometry.Pose2d pose) voidresetOdometry(edu.wpi.first.math.geometry.Pose2d pose) voidsetChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds) voidsetChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds) voidsetGyro(edu.wpi.first.math.geometry.Rotation3d gyro) Rotation3d object.voidsetModuleStates(SwerveModuleState2[] desiredStates,
boolean isOpenLoop) Translation3dRotation3d object. (Only yaw works currently.)gyro - Gyroscope offset.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.getIMU()Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()getIMU()edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.getRotation3d in class SwerveIMURotation3d from the IMU.abstract ObjectgetIMU()abstract Optional<edu.wpi.first.math.geometry.Translation3d>getAccel()abstract ObjectgetIMU()abstract edu.wpi.first.math.geometry.Rotation3dRotation3d from the IMU.abstract voidgetYawPitchRoll(double[] yprArray) Rotation3d from the IMU. Robot relative.Rotation3d from the IMU.Translation3d of the acceleration as an Optional.edu.wpi.first.math.geometry.Rotation3dOptional<edu.wpi.first.math.geometry.Translation3d>getAccel()edu.wpi.first.math.geometry.Rotation3dRotation3d of the robot.edu.wpi.first.math.geometry.Rotation2dgetPitch()edu.wpi.first.math.geometry.Rotation2dgetPitch()edu.wpi.first.math.geometry.Rotation2dgetRoll()edu.wpi.first.math.geometry.Rotation2dgetRoll()edu.wpi.first.math.geometry.Rotation2dgetYaw()edu.wpi.first.math.geometry.Rotation2dgetYaw()voidsetAngle(double angle) voidsetAngle(double angle) voidupdateOdometry(SwerveKinematics2 kinematics,
+void
+updateOdometry(SwerveKinematics2 kinematics,
SwerveModuleState2[] states,
edu.wpi.first.math.geometry.Pose2d[] modulePoses,
edu.wpi.first.wpilibj.smartdashboard.Field2d field)
-
+
@@ -275,6 +280,17 @@ loadScripts(document, 'script');
+
+getAccel
+
+Fetch the acceleration [x, y, z] from the IMU in m/s/s. If acceleration isn't supported returns empty.
+
+- Returns:
+Translation3d of the acceleration as an Optional.
+
+
+
+
updateOdometry
public void updateOdometry(SwerveKinematics2 kinematics,
diff --git a/docs/swervelib/simulation/SwerveModuleSimulation.html b/docs/swervelib/simulation/SwerveModuleSimulation.html
index 1cad476..152c318 100644
--- a/docs/swervelib/simulation/SwerveModuleSimulation.html
+++ b/docs/swervelib/simulation/SwerveModuleSimulation.html
@@ -1,11 +1,11 @@
-
+
SwerveModuleSimulation
-
+
diff --git a/docs/swervelib/simulation/ctre/PhysicsSim.SimProfile.html b/docs/swervelib/simulation/ctre/PhysicsSim.SimProfile.html
index ac4726b..9fcc100 100644
--- a/docs/swervelib/simulation/ctre/PhysicsSim.SimProfile.html
+++ b/docs/swervelib/simulation/ctre/PhysicsSim.SimProfile.html
@@ -1,11 +1,11 @@
-
+
PhysicsSim.SimProfile
-
+
diff --git a/docs/swervelib/simulation/ctre/PhysicsSim.html b/docs/swervelib/simulation/ctre/PhysicsSim.html
index e84f47a..798662d 100644
--- a/docs/swervelib/simulation/ctre/PhysicsSim.html
+++ b/docs/swervelib/simulation/ctre/PhysicsSim.html
@@ -1,11 +1,11 @@
-
+
PhysicsSim
-
+
diff --git a/docs/swervelib/simulation/ctre/TalonFXSimProfile.html b/docs/swervelib/simulation/ctre/TalonFXSimProfile.html
index 1431fc6..9ba1bc3 100644
--- a/docs/swervelib/simulation/ctre/TalonFXSimProfile.html
+++ b/docs/swervelib/simulation/ctre/TalonFXSimProfile.html
@@ -1,11 +1,11 @@
-
+
TalonFXSimProfile
-
+
diff --git a/docs/swervelib/simulation/ctre/TalonSRXSimProfile.html b/docs/swervelib/simulation/ctre/TalonSRXSimProfile.html
index 0570fa6..ee692a6 100644
--- a/docs/swervelib/simulation/ctre/TalonSRXSimProfile.html
+++ b/docs/swervelib/simulation/ctre/TalonSRXSimProfile.html
@@ -1,11 +1,11 @@
-
+
TalonSRXSimProfile
-
+
diff --git a/docs/swervelib/simulation/ctre/VictorSPXSimProfile.html b/docs/swervelib/simulation/ctre/VictorSPXSimProfile.html
index 77c6bcd..bac6b7a 100644
--- a/docs/swervelib/simulation/ctre/VictorSPXSimProfile.html
+++ b/docs/swervelib/simulation/ctre/VictorSPXSimProfile.html
@@ -1,11 +1,11 @@
-
+
VictorSPXSimProfile
-
+
diff --git a/docs/swervelib/simulation/ctre/package-summary.html b/docs/swervelib/simulation/ctre/package-summary.html
index 3a3c285..48fe2ed 100644
--- a/docs/swervelib/simulation/ctre/package-summary.html
+++ b/docs/swervelib/simulation/ctre/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib.simulation.ctre
-
+
diff --git a/docs/swervelib/simulation/ctre/package-tree.html b/docs/swervelib/simulation/ctre/package-tree.html
index b334aa6..ddab880 100644
--- a/docs/swervelib/simulation/ctre/package-tree.html
+++ b/docs/swervelib/simulation/ctre/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib.simulation.ctre Class Hierarchy
-
+
diff --git a/docs/swervelib/simulation/package-summary.html b/docs/swervelib/simulation/package-summary.html
index b2a4862..600f417 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 c7420d5..b1f087a 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/SwerveDriveTelemetry.TelemetryVerbosity.html b/docs/swervelib/telemetry/SwerveDriveTelemetry.TelemetryVerbosity.html
index d3ef467..c3f9559 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 6f2aa52..5be04f5 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 5401227..19d81a0 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 6d0bb36..356747d 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 6e5b00e..3ed9256 100644
--- a/swervelib/SwerveDrive.java
+++ b/swervelib/SwerveDrive.java
@@ -9,6 +9,7 @@ import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.numbers.N1;
@@ -20,6 +21,7 @@ import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import java.util.ArrayList;
import java.util.List;
+import java.util.Optional;
import swervelib.imu.SwerveIMU;
import swervelib.math.SwerveKinematics2;
import swervelib.math.SwerveMath;
@@ -407,6 +409,7 @@ public class SwerveDrive
simIMU.setAngle(0);
}
swerveController.lastAngleScalar = 0;
+ lastHeadingRadians = 0;
resetOdometry(new Pose2d(getPose().getTranslation(), new Rotation2d()));
}
@@ -420,9 +423,9 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- double[] ypr = new double[3];
- imu.getYawPitchRoll(ypr);
- return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[0] : ypr[0]);
+ return swerveDriveConfiguration.invertedIMU
+ ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getZ())
+ : Rotation2d.fromRadians(imu.getRotation3d().getZ());
} else
{
return simIMU.getYaw();
@@ -439,9 +442,9 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- double[] ypr = new double[3];
- imu.getYawPitchRoll(ypr);
- return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[1] : ypr[1]);
+ return swerveDriveConfiguration.invertedIMU
+ ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getY())
+ : Rotation2d.fromRadians(imu.getRotation3d().getY());
} else
{
return simIMU.getPitch();
@@ -458,9 +461,9 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- double[] ypr = new double[3];
- imu.getYawPitchRoll(ypr);
- return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[2] : ypr[2]);
+ return swerveDriveConfiguration.invertedIMU
+ ? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getX())
+ : Rotation2d.fromRadians(imu.getRotation3d().getX());
} else
{
return simIMU.getRoll();
@@ -477,18 +480,31 @@ public class SwerveDrive
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
- double[] ypr = new double[3];
- imu.getYawPitchRoll(ypr);
- return new Rotation3d(
- Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[2] : ypr[2]),
- Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[1] : ypr[1]),
- Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[0] : ypr[0]));
+ return swerveDriveConfiguration.invertedIMU
+ ? imu.getRotation3d().unaryMinus()
+ : imu.getRotation3d();
} else
{
return simIMU.getGyroRotation3d();
}
}
+ /**
+ * Gets current acceleration of the robot in m/s/s. If gyro unsupported returns empty.
+ *
+ * @return acceleration of the robot as a {@link Translation3d}
+ */
+ public Optional getAccel()
+ {
+ if (!SwerveDriveTelemetry.isSimulation)
+ {
+ return imu.getAccel();
+ } else
+ {
+ return simIMU.getAccel();
+ }
+ }
+
/**
* Sets the drive motors to brake/coast mode.
*
@@ -673,4 +689,15 @@ public class SwerveDrive
simIMU.setAngle(swerveDrivePoseEstimator.getEstimatedPosition().getRotation().getRadians());
}
}
+
+ /**
+ * Set the Gyroscope offset using a {@link Rotation3d} object. (Only yaw works currently.)
+ *
+ * @param gyro Gyroscope offset.
+ */
+ public void setGyro(Rotation3d gyro)
+ {
+ imu.setYaw(gyro.getZ());
+ }
+
}
diff --git a/swervelib/imu/ADIS16448Swerve.java b/swervelib/imu/ADIS16448Swerve.java
index afb7a78..7b1b2ff 100644
--- a/swervelib/imu/ADIS16448Swerve.java
+++ b/swervelib/imu/ADIS16448Swerve.java
@@ -1,7 +1,10 @@
package swervelib.imu;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.ADIS16448_IMU;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* IMU Swerve class for the {@link ADIS16448_IMU} device.
@@ -70,6 +73,31 @@ public class ADIS16448Swerve extends SwerveIMU
yprArray[2] = imu.getYComplementaryAngle() % 360;
}
+
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public Rotation3d getRotation3d()
+ {
+ return new Rotation3d(
+ imu.getYComplementaryAngle(), imu.getXComplementaryAngle(), imu.getAngle())
+ .minus(new Rotation3d(0, 0, Math.toRadians(yawOffset)));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ return Optional.of(new Translation3d(imu.getAccelX(), imu.getAccelY(), imu.getAccelZ()));
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/ADIS16470Swerve.java b/swervelib/imu/ADIS16470Swerve.java
index 34e8aef..d586872 100644
--- a/swervelib/imu/ADIS16470Swerve.java
+++ b/swervelib/imu/ADIS16470Swerve.java
@@ -1,7 +1,10 @@
package swervelib.imu;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.ADIS16470_IMU;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* IMU Swerve class for the {@link ADIS16470_IMU} device.
@@ -70,6 +73,30 @@ public class ADIS16470Swerve extends SwerveIMU
yprArray[2] = imu.getYComplementaryAngle() % 360;
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public Rotation3d getRotation3d()
+ {
+ return new Rotation3d(
+ imu.getYComplementaryAngle(), imu.getXComplementaryAngle(), imu.getAngle())
+ .minus(new Rotation3d(0, 0, Math.toRadians(yawOffset)));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ return Optional.of(new Translation3d(imu.getAccelX(), imu.getAccelY(), imu.getAccelZ()));
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/ADXRS450Swerve.java b/swervelib/imu/ADXRS450Swerve.java
index 9ce3cb9..0af120b 100644
--- a/swervelib/imu/ADXRS450Swerve.java
+++ b/swervelib/imu/ADXRS450Swerve.java
@@ -1,7 +1,10 @@
package swervelib.imu;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* IMU Swerve class for the {@link ADXRS450_Gyro} device.
@@ -70,6 +73,29 @@ public class ADXRS450Swerve extends SwerveIMU
yprArray[2] = 0;
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public Rotation3d getRotation3d()
+ {
+ return new Rotation3d(0, 0, imu.getAngle())
+ .minus(new Rotation3d(0, 0, Math.toRadians(yawOffset)));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ return Optional.empty();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/AnalogGyroSwerve.java b/swervelib/imu/AnalogGyroSwerve.java
index 15a63d4..e114062 100644
--- a/swervelib/imu/AnalogGyroSwerve.java
+++ b/swervelib/imu/AnalogGyroSwerve.java
@@ -1,7 +1,10 @@
package swervelib.imu;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* Creates a IMU for {@link edu.wpi.first.wpilibj.AnalogGyro} devices, only uses yaw.
@@ -77,6 +80,29 @@ public class AnalogGyroSwerve extends SwerveIMU
yprArray[2] = 0;
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public Rotation3d getRotation3d()
+ {
+ return new Rotation3d(0, 0, gyro.getAngle())
+ .minus(new Rotation3d(0, 0, Math.toRadians(yawOffset)));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ return Optional.empty();
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/NavXSwerve.java b/swervelib/imu/NavXSwerve.java
index 9c0cbb4..0e6b9ed 100644
--- a/swervelib/imu/NavXSwerve.java
+++ b/swervelib/imu/NavXSwerve.java
@@ -1,9 +1,13 @@
package swervelib.imu;
import com.kauailabs.navx.frc.AHRS;
+import edu.wpi.first.math.geometry.Quaternion;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.SerialPort;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* Communicates with the NavX as the IMU.
@@ -84,6 +88,37 @@ public class NavXSwerve extends SwerveIMU
yprArray[2] = (gyro.getRoll() % 360);
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public Rotation3d getRotation3d()
+ {
+ return new Rotation3d(new Quaternion(gyro.getQuaternionW(),
+ gyro.getQuaternionX(),
+ gyro.getQuaternionY(),
+ gyro.getQuaternionZ()))
+ .minus(new Rotation3d(0, 0, Math.toRadians(yawOffset)));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ return Optional.of(
+ new Translation3d(
+ gyro.getWorldLinearAccelX(),
+ gyro.getWorldLinearAccelY(),
+ gyro.getWorldLinearAccelZ())
+ .times(9.81));
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/Pigeon2Swerve.java b/swervelib/imu/Pigeon2Swerve.java
index e03701c..e865c87 100644
--- a/swervelib/imu/Pigeon2Swerve.java
+++ b/swervelib/imu/Pigeon2Swerve.java
@@ -2,7 +2,11 @@ package swervelib.imu;
import com.ctre.phoenix.sensors.Pigeon2Configuration;
import com.ctre.phoenix.sensors.WPI_Pigeon2;
+import edu.wpi.first.math.geometry.Quaternion;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* SwerveIMU interface for the Pigeon2
@@ -79,6 +83,33 @@ public class Pigeon2Swerve extends SwerveIMU
imu.getYawPitchRoll(yprArray);
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ @Override
+ public Rotation3d getRotation3d()
+ {
+ double[] wxyz = new double[4];
+ imu.get6dQuaternion(wxyz);
+ return new Rotation3d(new Quaternion(wxyz[0], wxyz[1], wxyz[2], wxyz[3]));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ short[] initial = new short[3];
+ imu.getBiasedAccelerometer(initial);
+ return Optional.of(new Translation3d(initial[0], initial[1], initial[2]).times(9.81 / 16384.0));
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/PigeonSwerve.java b/swervelib/imu/PigeonSwerve.java
index b4f2dae..64cd3de 100644
--- a/swervelib/imu/PigeonSwerve.java
+++ b/swervelib/imu/PigeonSwerve.java
@@ -1,7 +1,11 @@
package swervelib.imu;
import com.ctre.phoenix.sensors.WPI_PigeonIMU;
+import edu.wpi.first.math.geometry.Quaternion;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import java.util.Optional;
/**
* SwerveIMU interface for the Pigeon.
@@ -65,6 +69,33 @@ public class PigeonSwerve extends SwerveIMU
imu.getYawPitchRoll(yprArray);
}
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ @Override
+ public Rotation3d getRotation3d()
+ {
+ double[] wxyz = new double[4];
+ imu.get6dQuaternion(wxyz);
+ return new Rotation3d(new Quaternion(wxyz[0], wxyz[1], wxyz[2], wxyz[3]));
+ }
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ @Override
+ public Optional getAccel()
+ {
+ short[] initial = new short[3];
+ imu.getBiasedAccelerometer(initial);
+ return Optional.of(new Translation3d(initial[0], initial[1], initial[2]).times(9.81 / 16384.0));
+ }
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/imu/SwerveIMU.java b/swervelib/imu/SwerveIMU.java
index f46c545..1dd98af 100644
--- a/swervelib/imu/SwerveIMU.java
+++ b/swervelib/imu/SwerveIMU.java
@@ -1,5 +1,9 @@
package swervelib.imu;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
+import java.util.Optional;
+
/**
* Swerve IMU abstraction to define a standard interface with a swerve drive.
*/
@@ -30,6 +34,21 @@ public abstract class SwerveIMU
*/
public abstract void getYawPitchRoll(double[] yprArray);
+ /**
+ * Fetch the {@link Rotation3d} from the IMU. Robot relative.
+ *
+ * @return {@link Rotation3d} from the IMU.
+ */
+ public abstract Rotation3d getRotation3d();
+
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in meters per second squared. If acceleration isn't supported returns
+ * empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ public abstract Optional getAccel();
+
/**
* Get the instantiated IMU object.
*
diff --git a/swervelib/motors/TalonFXSwerve.java b/swervelib/motors/TalonFXSwerve.java
index 756af0a..54e381e 100644
--- a/swervelib/motors/TalonFXSwerve.java
+++ b/swervelib/motors/TalonFXSwerve.java
@@ -6,6 +6,7 @@ import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
+import edu.wpi.first.wpilibj.Timer;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.simulation.ctre.PhysicsSim;
@@ -241,6 +242,7 @@ public class TalonFXSwerve extends SwerveMotor
@Override
public void setInverted(boolean inverted)
{
+ Timer.delay(1);
motor.setInverted(inverted);
}
diff --git a/swervelib/motors/TalonSRXSwerve.java b/swervelib/motors/TalonSRXSwerve.java
index bf88b37..3b29087 100644
--- a/swervelib/motors/TalonSRXSwerve.java
+++ b/swervelib/motors/TalonSRXSwerve.java
@@ -7,6 +7,7 @@ import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced;
import com.ctre.phoenix.motorcontrol.can.TalonSRXConfiguration;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
+import edu.wpi.first.wpilibj.Timer;
import swervelib.encoders.SwerveAbsoluteEncoder;
import swervelib.parser.PIDFConfig;
import swervelib.simulation.ctre.PhysicsSim;
@@ -231,6 +232,7 @@ public class TalonSRXSwerve extends SwerveMotor
@Override
public void setInverted(boolean inverted)
{
+ Timer.delay(1);
motor.setInverted(inverted);
}
diff --git a/swervelib/simulation/SwerveIMUSimulation.java b/swervelib/simulation/SwerveIMUSimulation.java
index 2a80f66..949bda7 100644
--- a/swervelib/simulation/SwerveIMUSimulation.java
+++ b/swervelib/simulation/SwerveIMUSimulation.java
@@ -3,8 +3,10 @@ package swervelib.simulation;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
+import java.util.Optional;
import swervelib.math.SwerveKinematics2;
import swervelib.math.SwerveModuleState2;
@@ -77,6 +79,16 @@ public class SwerveIMUSimulation
return new Rotation3d(0, 0, angle);
}
+ /**
+ * Fetch the acceleration [x, y, z] from the IMU in m/s/s. If acceleration isn't supported returns empty.
+ *
+ * @return {@link Translation3d} of the acceleration as an {@link Optional}.
+ */
+ public Optional getAccel()
+ {
+ return Optional.empty();
+ }
+
/**
* Update the odometry of the simulated {@link swervelib.SwerveDrive} and post the {@link swervelib.SwerveModule}
* states to the {@link Field2d}.