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
  • Physically Label each component with their ID's
  • Motors should spin counter clockwise positive
  • Conversion Factors and your motors
  • The Absolute Encoder offset

Was this helpful?

Edit on GitHub
  1. Bringing up swerve

Check your motors

PreviousCheck your gyroscopeNextCreating your first configuration

Last updated 3 months ago

Was this helpful?

Make sure your CAN ID's are unique! There is a known issue where if the CAN ID of your REV Power Distribution Hub is the same as the CAN ID of the SparkMAX it will cause the SparkMAX to not move the motor!

Physically Label each component with their ID's

There is no easier way to screw up configuring a swerve drive (or any other kind of drive system) than putting the wrong channel number, CAN ID, or even CAN bus (if your device is on a CANivore) for a component whether it is the drive motor, angle motor, absolute encoder, or gyroscope. Some components don't have ID's like NavX's and instead have a few different type's which define the connection method (navx_spi, navx_usb, navx_i2c) these just have to be known beforehand.

I strongly suggest you find the information from the Getting to know your robotsheet before you start configuring your robot.

Motors should spin counter clockwise positive

When you spin your motor while the robot is disabled you will notice swerve/modules/.../Raw Angle Encoder (angle/steering/azimuth relative encoder) and swerve/modules/.../Raw Absolute Encoder (absolute encoder) . Both of these should increase while the motor is spun counter clockwise. For more information see here.

When to invert?

Conversion Factors and your motors

Conversion factors are applied to your motor convert from native units (usually rotations) to degrees for steering/azimuth/angle motors, and meters for drive motors. Conversion factors are only relevant to motor controllers, except if there is an absolute encoder attached to your motor controller.

The Absolute Encoder offset

All the examples here use Shuffleboard as the driver dashboard, but can be done using any other alternative such as Advantage Scope or Elastic

The absolute encoder offset is what allows your swerve module to maintain the wheel orientation between power offs. It is vital to a functioning swerve drive.

  1. Line up all wheels so that the bevels are facing to the left like this.

  1. Deploy your code.

  2. DO NOT ENABLE YOUR ROBOT!

  3. Open your driver dashboard.

<figure><img src="../.gitbook/assets/shuffleboard_open_tab.png" alt=""><figcaption></figcaption></figure>
<figure><img src="../.gitbook/assets/ShuffleboardAbsoluteEncoderHighlight.png" alt=""><figcaption><p>swerve/modules/... view in Shuffleboard</p></figcaption></figure>
  1. Take note of the swerve/modules/.../Raw Absolute Encoder value's and use them for absoluteEncoderOffset in the module JSONs.

Special note to MAXSwerve teams!

When you align using the MAXSwerveModules and find the absoluteEncoderOffset for each module you may need to +/-90 from the absoluteEncoderOffset to correct the module position. The absoluteEncoderInverted must also be true in every module configuration as well.

{
  "drive": {
    "type": "sparkmax",
    "id": 12,
    "canbus": null
  },
  "angle": {
    "type": "sparkmax",
    "id": 11,
    "canbus": null
  },
  "encoder": {
    "type": "attached",
    "id": 0,
    "canbus": null
  },
  "inverted": {
    "drive": false,
    "angle": false
  },
  "absoluteEncoderInverted": true,
  "absoluteEncoderOffset": -90,
  "location": {
    "front": 12,
    "left": -12
  }
}
The left and right are physical left and right.