YAGSL supports a wide variety of Gyroscopes in an effort to best help teams of all budgets, while we do recommend the NavX or Pigeon2 and officially support and have tested them, we do try to support others with varying degrees of success.
- Gyroscope readings increase when rotated counter clockwise1.
- Yaw reading is the robot heading.
- Gyroscope
0
is the desired robot "front".
YAGSL creates wrappers over all supported Gyroscope types to uniformly fetch and set data that is needed for a Swerve Drive to operate, this wrapper is called SwerveIMU
. All Gyroscope's can be fetched from the SwerveDrive
object via the SwerveDriveConfiguration
object which is generated from the swervedrive.json
file given. For a user program to fetch the raw gyroscope object all you must do is as follows while casting the object to the right type, in our case this will be a NavX AHRS
class.
/**
* Initialize {@link SwerveDrive} with the directory provided.
*
* @param directory Directory of swerve drive config files.
*/
public SwerveSubsystem(File directory)
{
// Angle conversion factor is 360 / (GEAR RATIO * ENCODER RESOLUTION)
// In this case the gear ratio is 12.8 motor revolutions per wheel rotation.
// The encoder resolution per motor revolution is 1 per motor revolution.
double angleConversionFactor = SwerveMath.calculateDegreesPerSteeringRotation(12.8, 1);
// Motor conversion factor is (PI * WHEEL DIAMETER IN METERS) / (GEAR RATIO * ENCODER RESOLUTION).
// In this case the wheel diameter is 4 inches, which must be converted to meters to get meters/second.
// The gear ratio is 6.75 motor revolutions per wheel rotation.
// The encoder resolution per motor revolution is 1 per motor revolution.
double driveConversionFactor = SwerveMath.calculateMetersPerRotation(Units.inchesToMeters(4), 6.75, 1);
// Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created.
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
try
{
swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor);
} catch (Exception e)
{
throw new RuntimeException(e);
}
swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot via angle.
AHRS navx = (AHRS)swerveDrive.getGyro().getIMU();
}
These gyroscopes have been thoroughly tested and are used by many FRC teams. Generally speaking these will give you the best performance and reliability as well as help from the community at large.
NavX2 MXP by Studica
{% embed url="https://www.studica.ca/en/navx-2-mxp-robotics-navigation-sensor" %}
Pigeon2 IMU by CTRE
{% embed url="https://store.ctr-electronics.com/pigeon-2/" %}
{% hint style="warning" %}
Only CTRE devices currently support the canbus
option, if your device is using the roboRIO canbus
you must use the value of null
or "rio"
for supported CTRE devices. If you are using a CANivore, and the device is on the CANivore bus, the name must match the CANivore name.
{% endhint %}
In swervedrive.json
you specify the gyroscope with the
{
"imu": {
"type": "pigeon2",
"id": 13,
"canbus": "canivore"
},
"invertedIMU": true,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
{% hint style="warning" %} If your robot spins out of control without any controller input you probably need to invert your IMU here. {% endhint %}
Device | type | Communication |
---|---|---|
Pigeon | pigeon |
CAN; does not support CANivore. |
Pigeon2 | pigeon2 |
CAN; supports CANivore |
Canandgyro | canandgyro |
CAN; does not support CANivore. |
NavX | navx , navx_spi |
roboRIO MXP SPI |
NavX | navx_i2c |
I2C port on the roboRIO MXP. Not recommended! |
NavX | navx_usb |
Serial over USB Cable to roboRIO (not recommended) |
NavX | navx_mxp_serial |
Serial over roboRIO MXP |
ADIS16448 | adis16448 |
roboRIO MXP |
ADIS16470 | adis16470 |
roboRIO SPI port |
ADXRS450 | adxrs450 |
roboRIO SPI port. |
Analog Gyro | analog |
AnalogInput |
Footnotes
-
Also known as CounterClockWise Positive or CCW+ ↩