YAGSL
  • Welcome to Yet Another Swerve Document
    • Resources
  • Overview
    • What we do
    • Our Features
      • Telemetry
      • Simulation
      • Lock Pose
      • Max Speed
      • Chassis Speed Discretization
      • Vision Odometry
      • Heading Correction
      • Auto-centering Modules
      • Offset Offloading
      • Cosine Compensation
      • Module Auto-synchronization
      • Angular Velocity Compensation
    • Changelog
    • Java API
    • Example Code
    • Config Generator
    • 💸Donations
    • 👕Merch
    • Discord
  • Fundamentals
    • Swerve Drive
    • Swerve Modules
  • Bringing up swerve
    • Preface
    • Swerve Information
    • Check your gyroscope
    • Check your motors
    • Creating your first configuration
  • Configuring YAGSL
    • Getting to know your robot
      • Gear Ratio
    • Dependency Installation
    • Configuration
      • Swerve Drive Configuration
      • Physical Properties Configuration
      • PIDF Properties Configuration
        • PIDF
      • Swerve Module Configuration
      • Controller Properties Configuration
      • Device Configuration
    • Code Setup
    • Standard Conversion Factors
    • How to tune PIDF
    • When to invert?
    • Flowcharts
    • The eight steps
    • Swerve Drive Drift
    • SparkMAX Common Problems
    • Verifying your Module Locations
    • Tuning out Drift
  • Devices
    • Gyroscope
      • NavX
      • Pigeon
      • Pigeon 2.0
      • ADXRS450
      • ADIS16448
      • ADIS16470
    • Motor Controllers
      • SparkMAX
      • SparkFlex
      • TalonFX
    • Absolute Encoders
  • Analytics and Debugging
    • FRC Web Components
    • Advantage Scope
  • Product Guides
    • Java API
    • PathPlanner
    • ❌Tuning PID with REV Hardware Client
    • ❌Drive Code
  • Legacy Documentation
Powered by GitBook
On this page
  • Import YAGSL
  • Online
  • Offline
  • How to create a swerve drive?
  • How to create a SwerveDrive using JSON.
  • Telemetry
  • Follow along the example here!
  • Drive Code

Was this helpful?

Edit on GitHub
  1. Configuring YAGSL

Code Setup

PreviousDevice ConfigurationNextStandard Conversion Factors

Last updated 3 months ago

Was this helpful?

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

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

How to create a swerve drive?

How to create a SwerveDrive using JSON.

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();

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 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;

 = ;

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(() -> {

      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);
    });
  }

Copy the into src/main/java into your project.

Be sure to too!

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 directory. You can also create the Configuration objects manually and instantiate your Swerve Drive that way.

This example program creates the in the , as you should only interact with it in the if you are using command based programming.

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 .

swervelib directory from YAGSL-Example
install all dependencies
deploy
SwerveDrive
SwerveSubsystem
SwerveSubsystem
configuration documentation
3rd Party LibrariesFIRST Robotics Competition Documentation
Logo
https://github.com/BroncBotz3481/YAGSL-Example/tree/main/src/main/java/frc/robot