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.
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
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. */publicCommanddriveCommand(DoubleSupplier translationX,DoubleSupplier translationY,DoubleSupplier headingX,DoubleSupplier headingY) {returnrun(() -> {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. */publicCommanddriveCommand(DoubleSupplier translationX,DoubleSupplier translationY,DoubleSupplier angularRotationX) {returnrun(() -> {// Make the robot moveswerveDrive.drive(new Translation2d(translationX.getAsDouble() *swerveDrive.getMaximumVelocity(),translationY.getAsDouble() *swerveDrive.getMaximumVelocity()),angularRotationX.getAsDouble() *swerveDrive.getMaximumAngularVelocity(),true,false); }); }