+
double
+
+
Get the position of the integrated encoder.
-
double
-
-
+
double
+
+
Get the velocity of the integrated encoder.
+
double
+
+
+
Get the voltage output of the motor controller.
+
boolean
@@ -292,8 +302,13 @@ loadScripts(document, 'script');
Set the closed loop PID controller reference point.
void
-
+
+
Set the voltage of the motor.
+
+
void
+
+
Set the voltage compensation for the swerve module motor.
@@ -680,6 +695,45 @@ loadScripts(document, 'script');
+
+getVoltage
+public double getVoltage ()
+Get the voltage output of the motor controller.
+
+Specified by:
+getVoltage in class SwerveMotor
+Returns:
+Voltage output.
+
+
+
+
+
+setVoltage
+public void setVoltage (double voltage)
+Set the voltage of the motor.
+
+Specified by:
+setVoltage in class SwerveMotor
+Parameters:
+voltage - Voltage to set.
+
+
+
+
+
+getAppliedOutput
+public double getAppliedOutput ()
+Get the applied dutycycle output.
+
+Specified by:
+getAppliedOutput in class SwerveMotor
+Returns:
+Applied dutycycle output to the motor.
+
+
+
+
getVelocity
public double getVelocity ()
diff --git a/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html b/docs/swervelib/motors/SparkMaxSwerve.SparkMAX_slotIdx.html
index 369b435..f44d812 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 6da14ff..08985f0 100644
--- a/docs/swervelib/motors/SparkMaxSwerve.html
+++ b/docs/swervelib/motors/SparkMaxSwerve.html
@@ -1,11 +1,11 @@
-
+
SparkMaxSwerve
-
+
@@ -220,21 +220,31 @@ loadScripts(document, 'script');
Configure the factory defaults.
-
-
+double
+
+
Get the applied dutycycle output.
+
+
+
+
Get the motor object from the module.
-double
-
-
+
double
+
+
Get the position of the integrated encoder.
-
double
-
-
+
double
+
+
Get the velocity of the integrated encoder.
+
double
+
+
+
Get the voltage output of the motor controller.
+
boolean
@@ -290,8 +300,13 @@ loadScripts(document, 'script');
Set the closed loop PID controller reference point.
void
-
+
+
Set the voltage of the motor.
+
+
void
+
+
Set the voltage compensation for the swerve module motor.
@@ -649,6 +664,45 @@ loadScripts(document, 'script');
+
+getVoltage
+public double getVoltage ()
+Get the voltage output of the motor controller.
+
+Specified by:
+getVoltage in class SwerveMotor
+Returns:
+Voltage output.
+
+
+
+
+
+setVoltage
+public void setVoltage (double voltage)
+Set the voltage of the motor.
+
+Specified by:
+setVoltage in class SwerveMotor
+Parameters:
+voltage - Voltage to set.
+
+
+
+
+
+getAppliedOutput
+public double getAppliedOutput ()
+Get the applied dutycycle output.
+
+Specified by:
+getAppliedOutput in class SwerveMotor
+Returns:
+Applied dutycycle output to the motor.
+
+
+
+
getVelocity
public double getVelocity ()
diff --git a/docs/swervelib/motors/SwerveMotor.html b/docs/swervelib/motors/SwerveMotor.html
index ca6c4aa..2df8d6a 100644
--- a/docs/swervelib/motors/SwerveMotor.html
+++ b/docs/swervelib/motors/SwerveMotor.html
@@ -1,11 +1,11 @@
-
+
SwerveMotor
-
+
@@ -163,21 +163,31 @@ loadScripts(document, 'script');
Configure the factory defaults.
-
-
+abstract double
+
+
Get the applied dutycycle output.
+
+
+
+
Get the motor object from the module.
-abstract double
-
-
+
abstract double
+
+
Get the position of the integrated encoder.
-
abstract double
-
-
+
abstract double
+
+
Get the velocity of the integrated encoder.
+
abstract double
+
+
+
Get the voltage output of the motor controller.
+
abstract boolean
@@ -233,8 +243,13 @@ loadScripts(document, 'script');
Set the closed loop PID controller reference point.
abstract void
-
+
+
Set the voltage of the motor.
+
+
abstract void
+
+
Set the voltage compensation for the swerve module motor.
@@ -429,6 +444,39 @@ loadScripts(document, 'script');
+
+getVoltage
+public abstract double getVoltage ()
+Get the voltage output of the motor controller.
+
+Returns:
+Voltage output.
+
+
+
+
+
+setVoltage
+public abstract void setVoltage (double voltage)
+Set the voltage of the motor.
+
+Parameters:
+voltage - Voltage to set.
+
+
+
+
+
+getAppliedOutput
+public abstract double getAppliedOutput ()
+Get the applied dutycycle output.
+
+Returns:
+Applied dutycycle output to the motor.
+
+
+
+
getVelocity
public abstract double getVelocity ()
diff --git a/docs/swervelib/motors/TalonFXSwerve.html b/docs/swervelib/motors/TalonFXSwerve.html
index 29eedb0..9a2a339 100644
--- a/docs/swervelib/motors/TalonFXSwerve.html
+++ b/docs/swervelib/motors/TalonFXSwerve.html
@@ -1,11 +1,11 @@
-
+
TalonFXSwerve
-
+
@@ -223,21 +223,31 @@ loadScripts(document, 'script');
Configure the factory defaults.
-
-
+double
+
+
Get the applied dutycycle output.
+
+
+
+
Get the motor object from the module.
-double
-
-
+
double
+
+
Get the position of the integrated encoder.
-
double
-
-
+
double
+
+
Get the velocity of the integrated encoder.
+
double
+
+
+
Get the voltage output of the motor controller.
+
boolean
@@ -293,8 +303,13 @@ loadScripts(document, 'script');
Set the closed loop PID controller reference point.
void
-
+
+
Set the voltage of the motor.
+
+
void
+
+
Set the voltage compensation for the swerve module motor.
@@ -650,6 +665,45 @@ loadScripts(document, 'script');
+
+getVoltage
+public double getVoltage ()
+Get the voltage output of the motor controller.
+
+Specified by:
+getVoltage in class SwerveMotor
+Returns:
+Voltage output.
+
+
+
+
+
+setVoltage
+public void setVoltage (double voltage)
+Set the voltage of the motor.
+
+Specified by:
+setVoltage in class SwerveMotor
+Parameters:
+voltage - Voltage to set.
+
+
+
+
+
+getAppliedOutput
+public double getAppliedOutput ()
+Get the applied dutycycle output.
+
+Specified by:
+getAppliedOutput in class SwerveMotor
+Returns:
+Applied dutycycle output to the motor.
+
+
+
+
getVelocity
public double getVelocity ()
diff --git a/docs/swervelib/motors/TalonSRXSwerve.html b/docs/swervelib/motors/TalonSRXSwerve.html
index 1c99537..93acc8e 100644
--- a/docs/swervelib/motors/TalonSRXSwerve.html
+++ b/docs/swervelib/motors/TalonSRXSwerve.html
@@ -1,11 +1,11 @@
-
+
TalonSRXSwerve
-
+
@@ -223,21 +223,31 @@ loadScripts(document, 'script');
Configure the factory defaults.
-
-
+double
+
+
Get the applied dutycycle output.
+
+
+
+
Get the motor object from the module.
-double
-
-
+
double
+
+
Get the position of the integrated encoder.
-
double
-
-
+
double
+
+
Get the velocity of the integrated encoder.
+
double
+
+
+
Get the voltage output of the motor controller.
+
boolean
@@ -293,8 +303,13 @@ loadScripts(document, 'script');
Set the closed loop PID controller reference point.
void
-
+
+
Set the voltage of the motor.
+
+
void
+
+
Set the voltage compensation for the swerve module motor.
@@ -650,6 +665,45 @@ loadScripts(document, 'script');
+
+getVoltage
+public double getVoltage ()
+Get the voltage output of the motor controller.
+
+Specified by:
+getVoltage in class SwerveMotor
+Returns:
+Voltage output.
+
+
+
+
+
+setVoltage
+public void setVoltage (double voltage)
+Set the voltage of the motor.
+
+Specified by:
+setVoltage in class SwerveMotor
+Parameters:
+voltage - Voltage to set.
+
+
+
+
+
+getAppliedOutput
+public double getAppliedOutput ()
+Get the applied dutycycle output.
+
+Specified by:
+getAppliedOutput in class SwerveMotor
+Returns:
+Applied dutycycle output to the motor.
+
+
+
+
getVelocity
public double getVelocity ()
diff --git a/docs/swervelib/motors/package-summary.html b/docs/swervelib/motors/package-summary.html
index 48539bd..e6a1e89 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 a6b7cc8..e4f0ada 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 a15648d..e01b36b 100644
--- a/docs/swervelib/package-summary.html
+++ b/docs/swervelib/package-summary.html
@@ -1,11 +1,11 @@
-
+
swervelib
-
+
@@ -116,8 +116,12 @@ loadScripts(document, 'script');
Swerve Drive class representing and controlling the swerve drive.
-
+
+
Class to perform tests on the swerve drive.
+
+
+
The Swerve Module class which represents and controls Swerve Modules for the swerve drive.
diff --git a/docs/swervelib/package-tree.html b/docs/swervelib/package-tree.html
index 53714ba..62c1173 100644
--- a/docs/swervelib/package-tree.html
+++ b/docs/swervelib/package-tree.html
@@ -1,11 +1,11 @@
-
+
swervelib Class Hierarchy
-
+
@@ -61,6 +61,7 @@ loadScripts(document, 'script');
diff --git a/docs/swervelib/parser/PIDFConfig.html b/docs/swervelib/parser/PIDFConfig.html
index 6daa518..0338e53 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 4d0339f..47815a3 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 92b0ddf..2f06c49 100644
--- a/docs/swervelib/parser/SwerveDriveConfiguration.html
+++ b/docs/swervelib/parser/SwerveDriveConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveDriveConfiguration
-
+
diff --git a/docs/swervelib/parser/SwerveModuleConfiguration.html b/docs/swervelib/parser/SwerveModuleConfiguration.html
index 6e2775e..a347307 100644
--- a/docs/swervelib/parser/SwerveModuleConfiguration.html
+++ b/docs/swervelib/parser/SwerveModuleConfiguration.html
@@ -1,11 +1,11 @@
-
+
SwerveModuleConfiguration
-
+
@@ -147,9 +147,14 @@ loadScripts(document, 'script');
Physical characteristics of the swerve module.
-
-
+
boolean
+
+
Should do cosine compensation when not pointing correct direction;.
+
+
+
+
PIDF configuration options for the drive motor closed-loop PID controller.
@@ -163,7 +168,7 @@ loadScripts(document, 'script');
-
SwerveModuleConfiguration (SwerveMotor driveMotor,
+SwerveModuleConfiguration (SwerveMotor driveMotor,
SwerveMotor angleMotor,
MotorConfigDouble conversionFactors,
SwerveAbsoluteEncoder absoluteEncoder,
@@ -176,11 +181,12 @@ loadScripts(document, 'script');
boolean absoluteEncoderInverted,
boolean driveMotorInverted,
boolean angleMotorInverted,
- String name)
+ String name,
+ boolean useCosineCompensator)
Construct a configuration object for swerve modules.
-
SwerveModuleConfiguration (SwerveMotor driveMotor,
+SwerveModuleConfiguration (SwerveMotor driveMotor,
SwerveMotor angleMotor,
MotorConfigDouble conversionFactors,
SwerveAbsoluteEncoder absoluteEncoder,
@@ -190,7 +196,8 @@ loadScripts(document, 'script');
PIDFConfig anglePIDF,
PIDFConfig velocityPIDF,
SwerveModulePhysicalCharacteristics physicalCharacteristics,
- String name)
+ String name,
+ boolean useCosineCompensator)
Construct a configuration object for swerve modules.
@@ -309,6 +316,13 @@ loadScripts(document, 'script');
Name for the swerve module for telemetry.
+
+
+useCosineCompensator
+public boolean useCosineCompensator
+Should do cosine compensation when not pointing correct direction;.
+
+
@@ -318,7 +332,7 @@ loadScripts(document, 'script');
Constructor Details
-
+
SwerveModuleConfiguration
public SwerveModuleConfiguration (SwerveMotor driveMotor,
SwerveMotor angleMotor,
@@ -333,7 +347,8 @@ loadScripts(document, 'script');
boolean absoluteEncoderInverted,
boolean driveMotorInverted,
boolean angleMotorInverted,
- String name)
+ String name,
+ boolean useCosineCompensator)
Construct a configuration object for swerve modules.
Parameters:
@@ -351,11 +366,12 @@ loadScripts(document, 'script');
physicalCharacteristics - Physical characteristics of the swerve module.
name - The name for the swerve module.
conversionFactors - Conversion factors to be applied to the drive and angle motors.
+useCosineCompensator - Should use cosineCompensation.
-
+
SwerveModuleConfiguration
+ String name,
+ boolean useCosineCompensator)
Construct a configuration object for swerve modules. Assumes the absolute encoder and drive motor are not
inverted.
@@ -383,6 +400,7 @@ loadScripts(document, 'script');
velocityPIDF - Velocity PIDF configuration.
physicalCharacteristics - Physical characteristics of the swerve module.
name - Name for the module.
+useCosineCompensator - Should use cosineCompensation.
diff --git a/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html b/docs/swervelib/parser/SwerveModulePhysicalCharacteristics.html
index 482ae86..e4405f9 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 48a8672..c307d28 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 3ddff1f..d4f280d 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 97c91f0..2d05285 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 ccde2d6..9586203 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 aeb7265..94ed0c8 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 8b1c8d8..4004478 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 19f3e4f..903036b 100644
--- a/docs/swervelib/parser/json/ModuleJson.html
+++ b/docs/swervelib/parser/json/ModuleJson.html
@@ -1,11 +1,11 @@
-
+
ModuleJson
-
+
@@ -131,6 +131,11 @@ loadScripts(document, 'script');
The location of the swerve module from the center of the robot in inches.
+
boolean
+
+
+
Should do cosine compensation when not pointing correct direction;.
+
@@ -243,6 +248,13 @@ loadScripts(document, 'script');
The location of the swerve module from the center of the robot in inches.
+
+
+useCosineCompensator
+public boolean useCosineCompensator
+Should do cosine compensation when not pointing correct direction;.
+
+
diff --git a/docs/swervelib/parser/json/MotorConfigDouble.html b/docs/swervelib/parser/json/MotorConfigDouble.html
index c20e8a2..dfa8e4b 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 3d350f3..6dbb99c 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 c9fc3f3..093c6e7 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 099a7d6..ef1ea0a 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 98b2bd6..e0945c8 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 0d5161f..c8b2b9b 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 eeab53c..6e90ef5 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 236a15b..62775b5 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 57177d4..174eb7e 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 8519194..b5d8a3a 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 41c0a4a..4634f16 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 9e30797..4ef28ef 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 e4ed27b..b254574 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 ff85347..1443571 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 e8a4c04..8e15201 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 42685c7..6799fff 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 dfddc9d..9001125 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 4d12e59..46cd34f 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 5daf788..767b885 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 51ff475..a2e330b 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 4c111fe..2b5a548 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 0a88059..3c43c74 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 7dbd386..134fb32 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 ec1968f..1a8cdc1 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/docs/type-search-index.js b/docs/type-search-index.js
index 37761b1..8bfea55 100644
--- a/docs/type-search-index.js
+++ b/docs/type-search-index.js
@@ -1 +1 @@
-typeSearchIndex = [{"p":"swervelib.imu","l":"ADIS16448Swerve"},{"p":"swervelib.imu","l":"ADIS16470Swerve"},{"p":"swervelib.imu","l":"ADXRS450Swerve"},{"p":"swervelib.telemetry","l":"Alert"},{"p":"swervelib.telemetry","l":"Alert.AlertType"},{"l":"All Classes and Interfaces","u":"allclasses-index.html"},{"p":"swervelib.encoders","l":"AnalogAbsoluteEncoderSwerve"},{"p":"swervelib.imu","l":"AnalogGyroSwerve"},{"p":"swervelib.parser.json.modules","l":"BoolMotorJson"},{"p":"swervelib.encoders","l":"CanAndCoderSwerve"},{"p":"swervelib.encoders","l":"CANCoderSwerve"},{"p":"swervelib.parser.json","l":"ControllerPropertiesJson"},{"p":"swervelib.parser.json","l":"DeviceJson"},{"p":"swervelib.parser.json.modules","l":"LocationJson"},{"p":"swervelib.math","l":"Matter"},{"p":"swervelib.parser.json","l":"ModuleJson"},{"p":"swervelib.parser.json","l":"MotorConfigDouble"},{"p":"swervelib.parser.json","l":"MotorConfigInt"},{"p":"swervelib.imu","l":"NavXSwerve"},{"p":"swervelib.parser.json","l":"PhysicalPropertiesJson"},{"p":"swervelib.parser","l":"PIDFConfig"},{"p":"swervelib.parser.json","l":"PIDFPropertiesJson"},{"p":"swervelib.parser.deserializer","l":"PIDFRange"},{"p":"swervelib.imu","l":"Pigeon2Swerve"},{"p":"swervelib.imu","l":"PigeonSwerve"},{"p":"swervelib.encoders","l":"PWMDutyCycleEncoderSwerve"},{"p":"swervelib.telemetry","l":"Alert.SendableAlerts"},{"p":"swervelib.motors","l":"SparkFlexSwerve"},{"p":"swervelib.motors","l":"SparkFlexSwerve.SparkMAX_slotIdx"},{"p":"swervelib.motors","l":"SparkMaxSwerve.SparkMAX_slotIdx"},{"p":"swervelib.encoders","l":"SparkMaxAnalogEncoderSwerve"},{"p":"swervelib.motors","l":"SparkMaxBrushedMotorSwerve"},{"p":"swervelib.encoders","l":"SparkMaxEncoderSwerve"},{"p":"swervelib.motors","l":"SparkMaxSwerve"},{"p":"swervelib.encoders","l":"SwerveAbsoluteEncoder"},{"p":"swervelib","l":"SwerveController"},{"p":"swervelib.parser","l":"SwerveControllerConfiguration"},{"p":"swervelib","l":"SwerveDrive"},{"p":"swervelib.parser","l":"SwerveDriveConfiguration"},{"p":"swervelib.parser.json","l":"SwerveDriveJson"},{"p":"swervelib.telemetry","l":"SwerveDriveTelemetry"},{"p":"swervelib.imu","l":"SwerveIMU"},{"p":"swervelib.simulation","l":"SwerveIMUSimulation"},{"p":"swervelib.math","l":"SwerveMath"},{"p":"swervelib","l":"SwerveModule"},{"p":"swervelib.parser","l":"SwerveModuleConfiguration"},{"p":"swervelib.parser","l":"SwerveModulePhysicalCharacteristics"},{"p":"swervelib.simulation","l":"SwerveModuleSimulation"},{"p":"swervelib.motors","l":"SwerveMotor"},{"p":"swervelib.parser","l":"SwerveParser"},{"p":"swervelib.motors","l":"TalonFXSwerve"},{"p":"swervelib.motors","l":"TalonSRXSwerve"},{"p":"swervelib.telemetry","l":"SwerveDriveTelemetry.TelemetryVerbosity"}];updateSearchResults();
\ No newline at end of file
+typeSearchIndex = [{"p":"swervelib.imu","l":"ADIS16448Swerve"},{"p":"swervelib.imu","l":"ADIS16470Swerve"},{"p":"swervelib.imu","l":"ADXRS450Swerve"},{"p":"swervelib.telemetry","l":"Alert"},{"p":"swervelib.telemetry","l":"Alert.AlertType"},{"l":"All Classes and Interfaces","u":"allclasses-index.html"},{"p":"swervelib.encoders","l":"AnalogAbsoluteEncoderSwerve"},{"p":"swervelib.imu","l":"AnalogGyroSwerve"},{"p":"swervelib.parser.json.modules","l":"BoolMotorJson"},{"p":"swervelib.encoders","l":"CanAndCoderSwerve"},{"p":"swervelib.encoders","l":"CANCoderSwerve"},{"p":"swervelib.parser.json","l":"ControllerPropertiesJson"},{"p":"swervelib.parser.json","l":"DeviceJson"},{"p":"swervelib.parser.json.modules","l":"LocationJson"},{"p":"swervelib.math","l":"Matter"},{"p":"swervelib.parser.json","l":"ModuleJson"},{"p":"swervelib.parser.json","l":"MotorConfigDouble"},{"p":"swervelib.parser.json","l":"MotorConfigInt"},{"p":"swervelib.imu","l":"NavXSwerve"},{"p":"swervelib.parser.json","l":"PhysicalPropertiesJson"},{"p":"swervelib.parser","l":"PIDFConfig"},{"p":"swervelib.parser.json","l":"PIDFPropertiesJson"},{"p":"swervelib.parser.deserializer","l":"PIDFRange"},{"p":"swervelib.imu","l":"Pigeon2Swerve"},{"p":"swervelib.imu","l":"PigeonSwerve"},{"p":"swervelib.encoders","l":"PWMDutyCycleEncoderSwerve"},{"p":"swervelib.telemetry","l":"Alert.SendableAlerts"},{"p":"swervelib.motors","l":"SparkFlexSwerve"},{"p":"swervelib.motors","l":"SparkFlexSwerve.SparkMAX_slotIdx"},{"p":"swervelib.motors","l":"SparkMaxSwerve.SparkMAX_slotIdx"},{"p":"swervelib.encoders","l":"SparkMaxAnalogEncoderSwerve"},{"p":"swervelib.motors","l":"SparkMaxBrushedMotorSwerve"},{"p":"swervelib.encoders","l":"SparkMaxEncoderSwerve"},{"p":"swervelib.motors","l":"SparkMaxSwerve"},{"p":"swervelib.encoders","l":"SwerveAbsoluteEncoder"},{"p":"swervelib","l":"SwerveController"},{"p":"swervelib.parser","l":"SwerveControllerConfiguration"},{"p":"swervelib","l":"SwerveDrive"},{"p":"swervelib.parser","l":"SwerveDriveConfiguration"},{"p":"swervelib.parser.json","l":"SwerveDriveJson"},{"p":"swervelib.telemetry","l":"SwerveDriveTelemetry"},{"p":"swervelib","l":"SwerveDriveTest"},{"p":"swervelib.imu","l":"SwerveIMU"},{"p":"swervelib.simulation","l":"SwerveIMUSimulation"},{"p":"swervelib.math","l":"SwerveMath"},{"p":"swervelib","l":"SwerveModule"},{"p":"swervelib.parser","l":"SwerveModuleConfiguration"},{"p":"swervelib.parser","l":"SwerveModulePhysicalCharacteristics"},{"p":"swervelib.simulation","l":"SwerveModuleSimulation"},{"p":"swervelib.motors","l":"SwerveMotor"},{"p":"swervelib.parser","l":"SwerveParser"},{"p":"swervelib.motors","l":"TalonFXSwerve"},{"p":"swervelib.motors","l":"TalonSRXSwerve"},{"p":"swervelib.telemetry","l":"SwerveDriveTelemetry.TelemetryVerbosity"}];updateSearchResults();
\ No newline at end of file
diff --git a/swervelib/SwerveDrive.java b/swervelib/SwerveDrive.java
index 0244c57..96e165b 100644
--- a/swervelib/SwerveDrive.java
+++ b/swervelib/SwerveDrive.java
@@ -98,10 +98,6 @@ public class SwerveDrive
* Deadband for speeds in heading correction.
*/
private double HEADING_CORRECTION_DEADBAND = 0.01;
- /**
- * Whether heading correction PID is currently active.
- */
- private boolean correctionEnabled = false;
/**
* Swerve IMU device for sensing the heading of the robot.
*/
@@ -177,6 +173,7 @@ public class SwerveDrive
Rotation2d.fromDegrees(0))); // x,y,heading in radians; Vision measurement std dev, higher=less weight
zeroGyro();
+ setMaximumSpeed(maxSpeedMPS);
// Initialize Telemetry
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
@@ -452,16 +449,11 @@ public class SwerveDrive
&& (Math.abs(velocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(velocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
{
- if (!correctionEnabled)
- {
- lastHeadingRadians = getOdometryHeading().getRadians();
- correctionEnabled = true;
- }
velocity.omegaRadiansPerSecond =
- swerveController.headingCalculate(lastHeadingRadians, getOdometryHeading().getRadians());
+ swerveController.headingCalculate(getOdometryHeading().getRadians(), lastHeadingRadians);
} else
{
- correctionEnabled = false;
+ lastHeadingRadians = getOdometryHeading().getRadians();
}
}
@@ -686,6 +678,33 @@ public class SwerveDrive
return positions;
}
+ /**
+ * Getter for the {@link SwerveIMU}.
+ *
+ * @return generated {@link SwerveIMU}
+ */
+ public SwerveIMU getGyro()
+ {
+ return swerveDriveConfiguration.imu;
+ }
+
+ /**
+ * Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
+ * subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
+ *
+ * @param gyro expected gyroscope angle as {@link Rotation3d}.
+ */
+ public void setGyro(Rotation3d gyro)
+ {
+ if (SwerveDriveTelemetry.isSimulation)
+ {
+ setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
+ } else
+ {
+ setGyroOffset(imu.getRawRotation3d().minus(gyro));
+ }
+ }
+
/**
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
*/
@@ -820,6 +839,7 @@ public class SwerveDrive
swerveDriveConfiguration.physicalCharacteristics.optimalVoltage = optimalVoltage;
for (SwerveModule module : swerveModules)
{
+ module.maxSpeed = maximumSpeed;
if (updateModuleFeedforward)
{
module.feedforward = SwerveMath.createDriveFeedforward(optimalVoltage,
@@ -1030,9 +1050,7 @@ 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)}.
+ * the given timestamp of the vision measurement.
*
* @param robotPose Robot {@link Pose2d} as measured by vision.
* @param timestamp Timestamp the measurement was taken as time since startup, should be taken from
@@ -1050,24 +1068,6 @@ public class SwerveDrive
// resetOdometry(newOdometry);
}
-
- /**
- * Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
- * subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
- *
- * @param gyro expected gyroscope angle as {@link Rotation3d}.
- */
- public void setGyro(Rotation3d gyro)
- {
- if (SwerveDriveTelemetry.isSimulation)
- {
- setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
- } else
- {
- setGyroOffset(imu.getRawRotation3d().minus(gyro));
- }
- }
-
/**
* Helper function to get the {@link SwerveDrive#swerveController} for the {@link SwerveDrive} which can be used to
* generate {@link ChassisSpeeds} for the robot to orient it correctly given axis or angles, and apply
diff --git a/swervelib/SwerveDriveTest.java b/swervelib/SwerveDriveTest.java
new file mode 100644
index 0000000..37030a9
--- /dev/null
+++ b/swervelib/SwerveDriveTest.java
@@ -0,0 +1,198 @@
+package swervelib;
+
+import edu.wpi.first.math.geometry.Rotation2d;
+import edu.wpi.first.math.kinematics.SwerveModuleState;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.Timer;
+import swervelib.encoders.SwerveAbsoluteEncoder;
+
+/**
+ * Class to perform tests on the swerve drive.
+ */
+public class SwerveDriveTest
+{
+
+ /**
+ * Set the angle of the modules to a given {@link Rotation2d}
+ *
+ * @param swerveDrive {@link SwerveDrive} to use.
+ * @param moduleAngle {@link Rotation2d} to set every module to.
+ */
+ public static void angleModules(SwerveDrive swerveDrive, Rotation2d moduleAngle)
+ {
+ for (SwerveModule swerveModule : swerveDrive.getModules())
+ {
+ swerveModule.setDesiredState(new SwerveModuleState(0, moduleAngle), false, true);
+ }
+ }
+
+ /**
+ * Power the drive motors for the swerve drive to a set duty cycle percentage.
+ *
+ * @param swerveDrive {@link SwerveDrive} to control.
+ * @param percentage Duty cycle percentage of voltage to send to drive motors.
+ */
+ public static void powerDriveMotorsDutyCycle(SwerveDrive swerveDrive, double percentage)
+ {
+ for (SwerveModule swerveModule : swerveDrive.getModules())
+ {
+ swerveModule.getDriveMotor().set(percentage);
+ }
+ }
+
+ /**
+ * Power the angle motors for the swerve drive to a set percentage.
+ *
+ * @param swerveDrive {@link SwerveDrive} to control.
+ * @param percentage DutyCycle percentage to send to angle motors.
+ */
+ public static void powerAngleMotors(SwerveDrive swerveDrive, double percentage)
+ {
+ for (SwerveModule swerveModule : swerveDrive.getModules())
+ {
+ swerveModule.getAngleMotor().set(percentage);
+ }
+ }
+
+ /**
+ * Power the drive motors for the swerve drive to a set voltage.
+ *
+ * @param swerveDrive {@link SwerveDrive} to control.
+ * @param volts DutyCycle percentage of voltage to send to drive motors.
+ */
+ public static void powerDriveMotorsVoltage(SwerveDrive swerveDrive, double volts)
+ {
+ for (SwerveModule swerveModule : swerveDrive.getModules())
+ {
+ swerveModule.getDriveMotor().setVoltage(volts);
+ }
+ }
+
+ /**
+ * Power the angle motors for the swerve drive to a set voltage.
+ *
+ * @param swerveDrive {@link SwerveDrive} to control.
+ * @param volts Voltage to send to angle motors.
+ */
+ public static void powerAngleMotorsVoltage(SwerveDrive swerveDrive, double volts)
+ {
+ for (SwerveModule swerveModule : swerveDrive.getModules())
+ {
+ swerveModule.getAngleMotor().setVoltage(volts);
+ }
+ }
+
+ /**
+ * Set the modules to center to 0.
+ *
+ * @param swerveDrive Swerve Drive to control.
+ */
+ public static void centerModules(SwerveDrive swerveDrive)
+ {
+ angleModules(swerveDrive, Rotation2d.fromDegrees(0));
+ }
+
+ /**
+ * Find the minimum amount of power required to move the swerve drive motors.
+ *
+ * @param swerveDrive {@link SwerveDrive} to control.
+ * @param minMovement Minimum amount of movement to drive motors.
+ * @param testDelaySeconds Time in seconds for the motor to move.
+ * @param maxVolts The maximum voltage to send to drive motors.
+ * @return minimum voltage required.
+ */
+ public static double findDriveMotorKV(SwerveDrive swerveDrive, double minMovement, double testDelaySeconds,
+ double maxVolts)
+ {
+ double[] startingEncoders = new double[4];
+ double kV = 0;
+
+ SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, 0);
+ SwerveModule[] modules = swerveDrive.getModules();
+ for (int i = 0; i < modules.length; i++)
+ {
+ startingEncoders[i] = Math.abs(modules[i].getDriveMotor().getPosition());
+ }
+
+ for (double kV_new = 0; kV_new < maxVolts; kV_new += 0.0001)
+ {
+
+ SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, kV);
+ boolean foundkV = false;
+ double startTimeSeconds = Timer.getFPGATimestamp();
+ while ((Timer.getFPGATimestamp() - startTimeSeconds) < testDelaySeconds && !foundkV)
+ {
+ for (int i = 0; i < modules.length; i++)
+ {
+ if ((modules[i].getDriveMotor().getPosition() - startingEncoders[i]) > minMovement)
+ {
+ foundkV = true;
+ break;
+ }
+ }
+ }
+ if (foundkV)
+ {
+ SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, 0);
+ kV = kV_new;
+ }
+ }
+ return kV;
+ }
+
+ /**
+ * Find the coupling ratio for all modules.
+ *
+ * @param swerveDrive {@link SwerveDrive} to operate with.
+ * @param volts Voltage to send to angle motors to spin.
+ * @param automatic Attempt to automatically spin the modules.
+ * @return Average coupling ratio.
+ */
+ public static double findCouplingRatio(SwerveDrive swerveDrive, double volts, boolean automatic)
+ {
+ System.out.println("Stopping the Swerve Drive.");
+ SwerveDriveTest.powerDriveMotorsVoltage(swerveDrive, 0);
+ SwerveDriveTest.powerAngleMotorsVoltage(swerveDrive, 0);
+ Timer.delay(1);
+ double couplingRatioSum = 0;
+ for (SwerveModule module : swerveDrive.getModules())
+ {
+ if (module.getAbsoluteEncoder() == null)
+ {
+ throw new RuntimeException("Absolute encoders are required to find the coupling ratio.");
+ }
+ SwerveAbsoluteEncoder absoluteEncoder = module.getAbsoluteEncoder();
+ if (absoluteEncoder.readingError)
+ {
+ throw new RuntimeException("Absolute encoder encountered a reading error please debug.");
+ }
+ System.out.println("Fetching the current absolute encoder and drive encoder position.");
+ module.getAngleMotor().setVoltage(0);
+ Timer.delay(1);
+ Rotation2d startingAbsoluteEncoderPosition = Rotation2d.fromDegrees(absoluteEncoder.getAbsolutePosition());
+ double driveEncoderPositionRotations = module.getDriveMotor().getPosition() /
+ module.configuration.conversionFactors.drive;
+ if (automatic)
+ {
+ module.getAngleMotor().setVoltage(volts);
+ Timer.delay(0.01);
+ System.out.println("Rotating the module 360 degrees");
+ while (!Rotation2d.fromDegrees(absoluteEncoder.getAbsolutePosition()).equals(startingAbsoluteEncoderPosition))
+ ;
+ module.getAngleMotor().setVoltage(0);
+ } else
+ {
+ DriverStation.reportWarning(
+ "Spin the " + module.configuration.name + " module 360 degrees now, you have 1 minute.\n",
+ false);
+ Timer.delay(60);
+ }
+ double couplingRatio = (module.getDriveMotor().getPosition() / module.configuration.conversionFactors.drive) -
+ driveEncoderPositionRotations;
+ DriverStation.reportWarning(module.configuration.name + " Coupling Ratio: " + couplingRatio, false);
+ couplingRatioSum += couplingRatio;
+ }
+ DriverStation.reportWarning("Average Coupling Ratio: " + (couplingRatioSum / 4.0), false);
+ return (couplingRatioSum / 4.0);
+ }
+}
diff --git a/swervelib/SwerveModule.java b/swervelib/SwerveModule.java
index cc4cfef..260cdf0 100644
--- a/swervelib/SwerveModule.java
+++ b/swervelib/SwerveModule.java
@@ -112,7 +112,6 @@ public class SwerveModule
{
absoluteEncoder.factoryDefault();
absoluteEncoder.configure(moduleConfiguration.absoluteEncoderInverted);
- angleMotor.setPosition(getAbsolutePosition());
}
// Config angle motor/controller
@@ -122,6 +121,12 @@ public class SwerveModule
angleMotor.setInverted(moduleConfiguration.angleMotorInverted);
angleMotor.setMotorBrake(false);
+ // Set the position AFTER settings the conversion factor.
+ if (absoluteEncoder != null)
+ {
+ angleMotor.setPosition(getAbsolutePosition());
+ }
+
// Config drive motor/controller
driveMotor.configureIntegratedEncoder(moduleConfiguration.conversionFactors.drive);
driveMotor.configurePIDF(moduleConfiguration.velocityPIDF);
@@ -199,18 +204,22 @@ public class SwerveModule
driveMotor.set(percentOutput);
} else
{
- // Taken from the CTRE SwerveModule class.
- // https://api.ctr-electronics.com/phoenix6/release/java/src-html/com/ctre/phoenix6/mechanisms/swerve/SwerveModule.html#line.46
- /* From FRC 900's whitepaper, we add a cosine compensator to the applied drive velocity */
- /* To reduce the "skew" that occurs when changing direction */
- double steerMotorError = desiredState.angle.getDegrees() - getAbsolutePosition();
- /* If error is close to 0 rotations, we're already there, so apply full power */
- /* If the error is close to 0.25 rotations, then we're 90 degrees, so movement doesn't help us at all */
- double cosineScalar = Math.cos(Units.degreesToRadians(steerMotorError));
- /* Make sure we don't invert our drive, even though we shouldn't ever target over 90 degrees anyway */
- if (cosineScalar < 0.0 || desiredState.speedMetersPerSecond == 0)
+ double cosineScalar = 1.0;
+ if (configuration.useCosineCompensator)
{
- cosineScalar = 0.0;
+ // Taken from the CTRE SwerveModule class.
+ // https://api.ctr-electronics.com/phoenix6/release/java/src-html/com/ctre/phoenix6/mechanisms/swerve/SwerveModule.html#line.46
+ /* From FRC 900's whitepaper, we add a cosine compensator to the applied drive velocity */
+ /* To reduce the "skew" that occurs when changing direction */
+ double steerMotorError = desiredState.angle.getDegrees() - getAbsolutePosition();
+ /* If error is close to 0 rotations, we're already there, so apply full power */
+ /* If the error is close to 0.25 rotations, then we're 90 degrees, so movement doesn't help us at all */
+ cosineScalar = Math.cos(Units.degreesToRadians(steerMotorError));
+ /* Make sure we don't invert our drive, even though we shouldn't ever target over 90 degrees anyway */
+ if (cosineScalar < 0.0)
+ {
+ cosineScalar = 0.0;
+ }
}
double velocity = desiredState.speedMetersPerSecond * (cosineScalar);
diff --git a/swervelib/imu/Pigeon2Swerve.java b/swervelib/imu/Pigeon2Swerve.java
index d68e4f7..1ff4e18 100644
--- a/swervelib/imu/Pigeon2Swerve.java
+++ b/swervelib/imu/Pigeon2Swerve.java
@@ -102,14 +102,14 @@ 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();
- Rotation3d reading = 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;
}
@@ -135,8 +135,8 @@ public class Pigeon2Swerve extends SwerveIMU
{
// TODO: Switch to suppliers.
StatusSignal xAcc = imu.getAccelerationX();
- StatusSignal yAcc = imu.getAccelerationX();
- StatusSignal zAcc = imu.getAccelerationX();
+ StatusSignal yAcc = imu.getAccelerationY();
+ StatusSignal zAcc = imu.getAccelerationZ();
return Optional.of(new Translation3d(xAcc.refresh().getValue(),
yAcc.refresh().getValue(),
diff --git a/swervelib/motors/SparkFlexSwerve.java b/swervelib/motors/SparkFlexSwerve.java
index 27c9c4a..0c96826 100644
--- a/swervelib/motors/SparkFlexSwerve.java
+++ b/swervelib/motors/SparkFlexSwerve.java
@@ -404,6 +404,39 @@ public class SparkFlexSwerve extends SwerveMotor
setReference(setpoint, feedforward);
}
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ @Override
+ public double getVoltage()
+ {
+ return motor.getAppliedOutput() * motor.getBusVoltage();
+ }
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ @Override
+ public void setVoltage(double voltage)
+ {
+ motor.setVoltage(voltage);
+ }
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ @Override
+ public double getAppliedOutput()
+ {
+ return motor.getAppliedOutput();
+ }
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/motors/SparkMaxBrushedMotorSwerve.java b/swervelib/motors/SparkMaxBrushedMotorSwerve.java
index 3ec6536..e7018f0 100644
--- a/swervelib/motors/SparkMaxBrushedMotorSwerve.java
+++ b/swervelib/motors/SparkMaxBrushedMotorSwerve.java
@@ -402,6 +402,39 @@ public class SparkMaxBrushedMotorSwerve extends SwerveMotor
setReference(setpoint, feedforward);
}
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ @Override
+ public double getVoltage()
+ {
+ return motor.getAppliedOutput() * motor.getBusVoltage();
+ }
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ @Override
+ public void setVoltage(double voltage)
+ {
+ motor.setVoltage(voltage);
+ }
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ @Override
+ public double getAppliedOutput()
+ {
+ return motor.getAppliedOutput();
+ }
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/motors/SparkMaxSwerve.java b/swervelib/motors/SparkMaxSwerve.java
index e0aa13b..766b798 100644
--- a/swervelib/motors/SparkMaxSwerve.java
+++ b/swervelib/motors/SparkMaxSwerve.java
@@ -392,6 +392,39 @@ public class SparkMaxSwerve extends SwerveMotor
setReference(setpoint, feedforward);
}
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ @Override
+ public double getVoltage()
+ {
+ return motor.getAppliedOutput() * motor.getBusVoltage();
+ }
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ @Override
+ public void setVoltage(double voltage)
+ {
+ motor.setVoltage(voltage);
+ }
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ @Override
+ public double getAppliedOutput()
+ {
+ return motor.getAppliedOutput();
+ }
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/motors/SwerveMotor.java b/swervelib/motors/SwerveMotor.java
index 7d585ca..22b104d 100644
--- a/swervelib/motors/SwerveMotor.java
+++ b/swervelib/motors/SwerveMotor.java
@@ -101,6 +101,27 @@ public abstract class SwerveMotor
*/
public abstract void setReference(double setpoint, double feedforward, double position);
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ public abstract double getVoltage();
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ public abstract void setVoltage(double voltage);
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ public abstract double getAppliedOutput();
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/motors/TalonFXSwerve.java b/swervelib/motors/TalonFXSwerve.java
index cf7effb..d6959ce 100644
--- a/swervelib/motors/TalonFXSwerve.java
+++ b/swervelib/motors/TalonFXSwerve.java
@@ -40,7 +40,7 @@ public class TalonFXSwerve extends SwerveMotor
/**
* Conversion factor for the motor.
*/
- private double conversionFactor;
+ private double conversionFactor;
/**
* Current TalonFX configuration.
*/
@@ -343,6 +343,39 @@ public class TalonFXSwerve extends SwerveMotor
}
}
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ @Override
+ public double getVoltage()
+ {
+ return motor.getMotorVoltage().refresh().getValue();
+ }
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ @Override
+ public void setVoltage(double voltage)
+ {
+ motor.setVoltage(voltage);
+ }
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ @Override
+ public double getAppliedOutput()
+ {
+ return motor.getDutyCycle().refresh().getValue();
+ }
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/motors/TalonSRXSwerve.java b/swervelib/motors/TalonSRXSwerve.java
index 0290d82..4c42ce7 100644
--- a/swervelib/motors/TalonSRXSwerve.java
+++ b/swervelib/motors/TalonSRXSwerve.java
@@ -256,7 +256,6 @@ public class TalonSRXSwerve extends SwerveMotor
motor.set(percentOutput);
}
-
/**
* Convert the setpoint into native sensor units.
*
@@ -303,6 +302,39 @@ public class TalonSRXSwerve extends SwerveMotor
feedforward / nominalVoltage);
}
+ /**
+ * Get the voltage output of the motor controller.
+ *
+ * @return Voltage output.
+ */
+ @Override
+ public double getVoltage()
+ {
+ return motor.getMotorOutputVoltage();
+ }
+
+ /**
+ * Set the voltage of the motor.
+ *
+ * @param voltage Voltage to set.
+ */
+ @Override
+ public void setVoltage(double voltage)
+ {
+ motor.setVoltage(voltage);
+ }
+
+ /**
+ * Get the applied dutycycle output.
+ *
+ * @return Applied dutycycle output to the motor.
+ */
+ @Override
+ public double getAppliedOutput()
+ {
+ return motor.getMotorOutputPercent();
+ }
+
/**
* Get the velocity of the integrated encoder.
*
diff --git a/swervelib/parser/SwerveModuleConfiguration.java b/swervelib/parser/SwerveModuleConfiguration.java
index 2e8d9f8..24d0625 100644
--- a/swervelib/parser/SwerveModuleConfiguration.java
+++ b/swervelib/parser/SwerveModuleConfiguration.java
@@ -62,6 +62,10 @@ public class SwerveModuleConfiguration
* Name for the swerve module for telemetry.
*/
public String name;
+ /**
+ * Should do cosine compensation when not pointing correct direction;.
+ */
+ public boolean useCosineCompensator;
/**
* Construct a configuration object for swerve modules.
@@ -80,6 +84,7 @@ public class SwerveModuleConfiguration
* @param physicalCharacteristics Physical characteristics of the swerve module.
* @param name The name for the swerve module.
* @param conversionFactors Conversion factors to be applied to the drive and angle motors.
+ * @param useCosineCompensator Should use cosineCompensation.
*/
public SwerveModuleConfiguration(
SwerveMotor driveMotor,
@@ -95,7 +100,8 @@ public class SwerveModuleConfiguration
boolean absoluteEncoderInverted,
boolean driveMotorInverted,
boolean angleMotorInverted,
- String name)
+ String name,
+ boolean useCosineCompensator)
{
this.driveMotor = driveMotor;
this.angleMotor = angleMotor;
@@ -110,6 +116,7 @@ public class SwerveModuleConfiguration
this.velocityPIDF = velocityPIDF;
this.physicalCharacteristics = physicalCharacteristics;
this.name = name;
+ this.useCosineCompensator = useCosineCompensator;
}
/**
@@ -127,6 +134,7 @@ public class SwerveModuleConfiguration
* @param velocityPIDF Velocity PIDF configuration.
* @param physicalCharacteristics Physical characteristics of the swerve module.
* @param name Name for the module.
+ * @param useCosineCompensator Should use cosineCompensation.
*/
public SwerveModuleConfiguration(
SwerveMotor driveMotor,
@@ -139,7 +147,8 @@ public class SwerveModuleConfiguration
PIDFConfig anglePIDF,
PIDFConfig velocityPIDF,
SwerveModulePhysicalCharacteristics physicalCharacteristics,
- String name)
+ String name,
+ boolean useCosineCompensator)
{
this(
driveMotor,
@@ -155,7 +164,8 @@ public class SwerveModuleConfiguration
false,
false,
false,
- name);
+ name,
+ useCosineCompensator);
}
diff --git a/swervelib/parser/json/ModuleJson.java b/swervelib/parser/json/ModuleJson.java
index d345415..b9f2404 100644
--- a/swervelib/parser/json/ModuleJson.java
+++ b/swervelib/parser/json/ModuleJson.java
@@ -53,6 +53,10 @@ public class ModuleJson
* The location of the swerve module from the center of the robot in inches.
*/
public LocationJson location;
+ /**
+ * Should do cosine compensation when not pointing correct direction;.
+ */
+ public boolean useCosineCompensator = true;
/**
* Create the swerve module configuration based off of parsed data.
@@ -131,6 +135,7 @@ public class ModuleJson
absoluteEncoderInverted,
inverted.drive,
inverted.angle,
- name.replaceAll("\\.json", ""));
+ name.replaceAll("\\.json", ""),
+ useCosineCompensator);
}
}