Code Setup

Import YAGSL

Online

Use WPILib vendor deps to install it.

The URL for YAGSL vendordep is

https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json

Offline

Copy the swervelib directory from YAGSL-Example into src/main/java into your project.

You cannot have both the offline and online versions installed at the same time! Errors will occur!

Be sure to install all dependencies too!

How to create a swerve drive?

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.

How to create a SwerveDrive using JSON.

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 = Units.feetToMeters(4.5)
File swerveJsonDirectory = new File(Filesystem.getDeployDirectory(),"swerve");
SwerveDrive  swerveDrive = new SwerveParser(directory).createSwerveDrive();

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

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 Shuffleboard or SmartDashboard. 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;

 = ;

Follow along the example here!

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!

Drive Code

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(() -> {
      double xInput = Math.pow(translationX.getAsDouble(), 3); // Smooth controll out
      double yInput = Math.pow(translationY.getAsDouble(), 3); // Smooth controll out
      // Make the robot move
      driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(xInput, yInput,
                                                                      headingX.getAsDouble(),
                                                                      headingY.getAsDouble(),
                                                                      swerveDrive.getYaw().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);
    });
  }

Last updated