YAGSL-Example
YAGSL-Example copied to clipboard
Yet Another General Swerve Library Example Project
Yet Another Generic Swerve Library (YAGSL) Example project
YAGSL is intended to be an easy implementation of a generic swerve drive that should work for most square swerve drives. The project is documented on here. The JSON documentation can also be found here
This example is intended to be a starting place on how to use YAGSL. By no means is this intended to be the base of your robot project. YAGSL provides an easy way to generate a SwerveDrive which can be used in both TimedRobot and Command-Based Robot templates.
Overview
Installation
Vendor URL:
https://broncbotz3481.github.io/YAGSL-Lib/yagsl/yagsl.json
Javadocs here
Library here
Code here
WIKI
Config Generation
Create an issue if there is any errors you find!
We will be actively montoring this and fix any issues when we can!
Development
- Development happens here on
YAGSL-Example
.YAGSL
andYAGSL-Lib
are updated on a nightly basis.
Support our developers!
TL;DR Generate and download your configuration here and unzip it so that it follows structure below:
deploy
└── swerve
├── controllerproperties.json
├── modules
│ ├── backleft.json
│ ├── backright.json
│ ├── frontleft.json
│ ├── frontright.json
│ ├── physicalproperties.json
│ └── pidfproperties.json
└── swervedrive.json
Then create your SwerveDrive object like this.
import java.io.File;
import edu.wpi.first.wpilibj.Filesystem;
import swervelib.parser.SwerveParser;
import swervelib.SwerveDrive;
import edu.wpi.first.math.util.Units;
SwerveDrive swerveDrive=new SwerveParser(new File(Filesystem.getDeployDirectory(),"swerve")).createSwerveDrive(Units.feetToMeters(14.5));
Migrating Old Configuration Files
- Delete
wheelDiamter
,gearRatio
,encoderPulsePerRotation
fromphysicalproperties.json
- Add
optimalVoltage
tophysicalproperties.json
- Delete
maxSpeed
andoptimalVoltage
fromswervedrive.json
-
IF a swerve module doesn't have the same drive motor or steering motor as the rest of the
swerve drive you MUST specify a
conversionFactor
for BOTH the drive and steering motor in the modules configuration JSON file. IF one of the motors is the same as the rest of the swerve drive and you want to use thatconversionFactor
, set theconversionFactor
in the module JSON configuration to 0. - You MUST specify the maximum speed when creating a
SwerveDrive
throughnew SwerveParser(directory).createSwerveDrive(maximumSpeed);
- IF you do not want to set
conversionFactor
inswervedrive.json
. You can pass it into the constructor as a parameter like this
double DriveConversionFactor = SwerveMath.calculateMetersPerRotation(Units.inchesToMeters(WHEEL_DIAMETER), GEAR_RATIO, ENCODER_RESOLUTION);
double SteeringConversionFactor = SwerveMath.calculateDegreesPerSteeringRotation(GEAR_RATIO, ENCODER_RESOLUTION);
SwerveDrive swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, SteeringConversionFactor, DriveConversionFactor);
Falcon Support would not have been possible without support from Team 1466 Webb Robotics!
Configuration Tips
My Robot Spins around uncontrollably during autonomous or when attempting to set the heading!
- Invert the gyro scope.
- Invert the drive motors for every module. (If front and back become reversed when turning)
Angle motors are erratic.
- Invert the angle motor.
My robot is heavy.
- Implement momentum velocity limitations in SwerveMath.
Ensure the IMU is centered on the robot
Maintainers
- @thenetworkgrinch
- @Technologyman00
Special Thanks to Team 7900! Trial N' Terror
Without the debugging and aid of Team 7900 the project could never be as stable or active as it is.