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
  • How it works?
  • How do I enable it?
  • What does it do?
  • Swerve Module
  • Swerve Drive
  • Recommended Shuffleboard Layout
  • Alternative Dashboard Support

Was this helpful?

Edit on GitHub
  1. Overview
  2. Our Features

Telemetry

PreviousOur FeaturesNextSimulation

Last updated 4 months ago

Was this helpful?

How it works?

YAGSL uses telemetry in SwerveDrive and SwerveModule for consolidation. There are a few remainders of telemetry which is pushed from . All Telemtry is bound by a verbosity level in as a static variable. The following are the options which you can utilize.

/**
 * Verbosity of telemetry data sent back.
 */
 public enum TelemetryVerbosity
{
  /**
   * No telemetry data is sent back.
   */
  NONE,
  /**
   * Low telemetry data, only post the robot position on the field.
   */
  LOW,
  /**
   * Medium telemetry data, swerve directory
   */
  INFO,
  /**
   * Info level + field info
   */
  POSE,
  /**
   * Full swerve drive data is sent back in both human and machine readable forms.
   */
  HIGH,
  /**
   * Only send the machine readable data related to swerve drive.
   */
  MACHINE
}

How do I enable it?

Higher telemetry could induce some lag on the robot and slow down the cycle times. So be cautious on what you chose!

  /**
   * Initialize {@link SwerveDrive} with the directory provided.
   *
   * @param directory Directory of swerve drive config files.
   */
  public SwerveSubsystem(File directory)
  {
    // Configure the Telemetry before creating the SwerveDrive to avoid unnecessary objects being created.
    SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
    swerveDrive = new SwerveParser(directory).createSwerveDrive(Constants.MAX_SPEED);
  }

What does it do?

Telemetry outputs relevant Swerve Drive data to NetworkTables on the roboRIO. You can view these using any dashboard you like!

Some dashboard support swerve drive widgets based off of the SmartDashboard/swerve NetworkTable entry.

All Swerve Module data is stored under the relevant modules in SmartDashboard/swerve/modules/ which is invaluable during setup.

Swerve Module

Swerve Drive

Recommended Shuffleboard Layout

I use this layout during setup to ensure all modules are reading CCW+. This is the most common overlooked part while configuring swerve drives.

If the Raw Angle Encoder is CCW- (decreasing while rotated counter clockwise) then the angle motor needs to be inverted in the configuration file for that module.

If the Raw Absolute Encoder is CCW- (decreasing while the wheel is rotated counter clockwise) then the absolute encoder might need to be inverted for that module.

Alternative Dashboard Support

There are a few dashboard which support YAGSL widgets too! These developers are amazing and you should definitely checkout their work!

To configure the telemetry please change to one of the that you desire.

SwerveDrive.updateOdometry()
SwerveDriveTelemtry.verbosity
SwerveDriveTelemetry.verbosity
enum values
Elastic Dashboard
FRC Web Components
Advantage Scope
Swerve Module Telemetry in Shuffleboard
Swerve Drive Telemetry in Shuffleboard with circled relevant keys
Raw Absolute Encoder group on left side, Raw Angle Encoder group on right side.
Shuffleboard Tree