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 com.ctre.phoenix6.configs.Slot0Configs; 010import com.ctre.phoenix6.configs.Slot1Configs; 011import com.ctre.phoenix6.configs.Slot2Configs; 012import com.ctre.phoenix6.controls.PositionVoltage; 013import com.ctre.phoenix6.controls.StrictFollower; 014import com.ctre.phoenix6.controls.TorqueCurrentFOC; 015import com.ctre.phoenix6.controls.VelocityVoltage; 016import com.ctre.phoenix6.hardware.TalonFX; 017import com.ctre.phoenix6.sim.TalonFXSimState; 018import edu.wpi.first.math.trajectory.TrapezoidProfile; 019import edu.wpi.first.networktables.GenericPublisher; 020import edu.wpi.first.networktables.GenericSubscriber; 021import edu.wpi.first.wpilibj.DriverStation; 022import edu.wpi.first.wpilibj.IterativeRobotBase; 023import edu.wpi.first.wpilibj.Timer; 024import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts; 025import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; 026import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout; 027import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; 028import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; 029import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d; 030import tagalong.TagalongConfiguration; 031import tagalong.controls.PIDSGVAConstants; 032import tagalong.subsystems.micro.confs.MicrosystemConf; 033 034/** 035 * Base class for all Tagalong Microsystems 036 */ 037public class Microsystem { 038 /** 039 * Configuration common to all microsystems 040 */ 041 public final MicrosystemConf _conf; 042 043 /** 044 * True if the microsystem is configured to be disabled by a null in the conf 045 * files 046 */ 047 public final boolean _configuredMicrosystemDisable; 048 049 /** 050 * Disablement state, for dynamic disablement caused by hardware disconnects or 051 * on the fly disablement by robot code 052 */ 053 protected boolean _isMicrosystemDisabled = true; 054 055 /** 056 * Microsystem variable for tiling the shuffleboard entries 057 */ 058 public static int _tuningTabCounter = 0; 059 060 /** 061 * True if the microsystem is configured for shuffleboard based logging, also 062 * true if in PID or FF 063 * tuning modes 064 */ 065 protected boolean _isShuffleboardMicro = false; 066 067 /** 068 * True if the microsystem is configured for shuffleboard based PID tuning 069 */ 070 protected boolean _isPIDTuningMicro = false; 071 072 /** 073 * True if the microsystem is configured for shuffleboard based FeedForward 074 * tuning 075 */ 076 protected boolean _isFFTuningMicro = false; 077 078 /* --- Shuffleboard Entries --- */ 079 /** 080 * PID tuning entries that read PID from shuffleboard 081 */ 082 protected GenericSubscriber _slot0PFactorEntry, _slot0IFactorEntry, _slot0DFactorEntry, 083 _slot1PFactorEntry, _slot1IFactorEntry, _slot1DFactorEntry, _slot2PFactorEntry, 084 _slot2IFactorEntry, _slot2DFactorEntry; 085 /** 086 * FeedForward tuning entries that read FeedForward constants from shuffleboard 087 */ 088 protected GenericSubscriber _KSEntry, _KGEntry, _KVEntry, _KAEntry; 089 /** 090 * Logging entries that write robot status values to shuffleboard 091 */ 092 protected GenericPublisher _targetPositionEntry, _targetVelocityEntry, _currentPositionEntry, 093 _currentVelocityEntry; 094 095 /* -------- Hardware: motors and sensors -------- */ 096 /** 097 * The primary motor for the microsystem, all others will follow this motor 098 */ 099 protected TalonFX _primaryMotor; 100 /** 101 * Array of all microsystem motors, the first in the array 102 */ 103 protected TalonFX[] _allMotors; 104 105 /* -------- Control: controllers and utilities -------- */ 106 /** 107 * Shared motor positional voltage request, we put positional PIDSGVA constants 108 * into slot 0 109 */ 110 protected PositionVoltage _requestedPositionVoltage = new PositionVoltage(0.0).withSlot(0); 111 /** 112 * Shared motor velocity voltage request, we put velocity PIDSGVA constants into 113 * slot 1 114 */ 115 protected VelocityVoltage _requestedVelocityVoltage = new VelocityVoltage(0.0).withSlot(1); 116 /** 117 * Shared motor torque current request 118 */ 119 protected TorqueCurrentFOC _requestedTorqueCurrent = new TorqueCurrentFOC(0.0); 120 /** 121 * True if the microsystem should follow the a profile during each periodic loop 122 */ 123 protected boolean _followProfile = false; 124 125 /* -------- Control: states and constants -------- */ 126 /** 127 * Trapezoidal profile follower helper states that track current and goal state 128 */ 129 protected TrapezoidProfile.State _curState = new TrapezoidProfile.State(), 130 _goalState = new TrapezoidProfile.State(); 131 /** 132 * Trapezoidal profile currently being followed 133 */ 134 protected TrapezoidProfile _trapProfile; 135 /** 136 * Timer used for trapezoidal state timing and tracking 137 */ 138 protected Timer _profileTimer = new Timer(); 139 /** 140 * Timer used for tracking how long a system is in tolerance 141 */ 142 protected Timer _toleranceTimer = new Timer(); 143 144 /* ------ SIM ------ */ 145 /** 146 * Simulation for the primary motor 147 */ 148 protected TalonFXSimState _primaryMotorSim; 149 /** 150 * The root of the simulation animation 151 */ 152 protected MechanismRoot2d _root; 153 /** 154 * Visual representation of the elevator 155 */ 156 protected Mechanism2d _mechanism; 157 158 // null parser is a configured disablement 159 /** 160 * Constructs a microsystem with the below configurations 161 * 162 * @param conf Configuration for the microsystem 163 */ 164 public Microsystem(MicrosystemConf conf) { 165 _configuredMicrosystemDisable = conf == null; 166 // In the future we need a more discrete function configuring this 167 _isMicrosystemDisabled = _configuredMicrosystemDisable; 168 _conf = conf; 169 configTuningModes(); 170 171 if (_configuredMicrosystemDisable) { 172 _allMotors = new TalonFX[0]; 173 _primaryMotor = null; 174 return; 175 } 176 177 // Initialize motors 178 _allMotors = new TalonFX[conf.numMotors]; 179 for (int i = 0; i < conf.numMotors; i++) { 180 _allMotors[i] = new TalonFX(conf.motorDeviceIDs[i], conf.motorCanBus[i]); 181 } 182 _primaryMotor = _allMotors[0]; 183 // FUTURE DEV: Inject this here rather than robot builder 184 // configShuffleboard(); 185 waitForInitialization(); 186 } 187 188 /** 189 * Configures devices 190 */ 191 public void configAllDevices() { 192 for (int i = 0; i < _conf.numMotors; i++) { 193 _allMotors[i].getConfigurator().apply(_conf.motorConfig[i]); 194 } 195 196 for (int i = 1; i < _conf.numMotors; i++) { 197 _allMotors[i].setControl(new StrictFollower(_primaryMotor.getDeviceID())); 198 } 199 for (int i = 0; i < _conf.numMotors; i++) { 200 _allMotors[i].setNeutralMode( 201 DriverStation.isDisabled() ? _conf.motorDisabledBrakeMode[i] 202 : _conf.motorEnabledBrakeMode[i] 203 ); 204 } 205 } 206 207 /** 208 * Sets all motors on enable brake mode 209 * 210 * @param enabled whether or not the robot is enabled 211 */ 212 public void setBrakeMode(boolean enabled) { 213 for (int i = 0; i < _conf.numMotors; i++) { 214 _allMotors[i].setNeutralMode( 215 enabled ? _conf.motorEnabledBrakeMode[i] : _conf.motorDisabledBrakeMode[i] 216 ); 217 } 218 } 219 220 /** 221 * 222 */ 223 public void updateAllPIDSGVA() { 224 // update all 3 slots from shuffleboard 225 double s0p = _conf.motorConfig[0].Slot0.kP; 226 double s0i = _conf.motorConfig[0].Slot0.kI; 227 double s0d = _conf.motorConfig[0].Slot0.kD; 228 double s1p = _conf.motorConfig[0].Slot1.kP; 229 double s1i = _conf.motorConfig[0].Slot1.kI; 230 double s1d = _conf.motorConfig[0].Slot1.kD; 231 double s2p = _conf.motorConfig[0].Slot2.kP; 232 double s2i = _conf.motorConfig[0].Slot2.kI; 233 double s2d = _conf.motorConfig[0].Slot2.kD; 234 235 if (_isPIDTuningMicro) { 236 s0p = _slot0PFactorEntry.getDouble(s0p); 237 s0i = _slot0IFactorEntry.getDouble(s0i); 238 s0d = _slot0DFactorEntry.getDouble(s0d); 239 s1p = _slot1PFactorEntry.getDouble(s1p); 240 s1i = _slot1IFactorEntry.getDouble(s1i); 241 s1d = _slot1DFactorEntry.getDouble(s1d); 242 s2p = _slot2PFactorEntry.getDouble(s2p); 243 s2i = _slot2IFactorEntry.getDouble(s2i); 244 s2d = _slot2DFactorEntry.getDouble(s2d); 245 } 246 247 Slot0Configs s0 = 248 new PIDSGVAConstants(s0p, s0i, s0d, 0.0, 0.0, 0.0, 0.0).toCTRESlot0Configuration(); 249 Slot1Configs s1 = 250 new PIDSGVAConstants(s1p, s1i, s1d, 0.0, 0.0, 0.0, 0.0).toCTRESlot1Configuration(); 251 Slot2Configs s2 = 252 new PIDSGVAConstants(s2p, s2i, s2d, 0.0, 0.0, 0.0, 0.0).toCTRESlot2Configuration(); 253 254 for (int i = 0; i < _conf.numMotors; i++) { 255 // FUTURE DEV: add SGVA to shuffleboard 256 _conf.motorConfig[i].Slot0 = s0; 257 _conf.motorConfig[i].Slot1 = s1; 258 _conf.motorConfig[i].Slot2 = s2; 259 260 var configurator = _allMotors[i].getConfigurator(); 261 configurator.apply(_conf.motorConfig[i].Slot0); 262 configurator.apply(_conf.motorConfig[i].Slot1); 263 configurator.apply(_conf.motorConfig[i].Slot2); 264 } 265 } 266 267 /** 268 * Sets break mode for all motors 269 * If system is in PID tuning mode is updates all PID related settings 270 * If the system is in Feedforward Tuning mode, it sets the primary motor to 271 * coast mode. 272 */ 273 public void onEnable() { 274 if (_isMicrosystemDisabled) { 275 return; 276 } 277 278 setBrakeMode(true); 279 280 if (_isPIDTuningMicro) { 281 updateAllPIDSGVA(); 282 } 283 } 284 285 /** 286 * Checks initialize status 287 */ 288 protected void waitForInitialization() { 289 if (IterativeRobotBase.isReal()) { 290 int counter = 0; 291 // FUTURE DEV: Make the counter threshold configurable 292 while (!checkInitStatus() && counter <= 1000) { 293 System.out.println(_conf.name + " Check Init Status : " + counter++); 294 } 295 if (counter >= 1000) { 296 System.out.println(_conf.name + " failed to initialize!"); 297 } 298 } 299 } 300 301 /** 302 * checks to see if micro system is enabled and primary motor is alive 303 * 304 * @return boolean 305 */ 306 public boolean checkInitStatus() { 307 return !_isMicrosystemDisabled && _primaryMotor.isAlive(); 308 } 309 310 /** 311 * @return _primaryMotor(if system is enabled) 312 */ 313 public TalonFX getPrimaryMotor() { 314 if (_isMicrosystemDisabled) { 315 return new TalonFX(0); 316 } 317 return _primaryMotor; 318 } 319 320 /** 321 * @return position of the primary motor, 0.0 if system is disabled 322 */ 323 public double getPrimaryMotorPosition() { 324 if (_isMicrosystemDisabled) { 325 return 0.0; 326 } 327 return _primaryMotor.getPosition().getValueAsDouble(); 328 } 329 330 /** 331 * @return velocity of the primary motor, 0.0 if system is disabled 332 */ 333 public double getPrimaryMotorVelocity() { 334 if (_isMicrosystemDisabled) { 335 return 0.0; 336 } 337 return _primaryMotor.getVelocity().getValueAsDouble(); 338 } 339 340 /** 341 * exits method if micro system is disabled, if enabled sets primary motor to 342 * specified value 343 * 344 * @param power desired power 345 */ 346 public void setPrimaryPower(double power) { 347 if (_isMicrosystemDisabled) { 348 return; 349 } 350 _primaryMotor.set(power); 351 } 352 353 /** 354 * @return double(0.0 if micro system is disabled or actual power of primary 355 * motor) 356 */ 357 public double getPrimaryMotorPower() { 358 return _isMicrosystemDisabled ? 0.0 : _primaryMotor.get(); 359 } 360 361 /** 362 * configures the tuning states of the micro system based on whether it is 363 * selected for tuning, 364 * and whether it is in PID or feedforward tuning mode 365 */ 366 public void configTuningModes() { 367 _isPIDTuningMicro = TagalongConfiguration.pidTuningMicrosystems.contains(_conf.name); 368 _isFFTuningMicro = TagalongConfiguration.ffTuningMicrosystems.contains(_conf.name); 369 _isShuffleboardMicro = _isFFTuningMicro || _isPIDTuningMicro 370 || TagalongConfiguration.shuffleboardMicrosystems.contains(_conf.name); 371 } 372 373 /** 374 * Configures a user interface on the Shuffleboard for the specified micro 375 * system 376 */ 377 public void configShuffleboard() { 378 String name = _conf.name; 379 ShuffleboardTab tuningTab = Shuffleboard.getTab("Tuning tab"); 380 ShuffleboardLayout microLayout = tuningTab.getLayout(name, BuiltInLayouts.kGrid) 381 .withSize(3, 4) 382 .withPosition(2 * _tuningTabCounter++, 0); 383 if (_isShuffleboardMicro) { 384 _currentPositionEntry = 385 microLayout.add(name + " Current Position", 0.0).withPosition(0, 0).getEntry(); 386 _targetPositionEntry = 387 microLayout.add(name + " Target Position", 0.0).withPosition(0, 1).getEntry(); 388 _currentVelocityEntry = 389 microLayout.add(name + " Current Velocity", 0.0).withPosition(0, 2).getEntry(); 390 _targetVelocityEntry = 391 microLayout.add(name + " Target Velocity", 0.0).withPosition(0, 3).getEntry(); 392 } 393 394 if (_isPIDTuningMicro) { 395 _slot0PFactorEntry = microLayout.add(name + " P Fac", 0.0).withPosition(1, 0).getEntry(); 396 _slot0IFactorEntry = microLayout.add(name + " I Fac", 0.0).withPosition(1, 1).getEntry(); 397 _slot0DFactorEntry = microLayout.add(name + " D Fac", 0.0).withPosition(1, 2).getEntry(); 398 } 399 400 if (_isFFTuningMicro) { 401 _KSEntry = microLayout.add(name + " kS", 0.0).withPosition(2, 0).getEntry(); 402 _KVEntry = microLayout.add(name + " kV", 0.0).withPosition(2, 1).getEntry(); 403 _KAEntry = microLayout.add(name + " kA", 0.0).withPosition(2, 2).getEntry(); 404 } 405 } 406 407 /** 408 * returns nothing if micro system is disabled 409 */ 410 public void onDisable() { 411 if (_isMicrosystemDisabled) { 412 return; 413 } 414 415 setBrakeMode(false); 416 } 417 418 /** 419 * returns nothing if micro system is disabled else it sets 420 * followProfile to false which stops any movement 421 */ 422 public void onTeleopDisable() { 423 if (_isMicrosystemDisabled) 424 return; 425 setFollowProfile(false); 426 } 427 428 /** 429 * control whether the robot or subsystem should follow a predefined motion path 430 * 431 * @param followProfile whether or not to follow the trapezoidal profile 432 */ 433 public void setFollowProfile(boolean followProfile) { 434 if (!(_isMicrosystemDisabled)) { 435 _followProfile = followProfile; 436 } 437 } 438 439 /** 440 * alias for setFollowProfile 441 * 442 * @param holdPosition whether or not to hold position 443 */ 444 public void setHoldPosition(boolean holdPosition) { 445 setFollowProfile(holdPosition); 446 } 447 448 /** 449 * 450 * @return boolean (micro system is enabled and the primary motor has been reset 451 * and if 452 * successful, it reconfigures the devices and returns true) 453 */ 454 public boolean motorResetConfig() { 455 if (_isMicrosystemDisabled) { 456 return false; 457 } 458 if (_primaryMotor.hasResetOccurred()) { 459 configAllDevices(); 460 return true; 461 } 462 463 return false; 464 } 465 466 /** 467 * Checks if the trapezoidal profile has reached its goal 468 * 469 * @return whether or not the profile has finished 470 */ 471 public boolean isProfileFinished() { 472 return _isMicrosystemDisabled || _trapProfile.isFinished(_profileTimer.get()); 473 } 474 475 /** 476 * Sets microsystem disablement 477 * 478 * @param disable whether or not the microsystem should be disabled 479 */ 480 public void disableMicrosystem(boolean disable) { 481 _isMicrosystemDisabled = _configuredMicrosystemDisable || disable; 482 } 483 484 /** 485 * Sets the power of the primary motor to zero 486 */ 487 public void holdCurrentPosition() { 488 _primaryMotor.set(0.0); 489 } 490 491 /* -------- IO and config functions -------- */ 492 /** 493 * Updates shuffleboard 494 */ 495 public void updateShuffleboard() { 496 if (_isMicrosystemDisabled) { 497 return; 498 } 499 } 500 501 /* -------- CORE INTERFACE: THESE MUST BE ADDED TO THE SUBSYSTEM -------- */ 502 /** 503 * Periodic update function 504 */ 505 public void periodic() { 506 if (_isMicrosystemDisabled) { 507 return; 508 } 509 updateShuffleboard(); 510 } 511 512 /** 513 * Initializes simulation 514 */ 515 public void simulationInit() { 516 if (_isMicrosystemDisabled) { 517 return; 518 } 519 } 520 521 /** 522 * Periodic function during simulation 523 */ 524 public void simulationPeriodic() { 525 if (_isMicrosystemDisabled) { 526 return; 527 } 528 } 529 530 /** 531 * Resets the tolerance timer, must be ran as part of command initialization 532 */ 533 public void resetToleranceTimer() { 534 _toleranceTimer.reset(); 535 } 536 537 /** 538 * Ran each time the isFinished command is run when in tolerance duration is 539 * required. Resets or starts the timer accordingly and evaluates if required 540 * duration has been met 541 * 542 * @param inTolerance True if the microsystem is currently in tolerance 543 * @param requiredDurationS Require in tolerance duration in seconds 544 * @return True if the microsystem has been in tolerance the required duration 545 */ 546 public boolean checkToleranceTime(boolean inTolerance, double requiredDurationS) { 547 if (inTolerance) { 548 _toleranceTimer.start(); 549 return _toleranceTimer.hasElapsed(requiredDurationS); 550 } else { 551 resetToleranceTimer(); 552 return false; 553 } 554 } 555 556 /** 557 * 558 * @return sim root 559 */ 560 public MechanismRoot2d getRoot() { 561 return _root; 562 } 563}