-
Notifications
You must be signed in to change notification settings - Fork 37
Home
Welcome to the YAGSL wiki!
YAGSL can be utilized to generate a Swerve Drive for MAX Swerve, SDS MK4i, and SDS MK4 it uses generic. This can be configured via JSON for ease.
The deploy directory is used to add arbitrary files to the robot code, YAGSL uses this directory to store swerve module configurations. To get the location of the deploy directory you should use the function Filesystem.getDeployDirectory()
. Swerve Drive initialization requires certain files and folders to be present in whichever directory you define as the "JSONDirectory" the folders are "modules", "modules/back", and "modules/front". The files required to be present in the directory are "swerve.json", "modules/back/left.json", "modules/back/right.json", "modules/front/left.json", and "modules/front/right.json". Below is an example of what a swerve "JSONDirectory" looks like in "deploy/swerve" (new File(Filesystem.getDeployDirectory(), "swerve")
)
├── src
│ └── main
│ ├── deploy
│ │ ├── example.txt
│ │ └── swerve
│ │ ├── modules
│ │ │ ├── back
│ │ │ │ ├── left.json
│ │ │ │ └── right.json
│ │ │ └── front
│ │ │ ├── left.json
│ │ │ └── right.json
│ │ └── swerve.json
...
JSON stands for "JavaScript Object Notation" it is a popular format for configuration, and string data representation. Learn more here
In order to add custom periodic functions to synchronize steering encoders, or get the velocity of DutyCycle
and AnalogEncoder
s the a getInstance()
function needs to exist in your robot class. Simply add this to you robot class and the library will work.
private static Robot instance;
public Robot()
{
instance = this;
}
public static Robot getInstance()
{
return instance;
}
- Install CTRE and REV vendor dependencies.
- Clone YAGSL.
git clone https://github.com/BroncBotz3481/YAGSL
- Move swervelib into
src/main/frc/java/subsystems/swervedrive/swerve
- Copy example JSON directory or create your own then move it into
src/main/frc/deploy/swerve
- Create SwerveDrive from JSON directory via
SwerveDrive drive = SwerveParser.fromJSONDirectory(new File(Filesystem.getDeployDirectory(), "swerve"));
- View the java docs in docs/index.html
- Experiment!
swerve.json
stores the robot wide configuration options. The configurations in swerve.json
are as follows.
Name | Units | Required | Description |
---|---|---|---|
WheelBase | Inches | ✔️ | The distance between the centers of the front and back wheels of the robot in inches. |
TrackWidth | Inches | ✔️ | The distance between the centers of the right and left wheels of the robot in inches. |
WheelDiamter | Inches | ✔️ | The diameter of the wheels for the swerve modules in inches. |
Speed | Dictionary | ✔️ | Contains the physical and virtual speed limitations of the swerve drive. |
Acceleration | Dictionary | ✔️ | Contains the acceleration limitations for driver control via SlewRateLimiters . |
Drive | Dictionary | ✔️ | Contains the global configurations that apply to all drive motors on the swerve drive. |
Steer | Dictionary | ✔️ | Contains the global configurations that apply to all of the steering motors on the swerve drive. |
Gyro | Dictionary | ✔️ | Contains the configuration for the gyroscope, currently the only supported gyroscope is the Pigeon2. |
Initial Pose | Dictionary | ✔️ | Contains the configuration for the initial pose of the robot in inches and degrees. |
Name | Units | Required | Description |
---|---|---|---|
MetersPerSecond | double | ✔️ | Virtual speed limitation for the driver when controlling the swerve drive for both forward and strafe directions. |
PhysicalMetersPerSecond | double | ✔️ | The speed limitation to ensure the wheels to not exceed on every module. |
RadianPerSecond | double | ✔️ | The angular speed which the swerve drive should be able to achieve. Multiplied by PI internally. |
Name | Units | Required | Description |
---|---|---|---|
MetersPerSecond | double | ✔️ | Virtual acceleration limitation for the driver when controlling the swerve drive for both forward and strafe directions. Used with SlewRateLimiter . |
RadianPerSecond | double | ✔️ | The angular acceleration which the swerve drive should be able to achieve. Multiplied by PI internally and used with SlewRateLimiter . |
Name | Units | Required | Description |
---|---|---|---|
Inverted | boolean | ✔️ | Whether or not the drive motors for the swerve drive are inverted. Also possible to call the setInverted function on the module drive motors. |
GearRatio | double | ✔️ | The gear ratio in which the drive motor must turn in order for a complete rotation of the wheel. |
MaxPower | Percentage | ✔️ | The maximum output drive motor controllers should supply. Useful for tuning the robot power consumption to lower risk of brown outs. |
CurrentLimit | Amps | ❌ | Optional configuration setting. The current limit that the motor controller should abide by. |
PID | Dictionary | ❌ | Optional configuration setting. Supplies the values for PID that would be used for all onboard drive motor PID's of swerve modules. |
Name | Units | Required | Description |
---|---|---|---|
Inverted | boolean | ✔️ | Whether or not the steering motors for the swerve drive are inverted. |
GearRatio | double | ✔️ | The gear ratio in which the steering motor must turn in order for a complete rotation of the wheel. |
MaxPower | Percentage | ✔️ | The maximum output steering motor controllers should supply. Useful for tuning the robot power consumption to lower risk of brown outs. |
CurrentLimit | Amps | ❌ | Optional configuration setting. The current limit that the motor controller should abide by. |
PID | Dictionary | ❌ | Optional configuration setting. Supplies the values for PID that would be used for all onboard drive motor PID's of swerve modules. |
Name | Units | Required | Description |
---|---|---|---|
Inverted | boolean | ✔️ | Whether or not the gyroscope for the swerve drive are inverted. |
Type | String | ✔️ | Must be "Pigeon2" currently since no other gyroscope is supported yet. |
ID | CAN ID | ✔️ | The CAN ID for the Pigeon2. |
CANBus | String | ❌ | Optional CAN Bus name in which the Pigeon2 is current residing on. |
Name | Units | Required | Description |
---|---|---|---|
X | Inches | ✔️ | The distance from your alliance wall to the center of your robot in inches. |
Y | Inches | ✔️ | The distance from the field wall to the center of your robot in inches. |
Rotation | Degrees | ✔️ | The rotation of your robot on the field on the field when facing away from the alliance wall. |
Name | Units | Required | Description |
---|---|---|---|
P | double | ✔️ | Proportional gain for closed loop. This is multiplied by closed loop error in sensor units. |
I | double | ✔️ | Integral gain for closed loop. This is multiplied by closed loop error in sensor units every PID loop. |
D | double | ✔️ | Derivative gain for closed loop. This is multiplied by derivative error (sensor units per PID loop). |
F | double | ✔️ | Feedforward gain for closed loop. |
IntegralZone | double | ✔️ | Integral Zone can be used to auto clear the integral accumulator if the sensor position is too far from the target. This prevents unstable oscillation if the kI is too large. Value is in sensor units. |
Set the PIDF coefficients for the closed loop PID onboard the motor controller. Tuning the PID P = .5 and increase it by .1 until oscillations occur, then decrease by .05 then .005 until oscillations stop and angle is perfect or near perfect. I = 0 tune this if your PID never quite reaches the target, after tuning D. Increase this by P*.01 each time and adjust accordingly. D = 0 tune this if the PID accelerates too fast, it will smooth the motion. Increase this by P*10 and adjust accordingly. F = 0 tune this if the PID is being used for velocity, the F is multiplied by the target and added to the voltage output. Increase this by 0.01 until the PIDF reaches the desired state in a fast enough manner. Documentation for this is best described by CTRE here
What is modules/back/left.json
modules/back/right.json
modules/front/left.json
and modules/front/right.json
Name | Units | Required | Description |
---|---|---|---|
IntegratedAbsoluteEncoder | boolean | ❌ | Whether or not the absolute encoder is integrated into the motor controller via expansion port. Currently this only works with the SparkMax to fetch the attached DutyCycle AbsoluteEncoder. |
AbsoluteEncoder | Dictionary | ✔️ | The absolute encoder configuration. |
Motor | Dictionary | ✔️ | The motor configuration options. |
Name | Units | Required | Description |
---|---|---|---|
Type | String | ✔️ | The absolute encoder type, current options are CANCoder,ThriftyBot,AnalogEncoder,SRXMagEncoder,REVThoroughbore. If the encoder is integrated put anything else in. |
ID | CAN/Channel ID | ✔️ | The CAN ID for CANCoders, or the Channel ID for other encoders. |
Offset | Degrees | ✔️ | The offset in degrees for the motor to be at 0. |
CANBus | String | ❌ | Optional configuration setting to define the can bus of the CANCoder if on a CANivore. |
Name | Units | Required | Description |
---|---|---|---|
Drive | Dictionary | ✔️ | The drive motor configuration for the module. |
Steer | Dictionary | ✔️ | The steering motor configuration for the module. |
Name | Units | Required | Description |
---|---|---|---|
Type | String | ✔️ | The motor type, current options are "Neo" or "Falcon". |
ID | CAN ID | ✔️ | The CAN ID for the motor controller. |
CANBus | String | ❌ | Optional configuration setting to define the can bus of the Falcon if on a CANivore. |
PID | Dictionary | ❌ | Optional configuration setting. Supplies the values for PID that would be used for the motor. |
Name | Units | Required | Description |
---|---|---|---|
Type | String | ✔️ | The motor type, current options are "Neo" or "Falcon". |
ID | CAN ID | ✔️ | The CAN ID for the motor controller. |
CANBus | String | ❌ | Optional configuration setting to define the can bus of the Falcon if on a CANivore. |
FreeSpeedRPM | integer | ✔️ | The free speed RPM of the motor, used for feedforward calculation of the PID. |
PID | Dictionary | ❌ | Optional configuration setting. Supplies the values for PID that would be used for the motor. |