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
  • Swerve Motors
  • Spin your module counterclockwise
  • If the swerve/modules/.../Raw Angle Encoder is decreasing...
  • If the swerve/modules/.../Raw Absolute Encoder is decreasing...
  • Spin your wheel counterclockwise
  • If the swerve/modules/.../Raw Drive Encoder is decreasing...
  • Rotate your robot counterclockwise

Was this helpful?

Edit on GitHub
  1. Configuring YAGSL

When to invert?

PreviousHow to tune PIDFNextFlowcharts

Last updated 3 months ago

Was this helpful?

Swerve Modules and Swerve Drives require some inversions to get working properly. The goal is to get everything to increase counter clockwise positive!

When your gears are grinding on the ground but not while on blocks and your wheels are facing and spinning in the right directions you may need to tune PID instead of inverting!

IF you are inverted incorrectly your modules or robot may spin "out-of-control"

Swerve Motors

When you spin your motor counterclockwise the value in NetworkTables swerve/modules/.../Raw Absolute Encoder and swerve/modules/.../Raw Angle Encoder should both increase.

  • Take note of the swerve/modules/.../Raw Absolute Encoder value's and use them for absoluteEncoderOffset in the module JSONs.

Spin your module counterclockwise

Spin your modules COUNTERclockwise from the top down view.

The swerve drive should be on it's side or otherwise lifted. Your swerve module bevels must be facing the left like shown. To rotate the swerve modules they must be rotated counterclockwise like shown.

If the swerve/modules/.../Raw Angle Encoder is decreasing...

Invert your angle motor for every module that is decreasing!

{
  "drive": {
    "type": "sparkmax",
    "id": 2,
    "canbus": null
  },
  "angle": {
    "type": "sparkmax",
    "id": 1,
    "canbus": null
  },
  "encoder": {
    "type": "cancoder",
    "id": 10,
    "canbus": null
  },
  "inverted": {
    "drive": false,
    "angle": true
  },
  "absoluteEncoderInverted": false,
  "absoluteEncoderOffset": -50.977,
  "location": {
    "front": 12,
    "left": -12
  }
}

If the swerve/modules/.../Raw Absolute Encoder is decreasing...

Invert the absolute encoder in the module JSON with absoluteEncoderInverted as shown here.

{
  "drive": {
    "type": "sparkmax",
    "id": 2,
    "canbus": null
  },
  "angle": {
    "type": "sparkmax",
    "id": 1,
    "canbus": null
  },
  "encoder": {
    "type": "cancoder",
    "id": 10,
    "canbus": null
  },
  "inverted": {
    "drive": false,
    "angle": false
  },
  "absoluteEncoderInverted": true,
  "absoluteEncoderOffset": -50.977,
  "location": {
    "front": 12,
    "left": -12
  }
}

Spin your wheel counterclockwise

Sometimes you may need to invert these if when you rotate the robot changes it's front/back while driving in field-oriented mode.

Odometry mismatch

Whenever your robot is driving backwards in odometry and forwards in real life while maintaining that a spin-in-place generates Counter-Clockwise-Positive movement you may need to apply this patch.

You must add 180 to every absoluteEncoderOffset in every module file to correct this behavior.

If the swerve/modules/.../Raw Drive Encoder is decreasing...

Invert your drive motor for every module that is decreasing!

{
  "drive": {
    "type": "sparkmax",
    "id": 2,
    "canbus": null
  },
  "angle": {
    "type": "sparkmax",
    "id": 1,
    "canbus": null
  },
  "encoder": {
    "type": "cancoder",
    "id": 10,
    "canbus": null
  },
  "inverted": {
    "drive": true,
    "angle": false
  },
  "absoluteEncoderInverted": false,
  "absoluteEncoderOffset": -50.977,
  "location": {
    "front": 12,
    "left": -12
  }
}

Rotate your robot counterclockwise

Keep in mind that your robot spinning counter clockwise should look like this when the wheels are powered! You WILL need to change your IDs for each module file if they don't.

You should notice the Raw IMU Yaw field in your driver dashboard increase. If it doesn't you need to invert your IMU like this.

{
  "imu": {
    ,
    "id": 13,
    "canbus": "canivore"
  },
  "invertedIMU": true,
  "modules": [
    "frontleft.json",
    "frontright.json",
    "backleft.json",
    "backright.json"
  ]
}
Purple shows the way your bevels should be facing (photo by Team 2876)
ID's relocated in swerve module files