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 */
006
007package tagalong.subsystems.micro;
008
009import edu.wpi.first.math.controller.SimpleMotorFeedforward;
010import edu.wpi.first.math.geometry.Rotation2d;
011import edu.wpi.first.math.system.plant.LinearSystemId;
012import edu.wpi.first.math.trajectory.TrapezoidProfile;
013import edu.wpi.first.wpilibj.RobotController;
014import edu.wpi.first.wpilibj.simulation.BatterySim;
015import edu.wpi.first.wpilibj.simulation.FlywheelSim;
016import edu.wpi.first.wpilibj.simulation.RoboRioSim;
017import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d;
018import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d;
019import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
020import edu.wpi.first.wpilibj.util.Color8Bit;
021import edu.wpi.first.wpilibj2.command.Command;
022import edu.wpi.first.wpilibj2.command.Commands;
023import edu.wpi.first.wpilibj2.command.InstantCommand;
024import java.util.ArrayList;
025import tagalong.TagalongConfiguration;
026import tagalong.math.AlgebraicUtils;
027import tagalong.measurements.Angle;
028import tagalong.subsystems.micro.confs.RollerConf;
029
030/**
031 * Roller microsystem
032 */
033public class Roller extends Microsystem {
034  /**
035   * Configuration for the roller
036   */
037  public final RollerConf _rollerConf;
038
039  /* -------- Hardware: motors and sensors -------- */
040
041  /* -------- Control: states and constants -------- */
042  /**
043   * Ratio between motor rotations and roller rotations
044   */
045  private final double _motorToMechRatio;
046  /**
047   * Default lower tolerance for roller in rotations
048   */
049  public final double _defaultRollerLowerToleranceRot;
050  /**
051   * Default upper tolerance for roller in rotations
052   */
053  public final double _defaultRollerUpperToleranceRot;
054  /**
055   * Maximum velocity in rotations per second
056   */
057  public final double _maxVelocityRPS;
058  /**
059   * Maximum acceleration in rotations per second squared
060   */
061  public final double _maxAccelerationRPS2;
062
063  /* -------- Control: controllers and utilities -------- */
064  /**
065   * Feedforward model of the roller
066   */
067  protected SimpleMotorFeedforward _rollerFF;
068
069  /* -------- Sim -------- */
070  /**
071   * Flywheel simulation for the roller motor
072   */
073  protected FlywheelSim _rollerSim;
074  /**
075   * Simulated number of rotations
076   */
077  protected double _simRotations;
078  /**
079   * Simulated velocity in rotations per minute
080   */
081  protected double _simVeloRPM;
082  /**
083   * Simulated acceleration in rotations per minute squared
084   */
085  protected double _simAccelRPM2;
086  /**
087   * Simulated current angle of the roller
088   */
089  protected double _curSimAngle;
090  /**
091   * Roller ligaments
092   */
093  private ArrayList<MechanismLigament2d> _rollerLigaments = new ArrayList<MechanismLigament2d>();
094
095  /**
096   * Constructs a roller microsystem with the below configurations
097   *
098   * @param conf Configuration for the roller
099   */
100  public Roller(RollerConf conf) {
101    super(conf);
102    _rollerConf = conf;
103
104    if (_configuredMicrosystemDisable) {
105      _motorToMechRatio = 1.0;
106      _maxVelocityRPS = 0.0;
107      _maxAccelerationRPS2 = 0.0;
108      _defaultRollerLowerToleranceRot = 0.0;
109      _defaultRollerUpperToleranceRot = 0.0;
110      return;
111    }
112
113    _rollerFF = _rollerConf.feedForward;
114    _trapProfile = new TrapezoidProfile(_rollerConf.trapezoidalLimits);
115    _motorToMechRatio = _rollerConf.motorToMechRatio;
116    _maxVelocityRPS = conf.trapezoidalLimitsVelocity;
117    _maxAccelerationRPS2 = conf.trapezoidalLimitsAcceleration;
118    _defaultRollerLowerToleranceRot = _rollerConf.defaultLowerTolerance;
119    _defaultRollerUpperToleranceRot = _rollerConf.defaultUpperTolerance;
120
121    configAllDevices();
122  }
123
124  @Override
125  public void onEnable() {
126    if (_isMicrosystemDisabled) {
127      return;
128    }
129    super.onEnable();
130
131    if (_isFFTuningMicro) {
132      _rollerFF = new SimpleMotorFeedforward(
133          _KSEntry.getDouble(_rollerFF.getKs()),
134          _KVEntry.getDouble(_rollerFF.getKv()),
135          _KAEntry.getDouble(_rollerFF.getKa())
136      );
137      _primaryMotor.setControl(_requestedPositionVoltage.withFeedForward(_rollerFF.getKs()));
138    }
139  }
140
141  @Override
142  public void onDisable() {
143    if (_isMicrosystemDisabled) {
144      return;
145    }
146
147    super.onDisable();
148  }
149
150  /**
151   * Periodic update function
152   */
153  public void periodic() {
154    if (_isMicrosystemDisabled) {
155      return;
156    } else if (motorResetConfig()) {
157      setRollerProfile(getRollerPosition(), 0.0);
158      _primaryMotor.set(0.0);
159    }
160
161    if (_followProfile) {
162      followLastProfile();
163    }
164  }
165
166  @Override
167  public void simulationInit() {
168    if (_isMicrosystemDisabled) {
169      return;
170    }
171    var dcMotor = _rollerConf.motorTypes[0].simSupplier.apply(_rollerConf.numMotors);
172    _rollerSim = new FlywheelSim(
173        LinearSystemId.createFlywheelSystem(dcMotor, _rollerConf.rollerMOI, _motorToMechRatio),
174        dcMotor,
175        null
176    );
177    _mechanism = new Mechanism2d(_rollerConf.mech2dDim, _rollerConf.mech2dDim);
178    SmartDashboard.putData("SIM: " + _rollerConf.name, _mechanism);
179
180    _root = _mechanism.getRoot(_rollerConf.name, _rollerConf.rootX, _rollerConf.rootY);
181    for (int i = 1; i <= _rollerConf.simNumLigaments; i++) {
182      MechanismLigament2d ligament = new MechanismLigament2d(
183          _rollerConf.name + " " + i, 10, i * (360 / _rollerConf.simNumLigaments)
184      );
185      _rollerLigaments.add(ligament);
186      _root.append(ligament);
187
188      // FUTURE DEV: allow for explicit color configuration
189      ligament.setColor(new Color8Bit(
190          i * 255 / _rollerConf.simNumLigaments,
191          i * 255 / _rollerConf.simNumLigaments,
192          i * 255 / _rollerConf.simNumLigaments
193      ));
194    }
195    _primaryMotorSim = _primaryMotor.getSimState();
196  }
197
198  @Override
199  public void simulationPeriodic() {
200    if (_isMicrosystemDisabled) {
201      return;
202    }
203    _rollerSim.setInput(getPrimaryMotorPower() * RobotController.getBatteryVoltage());
204    _rollerSim.update(TagalongConfiguration.LOOP_PERIOD_S);
205
206    double prevSimVelo = _simVeloRPM;
207    _simVeloRPM = _rollerSim.getAngularVelocityRPM();
208    _simRotations += _simVeloRPM * TagalongConfiguration.LOOP_PERIOD_S / 60.0;
209    _simAccelRPM2 = (_simVeloRPM - prevSimVelo) * 60.0 / TagalongConfiguration.LOOP_PERIOD_S;
210
211    for (int i = 1; i <= _rollerConf.simNumLigaments; i++) {
212      _rollerLigaments.get(i - 1).setAngle(
213          Rotation2d.fromRotations(_simRotations + (i * (1.0 / _rollerConf.simNumLigaments)))
214      );
215    }
216
217    _primaryMotorSim.setRawRotorPosition(rollerRotToMotor(_simRotations));
218    _primaryMotorSim.setRotorVelocity(rollerRotToMotor(_rollerSim.getAngularVelocityRPM() / 60.0));
219    _primaryMotorSim.setRotorAcceleration(rollerRotToMotor(_simAccelRPM2 / 3600.0));
220    _primaryMotorSim.setSupplyVoltage(RobotController.getBatteryVoltage());
221
222    RoboRioSim.setVInVoltage(
223        BatterySim.calculateDefaultBatteryLoadedVoltage(_rollerSim.getCurrentDrawAmps())
224    );
225  }
226
227  @Override
228  public boolean motorResetConfig() {
229    if (_isMicrosystemDisabled) {
230      return false;
231    }
232    return super.motorResetConfig();
233  }
234
235  @Override
236  public void updateShuffleboard() {
237    if (_isMicrosystemDisabled) {
238      return;
239    }
240    if (_isShuffleboardMicro) {
241      _currentPositionEntry.setDouble(getRollerPosition());
242      _currentVelocityEntry.setDouble(getRollerVelocity());
243    }
244  }
245
246  @Override
247  public void configShuffleboard() {
248    if (_isMicrosystemDisabled) {
249      return;
250    }
251    super.configShuffleboard();
252  }
253
254  /**
255   * Converts motor rotations to roller rotations
256   *
257   * @param motorRot motor rotations
258   * @return roller rotations converted from motor rotations
259   *
260   */
261  public double motorToRollerRot(double motorRot) {
262    if (_isMicrosystemDisabled) {
263      return 0.0;
264    }
265    return motorRot / _motorToMechRatio;
266  }
267
268  /**
269   * Converts motor rotations to roller rotations
270   *
271   * @param rollerRot roller rotations
272   * @return motor rotations converted from roller rotations
273   */
274  public double rollerRotToMotor(double rollerRot) {
275    if (_isMicrosystemDisabled) {
276      return 0.0;
277    }
278    return rollerRot * _motorToMechRatio;
279  }
280
281  /**
282   * Calculates the next state according to the trapezoidal profile and requests the roller motor(s)
283   * to arrive at the next position with feedforward
284   */
285  public void followLastProfile() {
286    if (_isMicrosystemDisabled) {
287      return;
288    }
289    TrapezoidProfile.State nextState =
290        _trapProfile.calculate(TagalongConfiguration.LOOP_PERIOD_S, _curState, _goalState);
291
292    // Control and FeedForward based on mechanism rotations rather than motor rotations
293    _primaryMotor.setControl(_requestedPositionVoltage
294                                 .withPosition(rollerRotToMotor(nextState.position))
295                                 .withFeedForward(_rollerFF.calculate(nextState.velocity)));
296
297    if (_isShuffleboardMicro) {
298      _targetPositionEntry.setDouble(nextState.position);
299      _targetVelocityEntry.setDouble(nextState.velocity);
300    }
301
302    _curState = nextState;
303  }
304
305  /**
306   * Creates a new trapezoidal profile for the roller to follow
307   *
308   * @param goalPosition     goal position in rotations
309   */
310  public void setRollerProfile(Angle goalPosition) {
311    setRollerProfile(goalPosition.getRotations());
312  }
313  /**
314   * Creates a new trapezoidal profile for the roller to follow
315   *
316   * @param goalPosition     goal position in rotations
317   * @param goalVelocityRPS     goal velocity in rotations per second
318   */
319  public void setRollerProfile(Angle goalPosition, double goalVelocityRPS) {
320    setRollerProfile(goalPosition.getRotations(), goalVelocityRPS);
321  }
322
323  /**
324   * Creates a new trapezoidal profile for the roller to follow
325   *
326   * @param goalPosition     goal position in rotations
327   * @param goalVelocityRPS     goal velocity in rotations per second
328   * @param maxVelocityRPS      maximum velocity in rotations per second
329   */
330  public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS) {
331    setRollerProfile(goalPosition.getRotations(), goalVelocityRPS, maxVelocityRPS);
332  }
333
334  /**
335   * Creates a new trapezoidal profile for the roller to follow
336   *
337   * @param goalPosition     goal position in rotations
338   * @param goalVelocityRPS     goal velocity in rotations per second
339   * @param maxVelocityRPS      maximum velocity in rotations per second
340   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
341   */
342  public void setRollerProfile(
343      Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2
344  ) {
345    setRollerProfile(
346        goalPosition.getRotations(), goalVelocityRPS, maxVelocityRPS, maxAccelerationRPS2
347    );
348  }
349
350  /**
351   * Creates a new trapezoidal profile for the roller to follow
352   *
353   * @param goalPosition     goal position in rotations
354   * @param goalVelocityRPS     goal velocity in rotations per second
355   * @param maxVelocityRPS      maximum velocity in rotations per second
356   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
357   * @param setCurrentState     True if the profiles current state should base itself off sensor
358   *     values rather than continue from the existing state
359   */
360  public void setRollerProfile(
361      Angle goalPosition,
362      double goalVelocityRPS,
363      double maxVelocityRPS,
364      double maxAccelerationRPS2,
365      boolean setCurrentState
366  ) {
367    setRollerProfile(
368        goalPosition.getRotations(),
369        goalVelocityRPS,
370        maxVelocityRPS,
371        maxAccelerationRPS2,
372        setCurrentState
373    );
374  }
375
376  /**
377   * Creates a new trapezoidal profile for the roller to follow
378   *
379   * @param goalPositionRot goal position in rotations
380   */
381  public void setRollerProfile(double goalPositionRot) {
382    setRollerProfile(goalPositionRot, 0.0);
383  }
384
385  /**
386   * Creates a new trapezoidal profile for the roller to follow
387   *
388   * @param goalPositionRot goal position in rotations
389   * @param goalVelocityRPS goal velocity in rotations per second
390   */
391  public void setRollerProfile(double goalPositionRot, double goalVelocityRPS) {
392    setRollerProfile(goalPositionRot, goalVelocityRPS, _maxVelocityRPS);
393  }
394
395  /**
396   * Creates a new trapezoidal profile for the roller to follow
397   *
398   * @param goalPositionRot goal position in rotations
399   * @param goalVelocityRPS goal velocity in rotations per second
400   * @param maxVelocityRPS  maximum velocity in rotations per second
401   */
402  public void setRollerProfile(
403      double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS
404  ) {
405    setRollerProfile(goalPositionRot, goalVelocityRPS, maxVelocityRPS, _maxAccelerationRPS2);
406  }
407
408  /**
409   * Creates a new trapezoidal profile for the roller to follow
410   *
411   * @param goalPositionRot     goal position in rotations
412   * @param goalVelocityRPS     goal velocity in rotations per second
413   * @param maxVelocityRPS      maximum velocity in rotations per second
414   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
415   */
416  public void setRollerProfile(
417      double goalPositionRot,
418      double goalVelocityRPS,
419      double maxVelocityRPS,
420      double maxAccelerationRPS2
421  ) {
422    setRollerProfile(goalPositionRot, goalVelocityRPS, maxVelocityRPS, maxAccelerationRPS2, true);
423  }
424
425  /**
426   * Creates a new trapezoidal profile for the roller to follow
427   *
428   * @param goalPositionRot     goal position in rotations
429   * @param goalVelocityRPS     goal velocity in rotations per second
430   * @param maxVelocityRPS      maximum velocity in rotations per second
431   * @param maxAccelerationRPS2 maximum acceleration in rotations per second squared
432   * @param setCurrentState     True if the profiles current state should base itself off sensor
433   *     values rather than continue from the existing state
434   */
435  public void setRollerProfile(
436      double goalPositionRot,
437      double goalVelocityRPS,
438      double maxVelocityRPS,
439      double maxAccelerationRPS2,
440      boolean setCurrentState
441  ) {
442    if (_isMicrosystemDisabled) {
443      return;
444    }
445    setFollowProfile(false);
446
447    if (setCurrentState) {
448      _curState.position = getRollerPosition();
449      _curState.velocity = getRollerVelocity();
450    }
451
452    _goalState.position = goalPositionRot;
453    _goalState.velocity = goalVelocityRPS;
454
455    _trapProfile = new TrapezoidProfile(
456        (maxVelocityRPS >= _maxVelocityRPS || maxAccelerationRPS2 >= _maxAccelerationRPS2)
457            ? _rollerConf.trapezoidalLimits
458            : new TrapezoidProfile.Constraints(maxVelocityRPS, maxAccelerationRPS2)
459    );
460
461    _profileTimer.restart();
462  }
463
464  /**
465   * Sets the power of the primary roller motor
466   *
467   * @param power roller power
468   */
469  public void setRollerPower(double power) {
470    setPrimaryPower(power);
471  }
472
473  /**
474   * Gets the power of the primary roller motor
475   *
476   * @return roller power
477   */
478  public double getRollerPower() {
479    return getPrimaryMotorPower();
480  }
481
482  /**
483   * Gets the position of the roller in rotations
484   *
485   * @return roller position in rotations
486   */
487  public double getRollerPosition() {
488    return motorToRollerRot(getPrimaryMotorPosition());
489  }
490
491  /**
492   * Gets the velocity of roller in rotations
493   *
494   * @return roller velocity
495   */
496  public double getRollerVelocity() {
497    return motorToRollerRot(getPrimaryMotorVelocity());
498  }
499
500  /**
501   * Sets the velocity of the roller in RPS
502   *
503   * @param rps    Desired velocity in rotations per second
504   * @param withFF with feedforward
505   */
506  public void setRollerVelocity(double rps, boolean withFF) {
507    if (_isMicrosystemDisabled) {
508      return;
509    }
510
511    setFollowProfile(false);
512    _primaryMotor.setControl(_requestedVelocityVoltage.withVelocity(rollerRotToMotor(rps))
513                                 .withFeedForward(withFF ? _rollerFF.calculate(rps) : 0.0));
514  }
515
516  /**
517   * Checks if the roller is at the target speed
518   *
519   * @param targetSpeed target speed in rotations per second
520   * @return if roller is at target speed
521   */
522  public boolean isRollerAtTargetSpeed(double targetSpeed) {
523    if (_isMicrosystemDisabled) {
524      return true;
525    }
526    return AlgebraicUtils.inTolerance(
527        getRollerVelocity() - targetSpeed,
528        -_defaultRollerLowerToleranceRot,
529        _defaultRollerUpperToleranceRot
530    );
531  }
532
533  /**
534   * Command that sets the roller power
535   *
536   * @param power roller power
537   * @return instant command to set roller power
538   */
539  public Command setRollerPowerCmd(double power) {
540    return new InstantCommand(() -> setRollerPower(power));
541  }
542
543  /**
544   * Command that sets the velocity of the roller in rotations per second
545   *
546   * @param rps rotations per second
547   * @return instant command to set roller velocity
548   */
549  public Command setRollerRPSCmd(double rps) {
550    return new InstantCommand(() -> setRollerVelocity(rps, false));
551  }
552
553  /**
554   * Command that sets the velocity of the roller in rotations per second with feedforward
555   *
556   * @param rps rotations per second
557   * @return instant command to set roller velocity with feedforward
558   */
559  public Command setRollerRPSWithFFCmd(double rps) {
560    return new InstantCommand(() -> setRollerVelocity(rps, true));
561  }
562
563  /**
564   * Command that sets the power of the primary motor (zero if interrupted)
565   *
566   * @param power roller power
567   * @return start end command to set roller power
568   */
569  public Command startEndRollerPowerCmd(double power) {
570    return (Commands.startEnd(() -> setRollerPower(power), () -> setRollerPower(0.0)));
571  }
572
573  /**
574   * Command that sets the velocity of the roller in rotations per second (sets zero power if
575   * interrupted)
576   *
577   * @param rps rotations per second
578   * @return start end command to set roller velocity
579   */
580  public Command startEndRollerRPSCmd(double rps) {
581    return Commands.startEnd(() -> setRollerVelocity(rps, false), () -> setRollerPower(0.0));
582  }
583
584  /**
585   * Command that sets the velocity of the roller in rotations per second with feedforward. (sets
586   * zero power if interrupted)
587   *
588   * @param rps rotations per second
589   * @return start end command to set roller velocity with feedforward
590   */
591  public Command startEndRollerRPSWithFFCmd(double rps) {
592    return Commands.startEnd(() -> setRollerVelocity(rps, true), () -> setRollerPower(0.0));
593  }
594
595  /**
596   * Bounds checking function that uses the current roller position
597   *
598   * @param lowerBound minimum of acceptable range
599   * @param upperBound maximum of acceptable range
600   * @return if the current position is in specified acceptable range
601   */
602  public boolean isRollerInTolerance(double lowerBound, double upperBound) {
603    if (_isMicrosystemDisabled) {
604      return true;
605    }
606    return AlgebraicUtils.inTolerance(getRollerPosition(), lowerBound, upperBound);
607  }
608
609  @Override
610  public void holdCurrentPosition() {
611    setRollerProfile(getRollerPosition(), 0.0);
612    setFollowProfile(true);
613  }
614
615  /**
616   * Retrieves ligaments attached to roller Mechanism2d
617   *
618   * @return roller ligaments
619   */
620  public ArrayList<MechanismLigament2d> getRollerLigaments() {
621    return _rollerLigaments;
622  }
623}