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
  • Motor Checklist
  • Swerve Motor Wrapper
  • Motor Controller Configuration
  • Possible Motor Controller Types

Was this helpful?

Edit on GitHub
  1. Devices

Motor Controllers

PreviousADIS16470NextSparkMAX

Last updated 3 months ago

Was this helpful?

YAGSL supports most common FRC motor controllers (except 's) and while we recommend using a brushless motor with an integrated encoder if at all possible we support brushed motors with external quadrature encoders as well ONLY with SparkMAX's.

The integrated encoder value will show up in your driver dashboard under swerve/modules/.../Raw Motor Encoder as directly outputting the encoder value from the motor.

Motor Checklist

Swerve Motor Wrapper

YAGSL created wrappers over all supported Motor Controllers to uniformly fetch and set data that is needed for a Swerve Drive to operate. This wrapper is called . All 's can be fetched via the configuration object motor definitions and . The is able to be fetched by easily.

 /**
   * Initialize {@link SwerveDrive} with the directory provided.
   *
   * @param directory Directory of swerve drive config files.
   */
  public SwerveSubsystem(File directory)
  {
    // Angle conversion factor is 360 / (GEAR RATIO * ENCODER RESOLUTION)
    //  In this case the gear ratio is 12.8 motor revolutions per wheel rotation.
    //  The encoder resolution per motor revolution is 1 per motor revolution.
    double angleConversionFactor = SwerveMath.calculateDegreesPerSteeringRotation(12.8, 1);
    // Motor conversion factor is (PI * WHEEL DIAMETER IN METERS) / (GEAR RATIO * ENCODER RESOLUTION).
    //  In this case the wheel diameter is 4 inches, which must be converted to meters to get meters/second.
    //  The gear ratio is 6.75 motor revolutions per wheel rotation.
    //  The encoder resolution per motor revolution is 1 per motor revolution.
    double driveConversionFactor = SwerveMath.calculateMetersPerRotation(Units.inchesToMeters(4), 6.75, 1);

    // Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created.
    SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
    try
    {
      swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor);
    } catch (Exception e)
    {
      throw new RuntimeException(e);
    }
    swerveDrive.setHeadingCorrection(false); // Heading correction should only be used while controlling the robot via angle.

    for(SwerveModule m : swerveDrive.getModules())
    {
      System.out.println("Module Name: "+m.configuration.name);
      CANSparkMax steeringMotor = ()m.getAngleMotor().getMotor(); 
      CANSparkMax driveMotor = ()m.getDriveMotor().getMotor(); 
    }
  }

Motor Controller Configuration

Only CTRE devices currently support the canbus option, if your device is using the roboRIO canbus you must use the value of null or "rio" for supported CTRE devices. If you are using a CANivore, and the device is on the CANivore bus, the name must match the CANivore name.

Inside any module JSON such as frontleft.json,frontright.json,backleft.json,backright.json this is what you would see to configure a motor controller.

{
  "drive": {
    "type": ,
    "id": ,
    "canbus": 
  },
  "angle": {
    "type": ,
    "id": ,
    "canbus": 
  },
  "encoder": {
    "type": "cancoder",
    "id": 11,
    "canbus": null
  },
  "inverted": {
    "drive": ,
    "angle": 
  },
  "absoluteEncoderOffset": -18.281,
  "location": {
    "front": ,
    "left": 
  }
}

Possible Motor Controller Types

Device
type

sparkmax (same as neo);neo ; neo550

sparkflex (same as vortex); vortex; sparkflex_neo; sparkflex_vortex

talonfx(same as krakenx60);falcon500;falcon500foc;krakenx60; krakenx60foc

TalonSRX

talonsrx

SparkMAX Brushed

sparkmax_brushed

At this time I do not provide documentation on brushed motor utilization, like sparkmax_brushed and talonsrx.

Venom
SwerveMotor
SwerveMotor
SwerveModule
SwerveModuleConfiguration
angleMotor
driveMotor
SwerveModule
SwerveDrive.getModules()
SparkMAX
SparkFlex
TalonFX