001/*
002 * Copyright (C) Cross The Road Electronics.  All rights reserved.
003 * License information can be found in CTRE_LICENSE.txt
004 * For support and suggestions contact support@ctr-electronics.com or file
005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
006 */
007package com.ctre.phoenix6.swerve;
008
009import static edu.wpi.first.units.Units.*;
010
011import java.util.Optional;
012import java.util.concurrent.locks.Lock;
013import java.util.concurrent.locks.ReentrantLock;
014import java.util.function.Consumer;
015import java.util.function.IntSupplier;
016
017import com.ctre.phoenix6.StatusCode;
018import com.ctre.phoenix6.Utils;
019import com.ctre.phoenix6.hardware.Pigeon2;
020import com.ctre.phoenix6.signals.NeutralModeValue;
021import com.ctre.phoenix6.swerve.SwerveRequest.NativeSwerveRequest;
022import com.ctre.phoenix6.swerve.jni.SwerveJNI;
023
024import edu.wpi.first.math.Matrix;
025import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
026import edu.wpi.first.math.geometry.Pose2d;
027import edu.wpi.first.math.geometry.Rotation2d;
028import edu.wpi.first.math.geometry.Rotation3d;
029import edu.wpi.first.math.geometry.Translation2d;
030import edu.wpi.first.math.kinematics.ChassisSpeeds;
031import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
032import edu.wpi.first.math.kinematics.SwerveModulePosition;
033import edu.wpi.first.math.kinematics.SwerveModuleState;
034import edu.wpi.first.math.numbers.N1;
035import edu.wpi.first.math.numbers.N3;
036import edu.wpi.first.units.measure.*;
037
038/**
039 * Swerve Drive class utilizing CTR Electronics' Phoenix 6 API.
040 * <p>
041 * This class handles the kinematics, configuration, and odometry of a
042 * swerve drive utilizing CTR Electronics devices. We recommend using
043 * the Swerve Project Generator in Tuner X to create a template project
044 * that demonstrates how to use this class.
045 * <p>
046 * This class will construct the hardware devices internally, so the user
047 * only specifies the constants (IDs, PID gains, gear ratios, etc).
048 * Getters for these hardware devices are available.
049 * <p>
050 * This class performs pose estimation internally using a separate odometry
051 * thread. Vision measurements can be added using {@link #addVisionMeasurement}.
052 * Other odometry APIs such as {@link #resetPose} are also available. The
053 * resulting pose estimate can be retrieved along with module states and
054 * other information using {@link #getState}. Additionally, the odometry
055 * thread synchronously provides all new state updates to a telemetry function
056 * registered with {@link #registerTelemetry}.
057 * <p>
058 * If using the generator, the order in which modules are constructed is
059 * Front Left, Front Right, Back Left, Back Right. This means if you need
060 * the Back Left module, call {@code getModule(2);} to get the third
061 * (0-indexed) module.
062 */
063public class SwerveDrivetrain implements AutoCloseable {
064    /**
065     * Plain-Old-Data class holding the state of the swerve drivetrain.
066     * This encapsulates most data that is relevant for telemetry or
067     * decision-making from the Swerve Drive.
068     */
069    public static class SwerveDriveState implements Cloneable {
070        /** The current pose of the robot */
071        public Pose2d Pose = new Pose2d();
072        /** The current velocity of the robot */
073        public ChassisSpeeds Speeds = new ChassisSpeeds();
074        /** The current module states */
075        public SwerveModuleState[] ModuleStates;
076        /** The target module states */
077        public SwerveModuleState[] ModuleTargets;
078        /** The current module positions */
079        public SwerveModulePosition[] ModulePositions;
080        /** The raw heading of the robot, unaffected by vision updates and odometry resets */
081        public Rotation2d RawHeading = new Rotation2d();
082        /** The timestamp of the state capture, in the timebase of {@link Utils#getCurrentTimeSeconds()} */
083        public double Timestamp;
084        /** The measured odometry update period, in seconds */
085        public double OdometryPeriod;
086        /** Number of successful data acquisitions */
087        public int SuccessfulDaqs;
088        /** Number of failed data acquisitions */
089        public int FailedDaqs;
090
091        /**
092         * Creates a deep copy of this state object.
093         * This API is not thread-safe.
094         */
095        @Override
096        public SwerveDriveState clone() {
097            final var toReturn = new SwerveDriveState();
098            toReturn.Pose = Pose;
099            toReturn.Speeds = Speeds;
100            toReturn.ModuleStates = ModuleStates.clone();
101            toReturn.ModuleTargets = ModuleTargets.clone();
102            toReturn.ModulePositions = ModulePositions.clone();
103            toReturn.RawHeading = RawHeading;
104            toReturn.Timestamp = Timestamp;
105            toReturn.OdometryPeriod = OdometryPeriod;
106            toReturn.SuccessfulDaqs = SuccessfulDaqs;
107            toReturn.FailedDaqs = FailedDaqs;
108            return toReturn;
109        }
110
111        protected void updateFromJni(SwerveJNI.DriveState driveState) {
112            if (Pose.getX() != driveState.PoseX ||
113                Pose.getY() != driveState.PoseY ||
114                Pose.getRotation().getRadians() != driveState.PoseTheta)
115            {
116                Pose = new Pose2d(driveState.PoseX, driveState.PoseY, Rotation2d.fromRadians(driveState.PoseTheta));
117            }
118
119            if (Speeds.vxMetersPerSecond != driveState.SpeedsVx ||
120                Speeds.vyMetersPerSecond != driveState.SpeedsVy ||
121                Speeds.omegaRadiansPerSecond != driveState.SpeedsOmega)
122            {
123                Speeds = new ChassisSpeeds(driveState.SpeedsVx, driveState.SpeedsVy, driveState.SpeedsOmega);
124            }
125
126            for (int i = 0; i < ModuleStates.length; ++i) {
127                if (ModuleStates[i].speedMetersPerSecond != driveState.ModuleStates[i].speed ||
128                    ModuleStates[i].angle.getRadians() != driveState.ModuleStates[i].angle)
129                {
130                    ModuleStates[i] = new SwerveModuleState(driveState.ModuleStates[i].speed, Rotation2d.fromRadians(driveState.ModuleStates[i].angle));
131                }
132            }
133            for (int i = 0; i < ModuleTargets.length; ++i) {
134                if (ModuleTargets[i].speedMetersPerSecond != driveState.ModuleTargets[i].speed ||
135                    ModuleTargets[i].angle.getRadians() != driveState.ModuleTargets[i].angle)
136                {
137                    ModuleTargets[i] = new SwerveModuleState(driveState.ModuleTargets[i].speed, Rotation2d.fromRadians(driveState.ModuleTargets[i].angle));
138                }
139            }
140            for (int i = 0; i < ModulePositions.length; ++i) {
141                if (ModulePositions[i].distanceMeters != driveState.ModulePositions[i].distance ||
142                    ModulePositions[i].angle.getRadians() != driveState.ModulePositions[i].angle)
143                {
144                    ModulePositions[i] = new SwerveModulePosition(driveState.ModulePositions[i].distance, Rotation2d.fromRadians(driveState.ModulePositions[i].angle));
145                }
146            }
147
148            if (RawHeading.getRadians() != driveState.RawHeading) {
149                RawHeading = Rotation2d.fromRadians(driveState.RawHeading);
150            }
151
152            Timestamp = driveState.Timestamp;
153            OdometryPeriod = driveState.OdometryPeriod;
154            SuccessfulDaqs = driveState.SuccessfulDaqs;
155            FailedDaqs = driveState.FailedDaqs;
156        }
157    }
158
159    /**
160     * Contains everything the control requests need to calculate the module state.
161     */
162    public static class SwerveControlParameters {
163        /** ID of the native drivetrain instance, used for JNI calls */
164        public int drivetrainId;
165
166        /** The kinematics object used for control */
167        public SwerveDriveKinematics kinematics;
168        /** The locations of the swerve modules */
169        public Translation2d[] moduleLocations;
170        /** The max speed of the robot at 12 V output, in m/s */
171        public double kMaxSpeedMps;
172
173        /** The forward direction from the operator perspective */
174        public Rotation2d operatorForwardDirection = new Rotation2d();
175        /** The current chassis speeds of the robot */
176        public ChassisSpeeds currentChassisSpeed = new ChassisSpeeds();
177        /** The current pose of the robot */
178        public Pose2d currentPose = new Pose2d();
179        /** The timestamp of the current control apply, in the timebase of {@link Utils#getCurrentTimeSeconds()} */
180        public double timestamp;
181        /** The update period of control apply */
182        public double updatePeriod;
183
184        protected void updateFromJni(SwerveJNI.ControlParams controlParams) {
185            kMaxSpeedMps = controlParams.kMaxSpeedMps;
186            if (operatorForwardDirection.getRadians() != controlParams.operatorForwardDirection) {
187                operatorForwardDirection = Rotation2d.fromRadians(controlParams.operatorForwardDirection);
188            }
189            currentChassisSpeed.vxMetersPerSecond = controlParams.currentChassisSpeedVx;
190            currentChassisSpeed.vyMetersPerSecond = controlParams.currentChassisSpeedVy;
191            currentChassisSpeed.omegaRadiansPerSecond = controlParams.currentChassisSpeedOmega;
192            if (currentPose.getX() != controlParams.currentPoseX ||
193                currentPose.getY() != controlParams.currentPoseY ||
194                currentPose.getRotation().getRadians() != controlParams.currentPoseTheta)
195            {
196                currentPose = new Pose2d(
197                    controlParams.currentPoseX,
198                    controlParams.currentPoseY,
199                    Rotation2d.fromRadians(controlParams.currentPoseTheta)
200                );
201            }
202            timestamp = controlParams.timestamp;
203            updatePeriod = controlParams.updatePeriod;
204        }
205    }
206
207    /** Number of times to attempt config applies. */
208    protected static final int kNumConfigAttempts = 2;
209
210    /** ID of the native drivetrain instance, used for JNI calls. */
211    protected final int m_drivetrainId;
212    /** JNI instance to use for non-static JNI calls. This object is not thread-safe. */
213    protected final SwerveJNI m_jni = new SwerveJNI();
214
215    private final SwerveModule[] m_modules;
216    private final Translation2d[] m_moduleLocations;
217
218    private final SwerveDriveKinematics m_kinematics;
219
220    private final Pigeon2 m_pigeon2;
221    private final SimSwerveDrivetrain m_simDrive;
222
223    /** The control parameters supplied to a non-native SwerveRequest. */
224    private final SwerveControlParameters m_controlParams = new SwerveControlParameters();
225    /** The swerve request currently applied. */
226    private SwerveRequest m_swerveRequest = new SwerveRequest.Idle();
227    /** Handle to the native object used to apply a non-native SwerveRequest. */
228    private long m_controlHandle = 0;
229
230    /** JNI instance to use for telemetry JNI calls. This object is not thread-safe. */
231    protected final SwerveJNI m_telemetryJNI;
232    /** The telemetry function currently applied. */
233    private Consumer<SwerveDriveState> m_telemetryFunction = null;
234    /** Handle to the native object used to call the telemetry function. */
235    private long m_telemetryHandle = 0;
236
237    /** Lock protecting the swerve drive state. */
238    private final Lock m_stateLock = new ReentrantLock();
239    /** The last received swerve drive state. */
240    private final SwerveDriveState m_cachedState = new SwerveDriveState();
241    /** The current operator forward direction. */
242    private Rotation2d m_operatorForwardDirection = new Rotation2d();
243
244    /** Performs swerve module updates in a separate thread to minimize latency. */
245    public class OdometryThread {
246        /**
247         * Starts the odometry thread.
248         */
249        public final void start() {
250            SwerveJNI.JNI_Odom_Start(m_drivetrainId);
251        }
252
253        /**
254         * Stops the odometry thread.
255         */
256        public final void stop() {
257            SwerveJNI.JNI_Odom_Stop(m_drivetrainId);
258        }
259
260        /**
261         * Check if the odometry is currently valid.
262         *
263         * @return True if odometry is valid
264         */
265        public boolean isOdometryValid() {
266            return SwerveJNI.JNI_IsOdometryValid(m_drivetrainId);
267        }
268
269        /**
270         * Sets the odometry thread priority to a real time priority under the specified priority level
271         *
272         * @param priority Priority level to set the odometry thread to.
273         *                 This is a value between 0 and 99, with 99 indicating higher priority and 0 indicating lower priority.
274         */
275        public final void setThreadPriority(int priority) {
276            SwerveJNI.JNI_Odom_SetThreadPriority(m_drivetrainId, priority);
277        }
278    }
279
280    private final OdometryThread m_odometryThread = new OdometryThread();
281
282    /** Thread responsible for disposing the native drivetrain on shutdown. */
283    private Thread m_shutdownHook;
284
285    /**
286     * Constructs a CTRE SwerveDrivetrain using the specified constants.
287     * <p>
288     * This constructs the underlying hardware devices, so users should not construct
289     * the devices themselves. If they need the devices, they can access them through
290     * getters in the classes.
291     *
292     * @param drivetrainConstants Drivetrain-wide constants for the swerve drive
293     * @param modules             Constants for each specific module
294     */
295    public SwerveDrivetrain(SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) {
296        this(() -> {
297                long nativeDriveConstants = drivetrainConstants.createNativeInstance();
298                long nativeModuleConstants = SwerveModuleConstants.createNativeInstance(modules);
299
300                var drivetrain = SwerveJNI.JNI_CreateDrivetrain(nativeDriveConstants, nativeModuleConstants, modules.length);
301
302                SwerveJNI.JNI_DestroyConstants(nativeDriveConstants);
303                SwerveJNI.JNI_DestroyConstants(nativeModuleConstants);
304                return drivetrain;
305            }, drivetrainConstants, modules
306        );
307    }
308
309    /**
310     * Constructs a CTRE SwerveDrivetrain using the specified constants.
311     * <p>
312     * This constructs the underlying hardware devices, so users should not construct
313     * the devices themselves. If they need the devices, they can access them through
314     * getters in the classes.
315     *
316     * @param drivetrainConstants        Drivetrain-wide constants for the swerve drive
317     * @param odometryUpdateFrequency    The frequency to run the odometry loop. If
318     *                                   unspecified or set to 0 Hz, this is 250 Hz on
319     *                                   CAN FD, and 100 Hz on CAN 2.0.
320     * @param modules                    Constants for each specific module
321     */
322    public SwerveDrivetrain(
323            SwerveDrivetrainConstants drivetrainConstants, double odometryUpdateFrequency,
324            SwerveModuleConstants... modules) {
325        this(() -> {
326                long nativeDriveConstants = drivetrainConstants.createNativeInstance();
327                long nativeModuleConstants = SwerveModuleConstants.createNativeInstance(modules);
328
329                var drivetrain = SwerveJNI.JNI_CreateDrivetrainWithFreq(nativeDriveConstants, odometryUpdateFrequency,
330                        nativeModuleConstants, modules.length);
331
332                SwerveJNI.JNI_DestroyConstants(nativeDriveConstants);
333                SwerveJNI.JNI_DestroyConstants(nativeModuleConstants);
334                return drivetrain;
335            }, drivetrainConstants, modules
336        );
337    }
338
339    /**
340     * Constructs a CTRE SwerveDrivetrain using the specified constants.
341     * <p>
342     * This constructs the underlying hardware devices, so users should not construct
343     * the devices themselves. If they need the devices, they can access them through
344     * getters in the classes.
345     *
346     * @param drivetrainConstants        Drivetrain-wide constants for the swerve drive
347     * @param odometryUpdateFrequency    The frequency to run the odometry loop. If
348     *                                   unspecified or set to 0 Hz, this is 250 Hz on
349     *                                   CAN FD, and 100 Hz on CAN 2.0.
350     * @param odometryStandardDeviation  The standard deviation for odometry calculation
351     *                                   in the form [x, y, theta]ᵀ, with units in meters
352     *                                   and radians
353     * @param visionStandardDeviation    The standard deviation for vision calculation
354     *                                   in the form [x, y, theta]ᵀ, with units in meters
355     *                                   and radians
356     * @param modules                    Constants for each specific module
357     */
358    public SwerveDrivetrain(
359            SwerveDrivetrainConstants drivetrainConstants, double odometryUpdateFrequency,
360            Matrix<N3, N1> odometryStandardDeviation, Matrix<N3, N1> visionStandardDeviation,
361            SwerveModuleConstants... modules) {
362        this(() -> {
363                long nativeDriveConstants = drivetrainConstants.createNativeInstance();
364                long nativeModuleConstants = SwerveModuleConstants.createNativeInstance(modules);
365
366                var drivetrain = SwerveJNI.JNI_CreateDrivetrainWithStddev(nativeDriveConstants, odometryUpdateFrequency,
367                        odometryStandardDeviation.getData(), visionStandardDeviation.getData(),
368                        nativeModuleConstants, modules.length);
369
370                SwerveJNI.JNI_DestroyConstants(nativeDriveConstants);
371                SwerveJNI.JNI_DestroyConstants(nativeModuleConstants);
372                return drivetrain;
373            }, drivetrainConstants, modules
374        );
375    }
376
377    private SwerveDrivetrain(IntSupplier createNativeInst, SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) {
378        m_drivetrainId = createNativeInst.getAsInt();
379
380        m_cachedState.ModuleStates = new SwerveModuleState[modules.length];
381        m_cachedState.ModuleTargets = new SwerveModuleState[modules.length];
382        m_cachedState.ModulePositions = new SwerveModulePosition[modules.length];
383        m_jni.driveState.ModuleStates = new SwerveJNI.ModuleState[modules.length];
384        m_jni.driveState.ModuleTargets = new SwerveJNI.ModuleState[modules.length];
385        m_jni.driveState.ModulePositions = new SwerveJNI.ModulePosition[modules.length];
386        for (int i = 0; i < modules.length; ++i) {
387            m_cachedState.ModuleStates[i] = new SwerveModuleState();
388            m_cachedState.ModuleTargets[i] = new SwerveModuleState();
389            m_cachedState.ModulePositions[i] = new SwerveModulePosition();
390            m_jni.driveState.ModuleStates[i] = new SwerveJNI.ModuleState();
391            m_jni.driveState.ModuleTargets[i] = new SwerveJNI.ModuleState();
392            m_jni.driveState.ModulePositions[i] = new SwerveJNI.ModulePosition();
393        }
394
395        m_telemetryJNI = m_jni.clone();
396
397        m_modules = new SwerveModule[modules.length];
398        m_moduleLocations = new Translation2d[modules.length];
399        for (int i = 0; i < modules.length; ++i) {
400            m_modules[i] = new SwerveModule(modules[i], drivetrainConstants.CANBusName, m_drivetrainId, i);
401            m_moduleLocations[i] = new Translation2d(modules[i].LocationX, modules[i].LocationY);
402        }
403
404        m_kinematics = new SwerveDriveKinematics(m_moduleLocations);
405
406        m_controlParams.drivetrainId = m_drivetrainId;
407        m_controlParams.kinematics = m_kinematics;
408        m_controlParams.moduleLocations = m_moduleLocations;
409
410        m_pigeon2 = new Pigeon2(drivetrainConstants.Pigeon2Id, drivetrainConstants.CANBusName);
411        m_simDrive = new SimSwerveDrivetrain(m_moduleLocations, m_pigeon2.getSimState(), modules);
412
413        if (drivetrainConstants.Pigeon2Configs != null) {
414            StatusCode retval = StatusCode.OK;
415            for (int i = 0; i < kNumConfigAttempts; ++i) {
416                retval = getPigeon2().getConfigurator().apply(drivetrainConstants.Pigeon2Configs);
417                if (retval.isOK()) break;
418            }
419            if (!retval.isOK()) {
420                System.out.println("Pigeon2 ID " + getPigeon2().getDeviceID() + " failed config with error: " + retval);
421            }
422        }
423        /* do not start thread until after applying Pigeon 2 configs */
424        m_odometryThread.start();
425
426        m_shutdownHook = new Thread(() -> {
427            m_shutdownHook = null;
428            close();
429        });
430        Runtime.getRuntime().addShutdownHook(m_shutdownHook);
431    }
432
433    @Override
434    public void close() {
435        SwerveJNI.JNI_DestroyDrivetrain(m_drivetrainId);
436        if (m_controlHandle != 0) {
437            SwerveJNI.JNI_DestroyControl(m_controlHandle);
438            m_controlHandle = 0;
439        }
440        if (m_telemetryHandle != 0) {
441            SwerveJNI.JNI_DestroyTelemetry(m_telemetryHandle);
442            m_telemetryHandle = 0;
443        }
444
445        if (m_shutdownHook != null) {
446            Runtime.getRuntime().removeShutdownHook(m_shutdownHook);
447            m_shutdownHook = null;
448        }
449    }
450
451    /**
452     * Updates all the simulation state variables for this
453     * drivetrain class. User provides the update variables for the simulation.
454     *
455     * @param dtSeconds time since last update call
456     * @param supplyVoltage voltage as seen at the motor controllers
457     */
458    public void updateSimState(double dtSeconds, double supplyVoltage) {
459        m_simDrive.update(dtSeconds, supplyVoltage, m_modules);
460    }
461
462    /**
463     * Gets whether the drivetrain is on a CAN FD bus.
464     * 
465     * @return true if on CAN FD
466     */
467    public final boolean isOnCANFD() {
468        return SwerveJNI.JNI_IsOnCANFD(m_drivetrainId);
469    }
470
471    /**
472     * Gets the target odometry update frequency in Hz.
473     * 
474     * @return Target odometry update frequency
475     */
476    public final double getOdometryFrequency() {
477        return SwerveJNI.JNI_GetOdometryFrequency(m_drivetrainId);
478    }
479
480    /**
481     * Gets the target odometry update frequency.
482     * 
483     * @return Target odometry update frequency
484     */
485    public final Frequency getOdometryFrequencyMeasure() {
486        return Hertz.of(getOdometryFrequency());
487    }
488
489    /**
490     * Gets a reference to the odometry thread.
491     *
492     * @return Odometry thread
493     */
494    public final OdometryThread getOdometryThread() {
495        return m_odometryThread;
496    }
497
498    /**
499     * Check if the odometry is currently valid.
500     *
501     * @return True if odometry is valid
502     */
503    public boolean isOdometryValid() {
504        return SwerveJNI.JNI_IsOdometryValid(m_drivetrainId);
505    }
506
507    /**
508     * Gets a reference to the kinematics used for the drivetrain.
509     * 
510     * @return Swerve kinematics
511     */
512    public final SwerveDriveKinematics getKinematics() {
513        return m_kinematics;
514    }
515
516    /**
517     * Applies the specified control request to this swerve drivetrain.
518     *
519     * @param request Request to apply
520     */
521    public void setControl(SwerveRequest request) {
522        if (m_swerveRequest != request) {
523            m_swerveRequest = request;
524
525            var prevControlHandle = m_controlHandle;
526
527            if (request == null) {
528                m_controlHandle = m_jni.JNI_SetControl(m_drivetrainId, null);
529            } else if (request instanceof NativeSwerveRequest req) {
530                req.applyNative(m_drivetrainId);
531                m_controlHandle = 0;
532            } else {
533                m_controlHandle = m_jni.JNI_SetControl(m_drivetrainId, () -> {
534                    m_controlParams.updateFromJni(m_jni.controlParams);
535                    return request.apply(m_controlParams, m_modules).value;
536                });
537            }
538
539            if (prevControlHandle != 0) {
540                SwerveJNI.JNI_DestroyControl(prevControlHandle);
541            }
542        } else if (request instanceof NativeSwerveRequest req) {
543            /* update the native object */
544            req.applyNative(m_drivetrainId);
545        }
546    }
547
548    /**
549     * Gets the current state of the swerve drivetrain.
550     * This includes information such as the pose estimate,
551     * module states, and chassis speeds.
552     *
553     * @return Current state of the drivetrain
554     */
555    public final SwerveDriveState getState() {
556        m_jni.JNI_GetState(m_drivetrainId);
557        try {
558            m_stateLock.lock();
559            m_cachedState.updateFromJni(m_jni.driveState);
560            return m_cachedState;
561        } finally {
562            m_stateLock.unlock();
563        }
564    }
565
566    /**
567     * Gets a copy of the current state of the swerve drivetrain.
568     * This includes information such as the pose estimate,
569     * module states, and chassis speeds.
570     * <p>
571     * This can be used to get a thread-safe copy of the state object.
572     *
573     * @return Copy of the current state of the drivetrain
574     */
575    public final SwerveDriveState getStateCopy() {
576        m_jni.JNI_GetState(m_drivetrainId);
577        try {
578            m_stateLock.lock();
579            m_cachedState.updateFromJni(m_jni.driveState);
580            return m_cachedState.clone();
581        } finally {
582            m_stateLock.unlock();
583        }
584    }
585
586    /**
587     * Register the specified lambda to be executed whenever our SwerveDriveState function
588     * is updated in our odometry thread.
589     * <p>
590     * It is imperative that this function is cheap, as it will be executed along with
591     * the odometry call, and if this takes a long time, it may negatively impact the
592     * odometry of this stack.
593     * <p>
594     * This can also be used for logging data if the function performs logging instead of telemetry.
595     * Additionally, the SwerveDriveState object can be cloned and stored for later processing.
596     *
597     * @param telemetryFunction Function to call for telemetry or logging
598     */
599    public void registerTelemetry(Consumer<SwerveDriveState> telemetryFunction) {
600        if (m_telemetryFunction != telemetryFunction) {
601            m_telemetryFunction = telemetryFunction;
602
603            var prevTelemetryHandle = m_telemetryHandle;
604
605            if (telemetryFunction == null) {
606                m_telemetryHandle = m_telemetryJNI.JNI_RegisterTelemetry(m_drivetrainId, null);
607            } else {
608                m_telemetryHandle = m_telemetryJNI.JNI_RegisterTelemetry(m_drivetrainId, () -> {
609                    try {
610                        m_stateLock.lock();
611                        m_cachedState.updateFromJni(m_telemetryJNI.driveState);
612                        telemetryFunction.accept(m_cachedState);
613                    } finally {
614                        m_stateLock.unlock();
615                    }
616                });
617            }
618
619            if (prevTelemetryHandle != 0) {
620                SwerveJNI.JNI_DestroyTelemetry(prevTelemetryHandle);
621            }
622        }
623    }
624
625    /**
626     * Configures the neutral mode to use for all modules' drive motors.
627     *
628     * @param neutralMode The drive motor neutral mode
629     * @return Status code of the first failed config call, or OK if all succeeded
630     */
631    public StatusCode configNeutralMode(NeutralModeValue neutralMode) {
632        return StatusCode.valueOf(SwerveJNI.JNI_ConfigNeutralMode(m_drivetrainId, neutralMode.value));
633    }
634
635    /**
636     * Zero's this swerve drive's odometry entirely.
637     * <p>
638     * This will zero the entire odometry, and place the robot at 0,0
639     */
640    public void tareEverything() {
641        SwerveJNI.JNI_TareEverything(m_drivetrainId);
642    }
643
644    /**
645     * Resets the rotation of the robot pose to 0 from the
646     * {@link SwerveRequest.ForwardPerspectiveValue#OperatorPerspective}
647     * perspective. This makes the current orientation of the robot X
648     * forward for field-centric maneuvers.
649     * <p>
650     * This is equivalent to calling {@link #resetRotation} with the operator
651     * perspective rotation.
652     */
653    public void seedFieldCentric() {
654        SwerveJNI.JNI_SeedFieldCentric(m_drivetrainId);
655    }
656
657    /**
658     * Resets the pose of the robot. The pose should be from the
659     * {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perspective.
660     *
661     * @param pose Pose to make the current pose
662     */
663    public void resetPose(Pose2d pose) {
664        SwerveJNI.JNI_ResetPose(m_drivetrainId, pose.getX(), pose.getY(), pose.getRotation().getRadians());
665    }
666
667    /**
668     * Resets the translation of the robot pose without affecting rotation.
669     * The translation should be from the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance}
670     * perspective.
671     *
672     * @param translation Translation to make the current translation
673     */
674    public void resetTranslation(Translation2d translation) {
675        SwerveJNI.JNI_ResetTranslation(m_drivetrainId, translation.getX(), translation.getY());
676    }
677
678    /**
679     * Resets the rotation of the robot pose without affecting translation.
680     * The rotation should be from the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance}
681     * perspective.
682     *
683     * @param rotation Rotation to make the current rotation
684     */
685    public void resetRotation(Rotation2d rotation) {
686        SwerveJNI.JNI_ResetRotation(m_drivetrainId, rotation.getRadians());
687    }
688
689    /**
690     * Takes the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perpective direction
691     * and treats it as the forward direction for
692     * {@link SwerveRequest.ForwardPerspectiveValue#OperatorPerspective}.
693     * <p>
694     * If the operator is in the Blue Alliance Station, this should be 0 degrees.
695     * If the operator is in the Red Alliance Station, this should be 180 degrees.
696     * <p>
697     * This does not change the robot pose, which is in the
698     * {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perspective.
699     * As a result, the robot pose may need to be reset using {@link #resetPose}.
700     *
701     * @param fieldDirection Heading indicating which direction is forward from
702     *                       the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perspective
703     */
704    public void setOperatorPerspectiveForward(Rotation2d fieldDirection) {
705        SwerveJNI.JNI_SetOperatorPerspectiveForward(m_drivetrainId, fieldDirection.getRadians());
706    }
707
708    /**
709     * Returns the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perpective
710     * direction that is treated as the forward direction for
711     * {@link SwerveRequest.ForwardPerspectiveValue#OperatorPerspective}.
712     * <p>
713     * If the operator is in the Blue Alliance Station, this should be 0 degrees.
714     * If the operator is in the Red Alliance Station, this should be 180 degrees.
715     *
716     * @return Heading indicating which direction is forward from
717     *         the {@link SwerveRequest.ForwardPerspectiveValue#BlueAlliance} perspective
718     */
719    public final Rotation2d getOperatorForwardDirection() {
720        double operatorForwardDirectionRad = SwerveJNI.JNI_GetOperatorForwardDirection(m_drivetrainId);
721        try {
722            m_stateLock.lock();
723            if (m_operatorForwardDirection.getRadians() != operatorForwardDirectionRad) {
724                m_operatorForwardDirection = Rotation2d.fromRadians(operatorForwardDirectionRad);
725            }
726            return m_operatorForwardDirection;
727        } finally {
728            m_stateLock.unlock();
729        }
730    }
731
732    /**
733     * Adds a vision measurement to the Kalman Filter. This will correct the
734     * odometry pose estimate while still accounting for measurement noise.
735     * <p>
736     * This method can be called as infrequently as you want, as long as you are
737     * calling {@link SwerveDrivePoseEstimator#update} every loop.
738     * <p>
739     * To promote stability of the pose estimate and make it robust to bad vision
740     * data, we recommend only adding vision measurements that are already within
741     * one meter or so of the current pose estimate.
742     *
743     * @param visionRobotPoseMeters The pose of the robot as measured by the vision
744     *                              camera.
745     * @param timestampSeconds      The timestamp of the vision measurement in
746     *                              seconds. Note that you must use a timestamp with an
747     *                              epoch since system startup (i.e., the epoch of this
748     *                              timestamp is the same epoch as
749     *                              {@link Utils#getCurrentTimeSeconds}).
750     *                              This means that you should use
751     *                              {@link Utils#getCurrentTimeSeconds}
752     *                              as your time source or sync the epochs.
753     *                              An FPGA timestamp can be converted to the correct
754     *                              timebase using {@link Utils#fpgaToCurrentTime}.
755     */
756    public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
757        SwerveJNI.JNI_AddVisionMeasurement(m_drivetrainId, visionRobotPoseMeters.getX(), visionRobotPoseMeters.getY(),
758            visionRobotPoseMeters.getRotation().getRadians(), timestampSeconds);
759    }
760
761    /**
762     * Adds a vision measurement to the Kalman Filter. This will correct the
763     * odometry pose estimate while still accounting for measurement noise.
764     * <p>
765     * This method can be called as infrequently as you want, as long as you are
766     * calling {@link SwerveDrivePoseEstimator#update} every loop.
767     * <p>
768     * To promote stability of the pose estimate and make it robust to bad vision
769     * data, we recommend only adding vision measurements that are already within
770     * one meter or so of the current pose estimate.
771     * <p>
772     * Note that the vision measurement standard deviations passed into this method
773     * will continue to apply to future measurements until a subsequent call to {@link
774     * SwerveDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method.
775     *
776     * @param visionRobotPoseMeters    The pose of the robot as measured by the
777     *                                 vision camera.
778     * @param timestampSeconds         The timestamp of the vision measurement in
779     *                                 seconds. Note that you must use a timestamp with an
780     *                                 epoch since system startup (i.e., the epoch of this
781     *                                 timestamp is the same epoch as
782     *                                 {@link Utils#getCurrentTimeSeconds}).
783     *                                 This means that you should use
784     *                                 {@link Utils#getCurrentTimeSeconds}
785     *                                 as your time source or sync the epochs.
786     *                                 An FPGA timestamp can be converted to the correct
787     *                                 timebase using {@link Utils#fpgaToCurrentTime}.
788     * @param visionMeasurementStdDevs Standard deviations of the vision pose
789     *                                 measurement (x position
790     *                                 in meters, y position in meters, and heading
791     *                                 in radians). Increase these numbers to trust
792     *                                 the vision pose measurement less.
793     */
794    public void addVisionMeasurement(
795            Pose2d visionRobotPoseMeters,
796            double timestampSeconds,
797            Matrix<N3, N1> visionMeasurementStdDevs)
798    {
799        SwerveJNI.JNI_AddVisionMeasurementWithStdDev(m_drivetrainId, visionRobotPoseMeters.getX(), visionRobotPoseMeters.getY(),
800            visionRobotPoseMeters.getRotation().getRadians(), timestampSeconds, visionMeasurementStdDevs.getData());
801    }
802
803    /**
804     * Sets the pose estimator's trust of global measurements. This might be used to
805     * change trust in vision measurements after the autonomous period, or to change
806     * trust as distance to a vision target increases.
807     *
808     * @param visionMeasurementStdDevs Standard deviations of the vision
809     *                                 measurements. Increase these numbers to
810     *                                 trust global measurements from vision less.
811     *                                 This matrix is in the form [x, y, theta]ᵀ,
812     *                                 with units in meters and radians.
813     */
814    public void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs) {
815        SwerveJNI.JNI_SetVisionMeasurementStdDevs(m_drivetrainId, visionMeasurementStdDevs.getData());
816    }
817
818    /**
819     * Return the pose at a given timestamp, if the buffer is not empty.
820     *
821     * @param timestampSeconds The pose's timestamp. Note that you must use a timestamp
822     *                         with an epoch since system startup (i.e., the epoch of
823     *                         this timestamp is the same epoch as
824     *                         {@link Utils#getCurrentTimeSeconds}).
825     *                         This means that you should use
826     *                         {@link Utils#getCurrentTimeSeconds}
827     *                         as your time source in this case.
828     *                         An FPGA timestamp can be converted to the correct
829     *                         timebase using {@link Utils#fpgaToCurrentTime}.
830     * @return The pose at the given timestamp (or Optional.empty() if the buffer is
831     *         empty).
832     */
833    public Optional<Pose2d> samplePoseAt(double timestampSeconds) {
834        double[] retval = SwerveJNI.JNI_SamplePoseAt(m_drivetrainId, timestampSeconds);
835        if (retval == null) {
836            return Optional.empty();
837        }
838        return Optional.of(new Pose2d(retval[0], retval[1], Rotation2d.fromRadians(retval[2])));
839    }
840
841    /**
842     * Get a reference to the module at the specified index.
843     * The index corresponds to the module described in the constructor.
844     *
845     * @param index Which module to get
846     * @return Reference to SwerveModule
847     */
848    public final SwerveModule getModule(int index) {
849        if (index >= m_modules.length) {
850            return null;
851        }
852        return m_modules[index];
853    }
854
855    /**
856     * Get a reference to the full array of modules.
857     * The indexes correspond to the module described in the constructor.
858     *
859     * @return Reference to the SwerveModule array
860     */
861    public final SwerveModule[] getModules() {
862        return m_modules;
863    }
864
865    /**
866     * Gets the locations of the swerve modules.
867     * 
868     * @return Reference to the array of swerve module locations
869     */
870    public final Translation2d[] getModuleLocations() {
871        return m_moduleLocations;
872    }
873
874    /**
875     * Gets the current orientation of the robot as a {@link Rotation3d} from
876     * the Pigeon 2 quaternion values.
877     *
878     * @return The robot orientation as a {@link Rotation3d}
879     */
880    public final Rotation3d getRotation3d() {
881        return m_pigeon2.getRotation3d();
882    }
883
884    /**
885     * Gets this drivetrain's Pigeon 2 reference.
886     * <p>
887     * This should be used only to access signals and change configurations that the
888     * swerve drivetrain does not configure itself.
889     *
890     * @return This drivetrain's Pigeon 2 reference
891     */
892    public final Pigeon2 getPigeon2() {
893        return m_pigeon2;
894    }
895}