Use WPILib vendor deps to install it.
{% embed url="https://docs.wpilib.org/en/stable/docs/software/vscode-overview/3rd-party-libraries.html#rd-party-libraries" %}
The URL for YAGSL vendordep is
https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json
Copy the swervelib
directory from YAGSL-Example into src/main/java
into your project.
{% hint style="warning" %} You cannot have both the offline and online versions installed at the same time! Errors will occur! {% endhint %}
{% hint style="info" %} Be sure to install all dependencies too! {% endhint %}
YAGSL is unique in the fact that you can create a swerve drive based entirely off of JSON configuration files. The JSON configuration files should be located in the deploy
directory. You can also create the Configuration objects manually and instantiate your Swerve Drive that way.
This example program creates the SwerveDrive
in the SwerveSubsystem
, as you should only interact with it in the SwerveSubsystem
if you are using command based programming.
import java.io.File;
import edu.wpi.first.wpilibj.Filesystem;
import swervelib.parser.SwerveParser;
import swervelib.SwerveDrive;
import edu.wpi.first.math.util.Units;
double maximumSpeed = Units.feetToMeters(4.5)
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
SwerveDrive swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed);
This way is fast and easy, no more large unmaintainable and daunting constants file to worry about! To create a JSON directory look at the configuration documentation.
Telemetry can be great when you want it and YAGSL has no shortage of useful telemetry, such as the Module[...]
fields you will see in a driver dashboard. However Telemetry causes delays and slowdowns to the program so sometimes it is best to the them off. To do this change
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
{% embed url="https://github.com/BroncBotz3481/YAGSL-Example/tree/main/src/main/java/frc/robot" %}
{% hint style="info" %} Sometimes I like to include really advanced features in the example (like last year I had a drive to point command) so be sure to check back and see what we have done! {% endhint %}
Inside the SwerveSubsystem
you can make your own drive code as easy as a few lines.
/**
* Command to drive the robot using translative values and heading as a setpoint.
*
* @param translationX Translation in the X direction.
* @param translationY Translation in the Y direction.
* @param headingX Heading X to calculate angle of the joystick.
* @param headingY Heading Y to calculate angle of the joystick.
* @return Drive command.
*/
public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier headingX,
DoubleSupplier headingY)
{
return run(() -> {
Translation2d scaledInputs = SwerveMath.scaleTranslation(new Translation2d(translationX.getAsDouble(),
translationY.getAsDouble()), 0.8);
// Make the robot move
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(scaledInputs.getX(), scaledInputs.getY(),
headingX.getAsDouble(),
headingY.getAsDouble(),
swerveDrive.getOdometryHeading().getRadians(),
swerveDrive.getMaximumVelocity()));
});
}
/**
* Command to drive the robot using translative values and heading as angular velocity.
*
* @param translationX Translation in the X direction.
* @param translationY Translation in the Y direction.
* @param angularRotationX Rotation of the robot to set
* @return Drive command.
*/
public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translationY, DoubleSupplier angularRotationX)
{
return run(() -> {
// Make the robot move
swerveDrive.drive(new Translation2d(translationX.getAsDouble() * swerveDrive.getMaximumVelocity(),
translationY.getAsDouble() * swerveDrive.getMaximumVelocity()),
angularRotationX.getAsDouble() * swerveDrive.getMaximumAngularVelocity(),
true,
false);
});
}