001/**
002 * Copyright 2024 The Space Cookies : Girl Scout Troop #62868 and FRC Team #1868
003 * Open Source Software; you may modify and/or share it under the terms of
004 * the 3-Clause BSD License found in the root directory of this project.
005 */
006package tagalong.subsystems.micro;
007
008import com.ctre.phoenix6.configs.CANcoderConfiguration;
009import com.ctre.phoenix6.configs.FeedbackConfigs;
010import com.ctre.phoenix6.hardware.CANcoder;
011import com.ctre.phoenix6.hardware.TalonFX;
012import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
013import com.ctre.phoenix6.sim.CANcoderSimState;
014import edu.wpi.first.math.controller.ArmFeedforward;
015import edu.wpi.first.math.geometry.Rotation2d;
016import edu.wpi.first.math.trajectory.TrapezoidProfile;
017import edu.wpi.first.math.util.Units;
018import edu.wpi.first.wpilibj.IterativeRobotBase;
019import edu.wpi.first.wpilibj.RobotController;
020import edu.wpi.first.wpilibj.simulation.BatterySim;
021import edu.wpi.first.wpilibj.simulation.RoboRioSim;
022import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
023import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
024import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
025import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
026import edu.wpi.first.wpilibj.util.Color8Bit;
027import tagalong.TagalongConfiguration;
028import tagalong.math.AlgebraicUtils;
029import tagalong.measurements.Angle;
030import tagalong.subsystems.micro.confs.PivotConf;
031
032/**
033 * Pivot microsystem
034 */
035public class Pivot extends Microsystem {
036  /**
037   * Configuration for the pivot
038   */
039  public final PivotConf _pivotConf;
040
041  /* -------- Hardware: motors and sensors -------- */
042  /**
043   * CANcoder device
044   */
045  public CANcoder _pivotCancoder;
046  /**
047   * Configuration for the CANcoder
048   */
049  protected CANcoderConfiguration _pivotCancoderConfiguration;
050
051  /* -------- Control: states and constants -------- */
052  /**
053   * Gear ratio from the motor to encoder (conversion g.t. 1 represents a reduction)
054   */
055  protected double _motorToEncoderRatio;
056  /**
057   * Gear ratio from the encoder to pivot mechanism (conversion g.t. 1 represents a reduction)
058   */
059  protected double _encoderToPivotRatio;
060  /**
061   * Default lower tolerance of the pivot in rotations,
062   * Default upper tolerance of the pivot in rotations
063   */
064  public final double _defaultPivotLowerToleranceRot, _defaultPivotUpperToleranceRot;
065  /**
066   * Absolute range of pivot movement in rotations
067   */
068  public final double _absoluteRangeRot;
069  /**
070   * Minimum position of the pivot in rotations,
071   * Maximum position of the pivot in rotations
072   */
073  public final double _minPositionRot, _maxPositionRot;
074  /**
075   * Maximum velocity of the pivot in rotations per second,
076   * Maximum acceleration of the pivot in rotations per second squared
077   */
078  public final double _maxVelocityRPS, _maxAccelerationRPS2;
079  /**
080   * Offset value for the target position
081   */
082  public final double _profileTargetOffset;
083
084  /* -------- Control: controller and utilities -------- */
085  /**
086   * Feedforward model for the pivot
087   */
088  protected ArmFeedforward _pivotFF;
089  /**
090   * Offset value for the target position
091   */
092  public final double _ffCenterOfMassOffsetRad;
093  /**
094   * Positional values for safe clamp logic
095   */
096  private double[] _values;
097  /**
098   * IDs for safe clamp switch case
099   */
100  private int[] _ids;
101
102  /* -------- Sim -------- */
103  /**
104   * Single jointed arm simulation for the pivot
105   */
106  protected SingleJointedArmSim _pivotSim;
107  /**
108   * CANcoder simulation
109   */
110  protected CANcoderSimState _pivotCancoderSim;
111  /**
112   * Position of the simulated pivot in rotations
113   */
114  protected double _simRotations;
115  /**
116   * Velocity of the simulated pivot in rotations per second
117   */
118  protected double _simVeloRPS;
119  /**
120   * Acceleration of the simulated pivot in rotations per second squared
121   */
122  protected double _simAccelRPS2;
123  /**
124   * Simulated arm of the pivot
125   */
126  protected MechanismLigament2d _pivotLigament;
127
128  /**
129   * Constructs a pivot microsystem with the below configurations
130   *
131   * @param conf Configurations for the pivot
132   */
133  public Pivot(PivotConf conf) {
134    super(conf);
135    _pivotConf = conf;
136
137    if (_configuredMicrosystemDisable) {
138      _defaultPivotLowerToleranceRot = 0.0;
139      _defaultPivotUpperToleranceRot = 0.0;
140      _absoluteRangeRot = 0.0;
141      _minPositionRot = 0.0;
142      _maxPositionRot = 0.0;
143      _maxVelocityRPS = 0.0;
144      _maxAccelerationRPS2 = 0.0;
145      _profileTargetOffset = 0.0;
146      _ffCenterOfMassOffsetRad = 0.0;
147      return;
148    }
149
150    _pivotCancoder = new CANcoder(_pivotConf.encoderDeviceID, _pivotConf.encoderCanBus);
151
152    _pivotFF = _pivotConf.feedForward;
153    _defaultPivotLowerToleranceRot = _pivotConf.defaultLowerTolerance;
154    _defaultPivotUpperToleranceRot = _pivotConf.defaultUpperTolerance;
155    _minPositionRot = _pivotConf.rotationalMin;
156    _maxPositionRot = _pivotConf.rotationalMax;
157    _absoluteRangeRot = _maxPositionRot - _minPositionRot;
158    _maxVelocityRPS = _pivotConf.trapezoidalLimitsVelocity;
159    _maxAccelerationRPS2 = _pivotConf.trapezoidalLimitsAcceleration;
160    _profileTargetOffset = _pivotConf.profileOffsetValue;
161    _ffCenterOfMassOffsetRad = _pivotConf.ffOffsetValue;
162
163    _trapProfile = new TrapezoidProfile(_pivotConf.trapezoidalLimits);
164    _curState.position = getPivotPosition();
165
166    _motorToEncoderRatio = _pivotConf.motorToEncoderRatio;
167    _encoderToPivotRatio = _pivotConf.encoderToPivotRatio;
168
169    _pivotCancoderConfiguration = _pivotConf.encoderConfig;
170
171    double minAbs = AlgebraicUtils.cppMod(_minPositionRot, 1.0);
172    double maxAbs = AlgebraicUtils.cppMod(_maxPositionRot, 1.0);
173    double halfUnusedRange = (_absoluteRangeRot) / 2.0;
174    double midUnused = maxAbs + halfUnusedRange;
175
176    if (midUnused > 1.0) {
177      _values = new double[] {midUnused - 1.0, minAbs, maxAbs, 1.0};
178      _ids = new int[] {2, 0, 1, 2};
179    } else if (_minPositionRot > 0.0) {
180      _values = new double[] {minAbs, maxAbs, midUnused, 1.0};
181      _ids = new int[] {0, 1, 2, 0};
182    } else {
183      _values = new double[] {maxAbs, midUnused, minAbs, 1.0};
184      _ids = new int[] {1, 2, 0, 1};
185    }
186    if (IterativeRobotBase.isReal()) {
187      int count = 0;
188      // while (!_primaryMotor.isAlive() && count <= 1000) {
189      // System.out.println(_pivotConf.name + " not alive " + (count++));
190      // }
191      if (count >= 1000) {
192        System.out.println(_pivotConf.name + " failed to initialize!");
193      }
194    }
195
196    configCancoder();
197    configAllDevices();
198    configMotor();
199  }
200
201  /**
202   * Periodic update function
203   */
204  public void periodic() {
205    if (_isMicrosystemDisabled) {
206      return;
207    } else if (motorResetConfig()) {
208      setPivotProfile(getPivotPosition(), 0.0);
209      _primaryMotor.set(0.0);
210    } else if (_isFFTuningMicro && _trapProfile.isFinished(_profileTimer.get())) {
211      _primaryMotor.setControl(_requestedPositionVoltage.withFeedForward(
212          _pivotFF.getKs() + _pivotFF.getKs() * Math.cos(getFFPositionRad())
213      ));
214    }
215
216    if (_followProfile) {
217      followLastProfile();
218    }
219  }
220
221  /**
222   * Gets the primary motor of the pivot
223   *
224   * @return primary motor
225   */
226  public TalonFX getMotor() {
227    return _primaryMotor;
228  }
229
230  /**
231   * Executes logic for when the robot is first enabled
232   */
233  @Override
234  public void onEnable() {
235    if (_isMicrosystemDisabled) {
236      return;
237    }
238    super.onEnable();
239
240    if (_isFFTuningMicro) {
241      _pivotFF = new ArmFeedforward(
242          _KSEntry.getDouble(_pivotFF.getKs()),
243          _KGEntry.getDouble(_pivotFF.getKg()),
244          _KVEntry.getDouble(_pivotFF.getKv()),
245          _KAEntry.getDouble(_pivotFF.getKa())
246      );
247      _primaryMotor.setControl(_requestedPositionVoltage.withFeedForward(
248          _pivotFF.getKs() + _pivotFF.getKs() * Math.cos(getFFPositionRad())
249      ));
250    }
251  }
252
253  @Override
254  public void onDisable() {
255    if (_isMicrosystemDisabled) {
256      return;
257    }
258
259    super.onDisable();
260  }
261
262  /**
263   * Updates shuffleboard with the pivot's current position and velocity
264   */
265  @Override
266  public void updateShuffleboard() {
267    if (_isMicrosystemDisabled) {
268      return;
269    }
270    if (_isShuffleboardMicro) {
271      _currentPositionEntry.setDouble(getPivotPosition());
272      _currentVelocityEntry.setDouble(getPivotVelocity());
273    }
274  }
275
276  /**
277   * Converts motor rotations to rotations of the pivot mechanism
278   *
279   * @param motorRot position of the motor in rotations
280   * @return position of the pivot in rotations
281   */
282  public double motorToPivotRot(double motorRot) {
283    if (_isMicrosystemDisabled) {
284      return 0.0;
285    }
286    // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
287    return motorRot / (_encoderToPivotRatio * _motorToEncoderRatio);
288  }
289
290  /**
291   * Converts rotations of the pivot mechanism to motor rotations
292   *
293   * @param pivotRot position of the pivot in rotations
294   * @return position of the motor in rotations
295   */
296  public double pivotRotToMotor(double pivotRot) {
297    if (_isMicrosystemDisabled) {
298      return 0.0;
299    }
300    // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
301    return pivotRot * (_encoderToPivotRatio * _motorToEncoderRatio);
302  }
303
304  /**
305   * Configure shuffleboard for the pivot
306   */
307  @Override
308  public void configShuffleboard() {
309    if (_isMicrosystemDisabled) {
310      return;
311    }
312    super.configShuffleboard();
313  }
314
315  /**
316   * Calculates the next state according to the trapezoidal profile and requests the pivot motor(s)
317   * to arrive at the next position with feedforward
318   */
319  public void followLastProfile() {
320    if (_isMicrosystemDisabled) {
321      return;
322    }
323
324    TrapezoidProfile.State nextState =
325        _trapProfile.calculate(TagalongConfiguration.LOOP_PERIOD_S, _curState, _goalState);
326    // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot, convert to motor units
327    _primaryMotor.setControl(
328        _requestedPositionVoltage
329            .withPosition(nextState.position)
330            // FeedForward must know the pivot rotation and other arguments in radians
331            .withFeedForward(
332                _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(nextState.velocity))
333            )
334    );
335
336    if (_isShuffleboardMicro) {
337      _targetPositionEntry.setDouble(nextState.position);
338      _targetVelocityEntry.setDouble(nextState.velocity);
339    }
340
341    _curState = nextState;
342  }
343
344  /**
345   * Gets the position offset for feedforward (to account for a shifted center of
346   * mass) in rotations
347   *
348   * @return offset position in rotations
349   */
350  public double getFFPositionRad() {
351    if (_isMicrosystemDisabled) {
352      return 0.0;
353    }
354
355    // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
356    return Units.rotationsToRadians(_pivotCancoder.getPosition().getValueAsDouble())
357        + _ffCenterOfMassOffsetRad;
358  }
359
360  /**
361   * Sets the power of the primary motor
362   *
363   * @param power desired power
364   */
365  public void setPivotPower(double power) {
366    setPrimaryPower(power);
367  }
368
369  /**
370   * Gets the power of the primary motor
371   *
372   * @return the current power
373   */
374  public double getPivotPower() {
375    return getPrimaryMotorPower();
376  }
377
378  /**
379   * Sets the velocity of the pivot in RPS
380   *
381   * @param rps Desired velocity in rotations per second
382   * @param withFF with feedforward
383   */
384  public void setPivotVelocity(double rps, boolean withFF) {
385    if (_isMicrosystemDisabled) {
386      return;
387    }
388    setFollowProfile(false);
389
390    _primaryMotor.setControl(
391        _requestedVelocityVoltage
392            // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
393            .withVelocity(rps)
394            .withFeedForward(
395                withFF ? _pivotFF.calculate(getFFPositionRad(), Units.rotationsToRadians(rps)) : 0.0
396            )
397    );
398  }
399
400  /**
401   * Gets the current position of the pivot in rotations
402   *
403   * @return the position of the primary motor which is the same as the position of the pivot when
404   *     they are fused
405   */
406  public double getPivotPosition() {
407    return getPrimaryMotorPosition();
408  }
409
410  /**
411   * Gets the current velocity of the pivot in rotations per second
412   *
413   * @return the velocity of the primary motor which is the same as the velocity of the pivot when
414   *     they are fused
415   */
416  public double getPivotVelocity() {
417    return getPrimaryMotorVelocity();
418  }
419
420  /**
421   * Returns the new pivot angle in the closest scope of the reference pivot angle
422   *
423   * @param scopeReferenceRot reference angle in rotations
424   * @param newAngleRot       angle to be scoped in rotations
425   * @return scoped newAngleRot
426   */
427  public double placePivotInClosestRot(double scopeReferenceRot, double newAngleRot) {
428    return AlgebraicUtils.placeInScopeRot(scopeReferenceRot, newAngleRot);
429  }
430
431  /**
432   * Creates a new trapezoidal profile for the pivot to follow
433   *
434   * @param goalPosition     goal position in rotations
435   */
436  public void setPivotProfile(Angle goalPosition) {
437    setPivotProfile(goalPosition.getRotations());
438  }
439
440  /**
441   * Creates a new trapezoidal profile for the pivot to follow
442   *
443   * @param goalPosition     goal position in rotations
444   * @param goalVelocityRPS     goal velocity in rotations per second
445   */
446  public void setPivotProfile(Angle goalPosition, double goalVelocityRPS) {
447    setPivotProfile(goalPosition.getRotations(), goalVelocityRPS);
448  }
449
450  /**
451   * Creates a new trapezoidal profile for the pivot to follow
452   *
453   * @param goalPosition     goal position in rotations
454   * @param goalVelocityRPS     goal velocity in rotations per second
455   * @param maxVelocityRPS      maximum velocity in rotations per second
456   */
457  public void setPivotProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS) {
458    setPivotProfile(goalPosition.getRotations(), goalVelocityRPS, maxVelocityRPS);
459  }
460
461  /**
462   * Creates a new trapezoidal profile for the pivot to follow
463   *
464   * @param goalPosition     goal position in rotations
465   * @param goalVelocityRPS     goal velocity in rotations per second
466   * @param maxVelocityRPS      maximum velocity in rotations per second
467   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
468   */
469  public void setPivotProfile(
470      Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2
471  ) {
472    setPivotProfile(
473        goalPosition.getRotations(), goalVelocityRPS, maxVelocityRPS, maxAccelerationRPS2
474    );
475  }
476
477  /**
478   * Creates a new trapezoidal profile for the pivot to follow
479   *
480   * @param goalPosition     goal position in rotations
481   * @param goalVelocityRPS     goal velocity in rotations per second
482   * @param maxVelocityRPS      maximum velocity in rotations per second
483   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
484   * @param setCurrentState     True if the profiles current state should base itself off sensor
485   *     values rather than continue from the existing state
486   */
487  public void setPivotProfile(
488      Angle goalPosition,
489      double goalVelocityRPS,
490      double maxVelocityRPS,
491      double maxAccelerationRPS2,
492      boolean setCurrentState
493  ) {
494    setPivotProfile(
495        goalPosition.getRotations(),
496        goalVelocityRPS,
497        maxVelocityRPS,
498        maxAccelerationRPS2,
499        setCurrentState
500    );
501  }
502
503  /**
504   * Creates a new trapezoidal profile for the pivot to follow
505   *
506   * @param goalPositionRot goal position in rotations
507   */
508  public void setPivotProfile(double goalPositionRot) {
509    setPivotProfile(goalPositionRot, 0.0);
510  }
511
512  /**
513   * Creates a new trapezoidal profile for the pivot to follow
514   *
515   * @param goalPositionRot goal position in rotations
516   * @param goalVelocityRPS goal velocity in rotations per second
517   */
518  public void setPivotProfile(double goalPositionRot, double goalVelocityRPS) {
519    setPivotProfile(goalPositionRot, goalVelocityRPS, _maxVelocityRPS);
520  }
521
522  /**
523   * Creates a new trapezoidal profile for the pivot to follow
524   *
525   * @param goalPositionRot goal position in rotations
526   * @param goalVelocityRPS goal velocity in rotations per second
527   * @param maxVelocityRPS  maximum velocity in rotations per second
528   */
529  public void setPivotProfile(
530      double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS
531  ) {
532    setPivotProfile(goalPositionRot, goalVelocityRPS, maxVelocityRPS, _maxAccelerationRPS2);
533  }
534
535  /**
536   * Creates a new trapezoidal profile for the pivot to follow
537   *
538   * @param goalPositionRot     goal position in rotations
539   * @param goalVelocityRPS     goal velocity in rotations per second
540   * @param maxVelocityRPS      maximum velocity in rotations per second
541   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
542   */
543  public void setPivotProfile(
544      double goalPositionRot,
545      double goalVelocityRPS,
546      double maxVelocityRPS,
547      double maxAccelerationRPS2
548  ) {
549    setPivotProfile(goalPositionRot, goalVelocityRPS, maxVelocityRPS, maxAccelerationRPS2, true);
550  }
551
552  /**
553   * Creates a new trapezoidal profile for the pivot to follow
554   *
555   * @param goalPositionRot     goal position in rotations
556   * @param goalVelocityRPS     goal velocity in rotations per second
557   * @param maxVelocityRPS      maximum velocity in rotations per second
558   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
559   * @param setCurrentState     True if the profiles current state should base itself off sensor
560   *     values rather than continue from the existing state
561   */
562  public void setPivotProfile(
563      double goalPositionRot,
564      double goalVelocityRPS,
565      double maxVelocityRPS,
566      double maxAccelerationRPS2,
567      boolean setCurrentState
568  ) {
569    if (_isMicrosystemDisabled) {
570      return;
571    }
572    setFollowProfile(false);
573
574    if (setCurrentState) {
575      _curState.position = getPivotPosition();
576      _curState.velocity = getPivotVelocity();
577    }
578
579    _goalState.velocity = goalVelocityRPS;
580    _goalState.position = (_absoluteRangeRot < 1.0 ? absoluteClamp(goalPositionRot)
581                                                   : clampPivotPosition(goalPositionRot))
582        + _profileTargetOffset;
583
584    _trapProfile = new TrapezoidProfile(
585        (maxVelocityRPS >= _maxVelocityRPS || maxAccelerationRPS2 >= _maxAccelerationRPS2)
586            ? _pivotConf.trapezoidalLimits
587            : new TrapezoidProfile.Constraints(maxVelocityRPS, maxAccelerationRPS2)
588    );
589
590    _profileTimer.restart();
591  }
592
593  /**
594   * Configures the CANcoder according to specified configuration
595   */
596  private void configCancoder() {
597    if (_isMicrosystemDisabled) {
598      return;
599    }
600
601    _pivotCancoder.getConfigurator().apply(_pivotCancoderConfiguration);
602  }
603
604  /**
605   * Configures the motor according to specified configuration
606   */
607  private void configMotor() {
608    for (int i = 0; i < _conf.numMotors; i++) {
609      _conf.motorConfig[i].withFeedback(
610          new FeedbackConfigs()
611              .withFeedbackSensorSource(FeedbackSensorSourceValue.FusedCANcoder)
612              .withFeedbackRemoteSensorID(_pivotCancoder.getDeviceID())
613              .withRotorToSensorRatio(_pivotConf.motorToEncoderRatio)
614              .withSensorToMechanismRatio(_pivotConf.encoderToPivotRatio)
615      );
616      _allMotors[i].getConfigurator().apply(_conf.motorConfig[i]);
617    }
618  }
619
620  /**
621   * Clamps the goal pivot position to be within rotational limits
622   *
623   * @param target goal position in rotations
624   * @return clamped goal position in rotations
625   */
626  public double clampPivotPosition(double target) {
627    return AlgebraicUtils.clamp(target, _minPositionRot, _maxPositionRot);
628  }
629
630  /**
631   * Resets devices if resets have occurred
632   */
633  @Override
634  public boolean motorResetConfig() {
635    if (_isMicrosystemDisabled) {
636      return false;
637    }
638    if (_primaryMotor.hasResetOccurred()) {
639      configAllDevices();
640      configMotor();
641      return true;
642    }
643    if (_pivotCancoder.hasResetOccurred()) {
644      configCancoder();
645      return true;
646    }
647    return false;
648  }
649
650  /**
651   * Initializes the pivot simulation
652   */
653  @Override
654  public void simulationInit() {
655    if (_isMicrosystemDisabled) {
656      return;
657    }
658
659    _pivotSim = new SingleJointedArmSim(
660        _pivotConf.motorTypes[0].simSupplier.apply(_pivotConf.numMotors),
661        _motorToEncoderRatio * _encoderToPivotRatio,
662        _pivotConf.pivotMOI,
663        _pivotConf.pivotLengthM,
664        Units.rotationsToRadians(_minPositionRot),
665        Units.rotationsToRadians(_maxPositionRot),
666        true,
667        Units.rotationsToRadians(0)
668    );
669
670    _mechanism = new Mechanism2d(_pivotConf.mech2dDim, _pivotConf.mech2dDim);
671    SmartDashboard.putData("SIM: " + _pivotConf.name, _mechanism);
672
673    _root = _mechanism.getRoot(_pivotConf.name, _pivotConf.rootX, _pivotConf.rootY);
674    _pivotLigament = new MechanismLigament2d(_pivotConf.name, _pivotConf.pivotLengthM, 0.0);
675    _root.append(_pivotLigament);
676    _pivotLigament.setColor(new Color8Bit(255, 255, 255));
677
678    _pivotCancoderSim = _pivotCancoder.getSimState();
679    _primaryMotorSim = _primaryMotor.getSimState();
680  }
681
682  /**
683   * Runs the pivot simulation--sets motor and cancoder simulation fields and updates the visual
684   */
685  @Override
686  public void simulationPeriodic() {
687    if (_isMicrosystemDisabled) {
688      return;
689    }
690    _pivotSim.setInputVoltage(_primaryMotor.get() * RobotController.getBatteryVoltage());
691    _pivotSim.update(TagalongConfiguration.LOOP_PERIOD_S);
692
693    // FUTURE DEV: modify to allow for unfused or not 1:1 with pivot
694    double prevSimVelo = _simVeloRPS;
695    _simVeloRPS = Units.radiansToRotations(_pivotSim.getVelocityRadPerSec());
696    _simRotations += Units.radiansToRotations(_pivotSim.getAngleRads());
697    _simAccelRPS2 = (_simVeloRPS - prevSimVelo) / TagalongConfiguration.LOOP_PERIOD_S;
698
699    _pivotLigament.setAngle(Rotation2d.fromRadians(_pivotSim.getAngleRads()));
700
701    _pivotCancoderSim.setRawPosition(Units.radiansToRotations(_pivotSim.getAngleRads()));
702    _pivotCancoderSim.setVelocity(_simVeloRPS);
703    _pivotCancoderSim.setSupplyVoltage(RobotController.getBatteryVoltage());
704
705    _primaryMotorSim.setRawRotorPosition(pivotRotToMotor(_simRotations));
706    _primaryMotorSim.setRotorVelocity(pivotRotToMotor(_simVeloRPS));
707    _primaryMotorSim.setRotorAcceleration(pivotRotToMotor(_simAccelRPS2));
708    _primaryMotorSim.setSupplyVoltage(RobotController.getBatteryVoltage());
709
710    RoboRioSim.setVInVoltage(
711        BatterySim.calculateDefaultBatteryLoadedVoltage(_pivotSim.getCurrentDrawAmps())
712    );
713  }
714
715  /**
716   * Checks whether or not it's safe for the pivot to move
717   *
718   * @return whether or not it's safe to move
719   */
720  public boolean isSafeToMove() {
721    if (_isMicrosystemDisabled) {
722      return true;
723    }
724    return true;
725  }
726
727  /**
728   * Directs the pivot to its maximum position, current goal position, or minimum position
729   *
730   * @param value goal position
731   * @return redirected goal position
732   */
733  public double absoluteClamp(double value) {
734    double abs = AlgebraicUtils.cppMod(value, 1.0);
735    int i = 0;
736    while (abs >= _values[i] && i < _values.length) {
737      i++;
738    }
739    switch (_ids[i]) {
740      case 2:
741        return _maxPositionRot;
742      case 1:
743        return abs;
744      case 0:
745      default:
746        return _minPositionRot;
747    }
748  }
749
750  /**
751   * Bounds checking function that uses the current pivot position
752   *
753   * @param lowerBound minimum of acceptable range
754   * @param upperBound maximum of acceptable range
755   * @return if the current position is greater than or equal to the lower bound and less than or
756   *     equal to the upper bound
757   */
758  public boolean isPivotInTolerance(double lowerBound, double upperBound) {
759    if (_isMicrosystemDisabled) {
760      return true;
761    }
762    return AlgebraicUtils.inTolerance(getPivotPosition(), lowerBound, upperBound);
763  }
764
765  /**
766   * Bounds checking function that uses the absolute current pivot position (modulo one rotation)
767   *
768   * @param lowerBound minimum of acceptable range
769   * @param upperBound maximum of acceptable range
770   * @return if the absolute current position is in absolute acceptable range
771   */
772  public boolean isPivotInAbsoluteTolerance(double lowerBound, double upperBound) {
773    double position = AlgebraicUtils.cppMod(getPivotPosition(), 1.0);
774    lowerBound = AlgebraicUtils.cppMod(lowerBound, 1.0);
775    upperBound = AlgebraicUtils.cppMod(upperBound, 1.0);
776    return _isMicrosystemDisabled || position >= 0
777        ? AlgebraicUtils.inTolerance(position, lowerBound, upperBound)
778        : AlgebraicUtils.inTolerance(position + 1.0, lowerBound, upperBound);
779  }
780
781  @Override
782  public void holdCurrentPosition() {
783    setPivotProfile(getPivotPosition(), 0.0);
784    setFollowProfile(true);
785  }
786
787  /**
788   * Retrieves ligament attached to pivot Mechanism2d
789   *
790   * @return pivot ligament
791   */
792  public MechanismLigament2d getPivotLigament() {
793    return _pivotLigament;
794  }
795}