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.phoenixpro.hardware.core; 008 009import com.ctre.phoenixpro.hardware.ParentDevice; 010import com.ctre.phoenixpro.controls.*; 011import com.ctre.phoenixpro.configs.*; 012import com.ctre.phoenixpro.StatusCode; 013import com.ctre.phoenixpro.jni.ErrorReportingJNI; 014import com.ctre.phoenixpro.jni.PlatformJNI; 015import com.ctre.phoenixpro.sim.DeviceType; 016import com.ctre.phoenixpro.sim.TalonFXSimState; 017import com.ctre.phoenixpro.StatusSignalValue; 018import com.ctre.phoenixpro.spns.*; 019import com.ctre.phoenixpro.signals.*; 020import com.ctre.phoenixpro.Utils; 021import java.util.HashMap; 022import java.util.Map; 023 024/** 025 * Class description for the Talon FX integrated motor controller that runs on 026 * associated Falcon motors. 027 */ 028public class CoreTalonFX extends ParentDevice 029{ 030 private TalonFXConfigurator _configurator; 031 032 private StatusSignalValue<Integer> _version; 033 private boolean _isVersionOk = false; 034 private double _timeToRefreshVersion = Utils.getCurrentTimeSeconds(); 035 036 private StatusSignalValue<Integer> _resetFlags; 037 private double _resetTimestamp = 0; 038 039 private double _creationTime = Utils.getCurrentTimeSeconds(); 040 041 @Override 042 protected void reportIfTooOld() 043 { 044 /* If we're not initialized, we can't even check the versions */ 045 if (_isVersionOk) { 046 return; 047 } 048 /* Check if we have our versions initialized */ 049 if (_version == null) { 050 return; 051 } 052 053 /* get fresh data if enough time has passed */ 054 final double currentTime = Utils.getCurrentTimeSeconds(); 055 if (currentTime >= _timeToRefreshVersion) { 056 /* Try to refresh again after 250ms */ 057 _timeToRefreshVersion = currentTime + 0.25; 058 /* Refresh versions, don't print out if there's an error with refreshing */ 059 _version.refresh(false); 060 061 /* process the fetched version */ 062 StatusCode code = StatusCode.OK; 063 064 /* First check if we have good versions or not */ 065 if (_version.getError().isOK()) { 066 final long fullVersion = _version.getValue(); 067 068 if (Utils.isSimulation()) { 069 /* only check major version in simulation */ 070 final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF); 071 072 /* Just check if it's good */ 073 if (majorVersion != 23) { 074 code = StatusCode.FirmwareTooOld; 075 } 076 else { 077 /* Equal major versions, this is sufficient */ 078 } 079 } 080 else { 081 /* test the parts individually */ 082 final int majorVersion = (int)((fullVersion >> 0x18) & 0xFF); 083 final int minorVersion = (int)((fullVersion >> 0x10) & 0xFF); 084 final int bugfixVersion = (int)((fullVersion >> 0x08) & 0xFF); 085 final int buildVersion = (int)((fullVersion >> 0x00) & 0xFF); 086 087 /* Just check if they're good */ 088 if (majorVersion < 23) { 089 code = StatusCode.FirmwareTooOld; 090 } 091 else if (majorVersion > 23) { 092 } 093 else if (minorVersion < 1) { 094 code = StatusCode.FirmwareTooOld; 095 } 096 else if (minorVersion > 1) { 097 } 098 else if (bugfixVersion < 0) { 099 code = StatusCode.FirmwareTooOld; 100 } 101 else if (bugfixVersion > 0) { 102 } 103 else if (buildVersion < 0) { 104 code = StatusCode.FirmwareTooOld; 105 } 106 else if (buildVersion > 0) { 107 } 108 else { 109 /* Equal versions, this is sufficient */ 110 } 111 } 112 } 113 else { 114 /* don't care why we couldn't get message, just report we didn't get it */ 115 code = StatusCode.CouldNotRetrieveProFirmware; 116 } 117 118 /* how much time has passed */ 119 final double deltaTimeSec = currentTime - _creationTime; 120 121 if (code.isOK()) { 122 /* version is retrieved and healthy */ 123 _isVersionOk = true; 124 } 125 else if (code == StatusCode.FirmwareTooOld || deltaTimeSec >= 3.0) { 126 /* report error */ 127 ErrorReportingJNI.reportStatusCode(code.value, deviceIdentifier.toString()); 128 } 129 else { 130 /* don't start reporting CouldNotRetrieveProFirmware yet, device was likely recently constructed */ 131 } 132 133 } 134 } 135 136 137 /** 138 * Proportional output of PID controller when PID'ing under a 139 * DutyCycle Request 140 * 141 * <ul> 142 * <li> <b>Minimum Value:</b> -128.0 143 * <li> <b>Maximum Value:</b> 127.9990234375 144 * <li> <b>Default Value:</b> 0 145 * <li> <b>Units:</b> fractional 146 * </ul> 147 * 148 * Default Rates: 149 * <ul> 150 * <li> <b>CAN:</b> 4.0 Hz 151 * </ul> 152 * 153 * @return PIDDutyCycle_ProportionalOutput Status Signal Value object 154 */ 155 private StatusSignalValue<Double> getPIDDutyCycle_ProportionalOutput() 156 { 157 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_ProportionalOutput_DC.value, Double.class, "PIDDutyCycle_ProportionalOutput", true); 158 } 159 160 /** 161 * Proportional output of PID controller when PID'ing under a Voltage 162 * Request 163 * 164 * <ul> 165 * <li> <b>Minimum Value:</b> -1310.72 166 * <li> <b>Maximum Value:</b> 1310.71 167 * <li> <b>Default Value:</b> 0 168 * <li> <b>Units:</b> V 169 * </ul> 170 * 171 * Default Rates: 172 * <ul> 173 * <li> <b>CAN:</b> 4.0 Hz 174 * </ul> 175 * 176 * @return PIDMotorVoltage_ProportionalOutput Status Signal Value object 177 */ 178 private StatusSignalValue<Double> getPIDMotorVoltage_ProportionalOutput() 179 { 180 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_ProportionalOutput_V.value, Double.class, "PIDMotorVoltage_ProportionalOutput", true); 181 } 182 183 /** 184 * Proportional output of PID controller when PID'ing under a 185 * TorqueCurrent Request 186 * 187 * <ul> 188 * <li> <b>Minimum Value:</b> -13107.2 189 * <li> <b>Maximum Value:</b> 13107.1 190 * <li> <b>Default Value:</b> 0 191 * <li> <b>Units:</b> A 192 * </ul> 193 * 194 * Default Rates: 195 * <ul> 196 * <li> <b>CAN:</b> 4.0 Hz 197 * </ul> 198 * 199 * @return PIDTorqueCurrent_ProportionalOutput Status Signal Value object 200 */ 201 private StatusSignalValue<Double> getPIDTorqueCurrent_ProportionalOutput() 202 { 203 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_ProportionalOutput_A.value, Double.class, "PIDTorqueCurrent_ProportionalOutput", true); 204 } 205 206 /** 207 * Integrated Accumulator of PID controller when PID'ing under a 208 * DutyCycle Request 209 * 210 * <ul> 211 * <li> <b>Minimum Value:</b> -128.0 212 * <li> <b>Maximum Value:</b> 127.9990234375 213 * <li> <b>Default Value:</b> 0 214 * <li> <b>Units:</b> fractional 215 * </ul> 216 * 217 * Default Rates: 218 * <ul> 219 * <li> <b>CAN:</b> 4.0 Hz 220 * </ul> 221 * 222 * @return PIDDutyCycle_IntegratedAccum Status Signal Value object 223 */ 224 private StatusSignalValue<Double> getPIDDutyCycle_IntegratedAccum() 225 { 226 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_IntegratedAccum_DC.value, Double.class, "PIDDutyCycle_IntegratedAccum", true); 227 } 228 229 /** 230 * Integrated Accumulator of PID controller when PID'ing under a 231 * Voltage Request 232 * 233 * <ul> 234 * <li> <b>Minimum Value:</b> -1310.72 235 * <li> <b>Maximum Value:</b> 1310.71 236 * <li> <b>Default Value:</b> 0 237 * <li> <b>Units:</b> V 238 * </ul> 239 * 240 * Default Rates: 241 * <ul> 242 * <li> <b>CAN:</b> 4.0 Hz 243 * </ul> 244 * 245 * @return PIDMotorVoltage_IntegratedAccum Status Signal Value object 246 */ 247 private StatusSignalValue<Double> getPIDMotorVoltage_IntegratedAccum() 248 { 249 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_IntegratedAccum_V.value, Double.class, "PIDMotorVoltage_IntegratedAccum", true); 250 } 251 252 /** 253 * Integrated Accumulator of PID controller when PID'ing under a 254 * TorqueCurrent Request 255 * 256 * <ul> 257 * <li> <b>Minimum Value:</b> -13107.2 258 * <li> <b>Maximum Value:</b> 13107.1 259 * <li> <b>Default Value:</b> 0 260 * <li> <b>Units:</b> A 261 * </ul> 262 * 263 * Default Rates: 264 * <ul> 265 * <li> <b>CAN:</b> 4.0 Hz 266 * </ul> 267 * 268 * @return PIDTorqueCurrent_IntegratedAccum Status Signal Value object 269 */ 270 private StatusSignalValue<Double> getPIDTorqueCurrent_IntegratedAccum() 271 { 272 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_IntegratedAccum_A.value, Double.class, "PIDTorqueCurrent_IntegratedAccum", true); 273 } 274 275 /** 276 * Feedforward passed to PID controller 277 * 278 * <ul> 279 * <li> <b>Minimum Value:</b> -2.0 280 * <li> <b>Maximum Value:</b> 1.9990234375 281 * <li> <b>Default Value:</b> 0 282 * <li> <b>Units:</b> fractional 283 * </ul> 284 * 285 * Default Rates: 286 * <ul> 287 * <li> <b>CAN:</b> 4.0 Hz 288 * </ul> 289 * 290 * @return PIDDutyCycle_FeedForward Status Signal Value object 291 */ 292 private StatusSignalValue<Double> getPIDDutyCycle_FeedForward() 293 { 294 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_FeedForward_DC.value, Double.class, "PIDDutyCycle_FeedForward", true); 295 } 296 297 /** 298 * Feedforward passed to PID controller 299 * 300 * <ul> 301 * <li> <b>Minimum Value:</b> -20.48 302 * <li> <b>Maximum Value:</b> 20.47 303 * <li> <b>Default Value:</b> 0 304 * <li> <b>Units:</b> V 305 * </ul> 306 * 307 * Default Rates: 308 * <ul> 309 * <li> <b>CAN:</b> 4.0 Hz 310 * </ul> 311 * 312 * @return PIDMotorVoltage_FeedForward Status Signal Value object 313 */ 314 private StatusSignalValue<Double> getPIDMotorVoltage_FeedForward() 315 { 316 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_FeedForward_V.value, Double.class, "PIDMotorVoltage_FeedForward", true); 317 } 318 319 /** 320 * Feedforward passed to PID controller 321 * 322 * <ul> 323 * <li> <b>Minimum Value:</b> -409.6 324 * <li> <b>Maximum Value:</b> 409.40000000000003 325 * <li> <b>Default Value:</b> 0 326 * <li> <b>Units:</b> A 327 * </ul> 328 * 329 * Default Rates: 330 * <ul> 331 * <li> <b>CAN:</b> 4.0 Hz 332 * </ul> 333 * 334 * @return PIDTorqueCurrent_FeedForward Status Signal Value object 335 */ 336 private StatusSignalValue<Double> getPIDTorqueCurrent_FeedForward() 337 { 338 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_FeedForward_A.value, Double.class, "PIDTorqueCurrent_FeedForward", true); 339 } 340 341 /** 342 * Derivative Output of PID controller when PID'ing under a DutyCycle 343 * Request 344 * 345 * <ul> 346 * <li> <b>Minimum Value:</b> -128.0 347 * <li> <b>Maximum Value:</b> 127.9990234375 348 * <li> <b>Default Value:</b> 0 349 * <li> <b>Units:</b> fractional 350 * </ul> 351 * 352 * Default Rates: 353 * <ul> 354 * <li> <b>CAN:</b> 4.0 Hz 355 * </ul> 356 * 357 * @return PIDDutyCycle_DerivativeOutput Status Signal Value object 358 */ 359 private StatusSignalValue<Double> getPIDDutyCycle_DerivativeOutput() 360 { 361 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_DerivativeOutput_DC.value, Double.class, "PIDDutyCycle_DerivativeOutput", true); 362 } 363 364 /** 365 * Derivative Output of PID controller when PID'ing under a Voltage 366 * Request 367 * 368 * <ul> 369 * <li> <b>Minimum Value:</b> -1310.72 370 * <li> <b>Maximum Value:</b> 1310.71 371 * <li> <b>Default Value:</b> 0 372 * <li> <b>Units:</b> V 373 * </ul> 374 * 375 * Default Rates: 376 * <ul> 377 * <li> <b>CAN:</b> 4.0 Hz 378 * </ul> 379 * 380 * @return PIDMotorVoltage_DerivativeOutput Status Signal Value object 381 */ 382 private StatusSignalValue<Double> getPIDMotorVoltage_DerivativeOutput() 383 { 384 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_DerivativeOutput_V.value, Double.class, "PIDMotorVoltage_DerivativeOutput", true); 385 } 386 387 /** 388 * Derivative Output of PID controller when PID'ing under a 389 * TorqueCurrent Request 390 * 391 * <ul> 392 * <li> <b>Minimum Value:</b> -13107.2 393 * <li> <b>Maximum Value:</b> 13107.1 394 * <li> <b>Default Value:</b> 0 395 * <li> <b>Units:</b> A 396 * </ul> 397 * 398 * Default Rates: 399 * <ul> 400 * <li> <b>CAN:</b> 4.0 Hz 401 * </ul> 402 * 403 * @return PIDTorqueCurrent_DerivativeOutput Status Signal Value object 404 */ 405 private StatusSignalValue<Double> getPIDTorqueCurrent_DerivativeOutput() 406 { 407 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_DerivativeOutput_A.value, Double.class, "PIDTorqueCurrent_DerivativeOutput", true); 408 } 409 410 /** 411 * Output of PID controller when PID'ing under a DutyCycle Request 412 * 413 * <ul> 414 * <li> <b>Minimum Value:</b> -128.0 415 * <li> <b>Maximum Value:</b> 127.9990234375 416 * <li> <b>Default Value:</b> 0 417 * <li> <b>Units:</b> fractional 418 * </ul> 419 * 420 * Default Rates: 421 * <ul> 422 * <li> <b>CAN:</b> 4.0 Hz 423 * </ul> 424 * 425 * @return PIDDutyCycle_Output Status Signal Value object 426 */ 427 private StatusSignalValue<Double> getPIDDutyCycle_Output() 428 { 429 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_Output_DC.value, Double.class, "PIDDutyCycle_Output", true); 430 } 431 432 /** 433 * Output of PID controller when PID'ing under a Voltage Request 434 * 435 * <ul> 436 * <li> <b>Minimum Value:</b> -1310.72 437 * <li> <b>Maximum Value:</b> 1310.71 438 * <li> <b>Default Value:</b> 0 439 * <li> <b>Units:</b> V 440 * </ul> 441 * 442 * Default Rates: 443 * <ul> 444 * <li> <b>CAN:</b> 4.0 Hz 445 * </ul> 446 * 447 * @return PIDMotorVoltage_Output Status Signal Value object 448 */ 449 private StatusSignalValue<Double> getPIDMotorVoltage_Output() 450 { 451 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_Output_V.value, Double.class, "PIDMotorVoltage_Output", true); 452 } 453 454 /** 455 * Output of PID controller when PID'ing under a TorqueCurrent Request 456 * 457 * <ul> 458 * <li> <b>Minimum Value:</b> -13107.2 459 * <li> <b>Maximum Value:</b> 13107.1 460 * <li> <b>Default Value:</b> 0 461 * <li> <b>Units:</b> A 462 * </ul> 463 * 464 * Default Rates: 465 * <ul> 466 * <li> <b>CAN:</b> 4.0 Hz 467 * </ul> 468 * 469 * @return PIDTorqueCurrent_Output Status Signal Value object 470 */ 471 private StatusSignalValue<Double> getPIDTorqueCurrent_Output() 472 { 473 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_Output_A.value, Double.class, "PIDTorqueCurrent_Output", true); 474 } 475 476 /** 477 * Input position of PID controller when PID'ing to a position 478 * 479 * <ul> 480 * <li> <b>Minimum Value:</b> -10000 481 * <li> <b>Maximum Value:</b> 10000 482 * <li> <b>Default Value:</b> 0 483 * <li> <b>Units:</b> rotations 484 * </ul> 485 * 486 * Default Rates: 487 * <ul> 488 * <li> <b>CAN:</b> 4.0 Hz 489 * </ul> 490 * 491 * @return PIDPosition_Reference Status Signal Value object 492 */ 493 private StatusSignalValue<Double> getPIDPosition_Reference() 494 { 495 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefPIDErr_PIDRef_Position.value, Double.class, "PIDPosition_Reference", true); 496 } 497 498 /** 499 * Input velocity of PID controller when PID'ing to a velocity 500 * 501 * <ul> 502 * <li> <b>Minimum Value:</b> -10000 503 * <li> <b>Maximum Value:</b> 10000 504 * <li> <b>Default Value:</b> 0 505 * <li> <b>Units:</b> rotations per second 506 * </ul> 507 * 508 * Default Rates: 509 * <ul> 510 * <li> <b>CAN:</b> 4.0 Hz 511 * </ul> 512 * 513 * @return PIDVelocity_Reference Status Signal Value object 514 */ 515 private StatusSignalValue<Double> getPIDVelocity_Reference() 516 { 517 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefPIDErr_PIDRef_Velocity.value, Double.class, "PIDVelocity_Reference", true); 518 } 519 520 /** 521 * Change in input (velocity) of PID controller when PID'ing to a 522 * position 523 * 524 * <ul> 525 * <li> <b>Minimum Value:</b> -512.0 526 * <li> <b>Maximum Value:</b> 511.984375 527 * <li> <b>Default Value:</b> 0 528 * <li> <b>Units:</b> rotations per second 529 * </ul> 530 * 531 * Default Rates: 532 * <ul> 533 * <li> <b>CAN:</b> 4.0 Hz 534 * </ul> 535 * 536 * @return PIDPosition_ReferenceSlope Status Signal Value object 537 */ 538 private StatusSignalValue<Double> getPIDPosition_ReferenceSlope() 539 { 540 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefSlopeECUTime_ReferenceSlope_Position.value, Double.class, "PIDPosition_ReferenceSlope", true); 541 } 542 543 /** 544 * Change in input (acceleration) of PID controller when PID'ing to a 545 * velocity 546 * 547 * <ul> 548 * <li> <b>Minimum Value:</b> -512.0 549 * <li> <b>Maximum Value:</b> 511.984375 550 * <li> <b>Default Value:</b> 0 551 * <li> <b>Units:</b> rotations per second² 552 * </ul> 553 * 554 * Default Rates: 555 * <ul> 556 * <li> <b>CAN:</b> 4.0 Hz 557 * </ul> 558 * 559 * @return PIDVelocity_ReferenceSlope Status Signal Value object 560 */ 561 private StatusSignalValue<Double> getPIDVelocity_ReferenceSlope() 562 { 563 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefSlopeECUTime_ReferenceSlope_Velocity.value, Double.class, "PIDVelocity_ReferenceSlope", true); 564 } 565 566 /** 567 * The difference between target position and current position 568 * 569 * <ul> 570 * <li> <b>Minimum Value:</b> -10000 571 * <li> <b>Maximum Value:</b> 10000 572 * <li> <b>Default Value:</b> 0 573 * <li> <b>Units:</b> rotations 574 * </ul> 575 * 576 * Default Rates: 577 * <ul> 578 * <li> <b>CAN:</b> 4.0 Hz 579 * </ul> 580 * 581 * @return PIDPosition_ClosedLoopError Status Signal Value object 582 */ 583 private StatusSignalValue<Double> getPIDPosition_ClosedLoopError() 584 { 585 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefPIDErr_PIDErr_Position.value, Double.class, "PIDPosition_ClosedLoopError", true); 586 } 587 588 /** 589 * The difference between target velocity and current velocity 590 * 591 * <ul> 592 * <li> <b>Minimum Value:</b> -10000 593 * <li> <b>Maximum Value:</b> 10000 594 * <li> <b>Default Value:</b> 0 595 * <li> <b>Units:</b> rotations per second 596 * </ul> 597 * 598 * Default Rates: 599 * <ul> 600 * <li> <b>CAN:</b> 4.0 Hz 601 * </ul> 602 * 603 * @return PIDVelocity_ClosedLoopError Status Signal Value object 604 */ 605 private StatusSignalValue<Double> getPIDVelocity_ClosedLoopError() 606 { 607 return super.lookupStatusSignalValue(SpnValue.PRO_PIDRefPIDErr_PIDErr_Velocity.value, Double.class, "PIDVelocity_ClosedLoopError", true); 608 } 609 610 /** 611 * Constructs a new Talon FX motor controller object. 612 * <p> 613 * Constructs the device using the default CAN bus for the system: 614 * <ul> 615 * <li>"rio" on roboRIO 616 * <li>"can0" on Linux 617 * <li>"*" on Windows 618 * </ul> 619 * 620 * @param deviceId ID of the device, as configured in Phoenix Tuner. 621 */ 622 public CoreTalonFX(int deviceId) 623 { 624 this(deviceId, ""); 625 } 626 /** 627 * Constructs a new Talon FX motor controller object. 628 * 629 * @param deviceId ID of the device, as configured in Phoenix Tuner. 630 * @param canbus Name of the CAN bus this device is on. Possible CAN bus strings are: 631 * <ul> 632 * <li>"rio" for the native roboRIO CAN bus 633 * <li>CANivore name or serial number 634 * <li>SocketCAN interface (non-FRC Linux only) 635 * <li>"*" for any CANivore seen by the program 636 * <li>empty string (default) to select the default for the system: 637 * <ul> 638 * <li>"rio" on roboRIO 639 * <li>"can0" on Linux 640 * <li>"*" on Windows 641 * </ul> 642 * </ul> 643 */ 644 public CoreTalonFX(int deviceId, String canbus) 645 { 646 super(deviceId, "talon fx", canbus); 647 _configurator = new TalonFXConfigurator(this.deviceIdentifier); 648 _version = getVersion(); 649 _resetFlags = lookupStatusSignalValue( 650 SpnValue.Startup_ResetFlags.value, 651 Integer.class, 652 "ResetFlags", 653 false); 654 PlatformJNI.JNI_SimCreate(DeviceType.PRO_TalonFXType.value, deviceId); 655 } 656 657 658 /** 659 * @return true if device has reset since the previous call of this routine. 660 */ 661 public boolean hasResetOccurred() { 662 boolean retval = false; 663 664 /* did we receive an update */ 665 _resetFlags.refresh(false); 666 final var timestamp = _resetFlags.getAllTimestamps().getSystemTimestamp(); 667 if (timestamp.isValid()) { 668 /* if the update timestamp is new, then the startup frame was sent, indicating a reset occured */ 669 if (_resetTimestamp != timestamp.getTime()) { 670 _resetTimestamp = timestamp.getTime(); 671 retval = true; 672 } 673 } 674 return retval; 675 } 676 677 /** 678 * Gets the configurator to use with this device's configs 679 * 680 * @return Configurator for this object 681 */ 682 public TalonFXConfigurator getConfigurator() 683 { 684 return this._configurator; 685 } 686 687 688 private TalonFXSimState _simState = null; 689 /** 690 * Get the simulation state for this device. 691 * <p> 692 * This function reuses an allocated simulation state 693 * object, so it is safe to call this function multiple 694 * times in a robot loop. 695 * 696 * @return Simulation state 697 */ 698 public TalonFXSimState getSimState() { 699 if (_simState == null) 700 _simState = new TalonFXSimState(this); 701 return _simState; 702 } 703 704 705 706 /** 707 * App Major Version number. 708 * 709 * <ul> 710 * <li> <b>Minimum Value:</b> 0 711 * <li> <b>Maximum Value:</b> 255 712 * <li> <b>Default Value:</b> 0 713 * <li> <b>Units:</b> 714 * </ul> 715 * 716 * Default Rates: 717 * <ul> 718 * <li> <b>CAN:</b> 4.0 Hz 719 * </ul> 720 * 721 * @return VersionMajor Status Signal Value object 722 */ 723 public StatusSignalValue<Integer> getVersionMajor() 724 { 725 return super.lookupStatusSignalValue(SpnValue.Version_Major.value, Integer.class, "VersionMajor", false); 726 } 727 728 /** 729 * App Minor Version number. 730 * 731 * <ul> 732 * <li> <b>Minimum Value:</b> 0 733 * <li> <b>Maximum Value:</b> 255 734 * <li> <b>Default Value:</b> 0 735 * <li> <b>Units:</b> 736 * </ul> 737 * 738 * Default Rates: 739 * <ul> 740 * <li> <b>CAN:</b> 4.0 Hz 741 * </ul> 742 * 743 * @return VersionMinor Status Signal Value object 744 */ 745 public StatusSignalValue<Integer> getVersionMinor() 746 { 747 return super.lookupStatusSignalValue(SpnValue.Version_Minor.value, Integer.class, "VersionMinor", false); 748 } 749 750 /** 751 * App Bugfix Version number. 752 * 753 * <ul> 754 * <li> <b>Minimum Value:</b> 0 755 * <li> <b>Maximum Value:</b> 255 756 * <li> <b>Default Value:</b> 0 757 * <li> <b>Units:</b> 758 * </ul> 759 * 760 * Default Rates: 761 * <ul> 762 * <li> <b>CAN:</b> 4.0 Hz 763 * </ul> 764 * 765 * @return VersionBugfix Status Signal Value object 766 */ 767 public StatusSignalValue<Integer> getVersionBugfix() 768 { 769 return super.lookupStatusSignalValue(SpnValue.Version_Bugfix.value, Integer.class, "VersionBugfix", false); 770 } 771 772 /** 773 * App Build Version number. 774 * 775 * <ul> 776 * <li> <b>Minimum Value:</b> 0 777 * <li> <b>Maximum Value:</b> 255 778 * <li> <b>Default Value:</b> 0 779 * <li> <b>Units:</b> 780 * </ul> 781 * 782 * Default Rates: 783 * <ul> 784 * <li> <b>CAN:</b> 4.0 Hz 785 * </ul> 786 * 787 * @return VersionBuild Status Signal Value object 788 */ 789 public StatusSignalValue<Integer> getVersionBuild() 790 { 791 return super.lookupStatusSignalValue(SpnValue.Version_Build.value, Integer.class, "VersionBuild", false); 792 } 793 794 /** 795 * Full Version. The format is a four byte value. 796 * <p> 797 * Full Version of firmware in device. The format is a four byte 798 * value. 799 * 800 * <ul> 801 * <li> <b>Minimum Value:</b> 0 802 * <li> <b>Maximum Value:</b> 4294967295 803 * <li> <b>Default Value:</b> 0 804 * <li> <b>Units:</b> 805 * </ul> 806 * 807 * Default Rates: 808 * <ul> 809 * <li> <b>CAN:</b> 4.0 Hz 810 * </ul> 811 * 812 * @return Version Status Signal Value object 813 */ 814 public StatusSignalValue<Integer> getVersion() 815 { 816 return super.lookupStatusSignalValue(SpnValue.Version_Full.value, Integer.class, "Version", false); 817 } 818 819 /** 820 * Integer representing all faults 821 * <p> 822 * This returns the fault flags reported by the device. These are 823 * device specific and are not used directly in typical applications. 824 * Use the signal specific GetFault_*() methods instead. 825 * 826 * <ul> 827 * <li> <b>Minimum Value:</b> 0 828 * <li> <b>Maximum Value:</b> 1048575 829 * <li> <b>Default Value:</b> 0 830 * <li> <b>Units:</b> 831 * </ul> 832 * 833 * Default Rates: 834 * <ul> 835 * <li> <b>CAN:</b> 4.0 Hz 836 * </ul> 837 * 838 * @return FaultField Status Signal Value object 839 */ 840 public StatusSignalValue<Integer> getFaultField() 841 { 842 return super.lookupStatusSignalValue(SpnValue.AllFaults.value, Integer.class, "FaultField", true); 843 } 844 845 /** 846 * Integer representing all sticky faults 847 * <p> 848 * This returns the persistent "sticky" fault flags reported by the 849 * device. These are device specific and are not used directly in 850 * typical applications. Use the signal specific GetStickyFault_*() 851 * methods instead. 852 * 853 * <ul> 854 * <li> <b>Minimum Value:</b> 0 855 * <li> <b>Maximum Value:</b> 1048575 856 * <li> <b>Default Value:</b> 0 857 * <li> <b>Units:</b> 858 * </ul> 859 * 860 * Default Rates: 861 * <ul> 862 * <li> <b>CAN:</b> 4.0 Hz 863 * </ul> 864 * 865 * @return StickyFaultField Status Signal Value object 866 */ 867 public StatusSignalValue<Integer> getStickyFaultField() 868 { 869 return super.lookupStatusSignalValue(SpnValue.AllStickyFaults.value, Integer.class, "StickyFaultField", true); 870 } 871 872 /** 873 * Forward Limit Pin. 874 * 875 * 876 * Default Rates: 877 * <ul> 878 * <li> <b>CAN:</b> 100.0 Hz 879 * </ul> 880 * 881 * @return ForwardLimit Status Signal Value object 882 */ 883 public StatusSignalValue<ForwardLimitValue> getForwardLimit() 884 { 885 return super.lookupStatusSignalValue(SpnValue.ForwardLimit.value, ForwardLimitValue.class, "ForwardLimit", true); 886 } 887 888 /** 889 * Reverse Limit Pin. 890 * 891 * 892 * Default Rates: 893 * <ul> 894 * <li> <b>CAN:</b> 100.0 Hz 895 * </ul> 896 * 897 * @return ReverseLimit Status Signal Value object 898 */ 899 public StatusSignalValue<ReverseLimitValue> getReverseLimit() 900 { 901 return super.lookupStatusSignalValue(SpnValue.ReverseLimit.value, ReverseLimitValue.class, "ReverseLimit", true); 902 } 903 904 /** 905 * The applied rotor polarity. This typically is determined by the 906 * Inverted config, but can be overridden if using Follower features. 907 * 908 * 909 * Default Rates: 910 * <ul> 911 * <li> <b>CAN:</b> 100.0 Hz 912 * </ul> 913 * 914 * @return AppliedRotorPolarity Status Signal Value object 915 */ 916 public StatusSignalValue<AppliedRotorPolarityValue> getAppliedRotorPolarity() 917 { 918 return super.lookupStatusSignalValue(SpnValue.PRO_MotorOutput_RotorPolarity.value, AppliedRotorPolarityValue.class, "AppliedRotorPolarity", true); 919 } 920 921 /** 922 * The applied motor duty cycle. 923 * 924 * <ul> 925 * <li> <b>Minimum Value:</b> -2.0 926 * <li> <b>Maximum Value:</b> 1.9990234375 927 * <li> <b>Default Value:</b> 0 928 * <li> <b>Units:</b> fractional 929 * </ul> 930 * 931 * Default Rates: 932 * <ul> 933 * <li> <b>CAN:</b> 100.0 Hz 934 * </ul> 935 * 936 * @return DutyCycle Status Signal Value object 937 */ 938 public StatusSignalValue<Double> getDutyCycle() 939 { 940 return super.lookupStatusSignalValue(SpnValue.PRO_MotorOutput_DutyCycle.value, Double.class, "DutyCycle", true); 941 } 942 943 /** 944 * Current corresponding to the torque output by the motor. Similar to 945 * StatorCurrent. Users will likely prefer this current to calculate 946 * the applied torque to the rotor. 947 * <p> 948 * Stator current where positive current means torque is applied in 949 * the forward direction as determined by the Inverted setting 950 * 951 * <ul> 952 * <li> <b>Minimum Value:</b> -327.68 953 * <li> <b>Maximum Value:</b> 327.67 954 * <li> <b>Default Value:</b> 0 955 * <li> <b>Units:</b> A 956 * </ul> 957 * 958 * Default Rates: 959 * <ul> 960 * <li> <b>CAN:</b> 100.0 Hz 961 * </ul> 962 * 963 * @return TorqueCurrent Status Signal Value object 964 */ 965 public StatusSignalValue<Double> getTorqueCurrent() 966 { 967 return super.lookupStatusSignalValue(SpnValue.PRO_MotorOutput_TorqueCurrent.value, Double.class, "TorqueCurrent", true); 968 } 969 970 /** 971 * Current corresponding to the stator windings. Similar to 972 * TorqueCurrent. Users will likely prefer TorqueCurrent over 973 * StatorCurrent. 974 * <p> 975 * Stator current where Positive current indicates motoring regardless 976 * of direction. Negative current indicates regenerative braking 977 * regardless of direction. 978 * 979 * <ul> 980 * <li> <b>Minimum Value:</b> -327.68 981 * <li> <b>Maximum Value:</b> 327.67 982 * <li> <b>Default Value:</b> 0 983 * <li> <b>Units:</b> A 984 * </ul> 985 * 986 * Default Rates: 987 * <ul> 988 * <li> <b>CAN 2.0:</b> 5.0 Hz 989 * <li> <b>CAN FD:</b> 100.0 Hz 990 * </ul> 991 * 992 * @return StatorCurrent Status Signal Value object 993 */ 994 public StatusSignalValue<Double> getStatorCurrent() 995 { 996 return super.lookupStatusSignalValue(SpnValue.PRO_SupplyAndTemp_StatorCurrent.value, Double.class, "StatorCurrent", true); 997 } 998 999 /** 1000 * Measured supply side current 1001 * 1002 * <ul> 1003 * <li> <b>Minimum Value:</b> -327.68 1004 * <li> <b>Maximum Value:</b> 327.67 1005 * <li> <b>Default Value:</b> 0 1006 * <li> <b>Units:</b> A 1007 * </ul> 1008 * 1009 * Default Rates: 1010 * <ul> 1011 * <li> <b>CAN 2.0:</b> 5.0 Hz 1012 * <li> <b>CAN FD:</b> 100.0 Hz 1013 * </ul> 1014 * 1015 * @return SupplyCurrent Status Signal Value object 1016 */ 1017 public StatusSignalValue<Double> getSupplyCurrent() 1018 { 1019 return super.lookupStatusSignalValue(SpnValue.PRO_SupplyAndTemp_SupplyCurrent.value, Double.class, "SupplyCurrent", true); 1020 } 1021 1022 /** 1023 * Measured supply voltage to the TalonFX. 1024 * 1025 * <ul> 1026 * <li> <b>Minimum Value:</b> 4.0 1027 * <li> <b>Maximum Value:</b> 16.75 1028 * <li> <b>Default Value:</b> 4 1029 * <li> <b>Units:</b> V 1030 * </ul> 1031 * 1032 * Default Rates: 1033 * <ul> 1034 * <li> <b>CAN 2.0:</b> 5.0 Hz 1035 * <li> <b>CAN FD:</b> 100.0 Hz 1036 * </ul> 1037 * 1038 * @return SupplyVoltage Status Signal Value object 1039 */ 1040 public StatusSignalValue<Double> getSupplyVoltage() 1041 { 1042 return super.lookupStatusSignalValue(SpnValue.PRO_SupplyAndTemp_SupplyVoltage.value, Double.class, "SupplyVoltage", true); 1043 } 1044 1045 /** 1046 * Temperature of device 1047 * <p> 1048 * This is the temperature that the device measures itself to be at. 1049 * Similar to Processor Temperature. 1050 * 1051 * <ul> 1052 * <li> <b>Minimum Value:</b> 0.0 1053 * <li> <b>Maximum Value:</b> 255.0 1054 * <li> <b>Default Value:</b> 0 1055 * <li> <b>Units:</b> ℃ 1056 * </ul> 1057 * 1058 * Default Rates: 1059 * <ul> 1060 * <li> <b>CAN 2.0:</b> 5.0 Hz 1061 * <li> <b>CAN FD:</b> 100.0 Hz 1062 * </ul> 1063 * 1064 * @return DeviceTemp Status Signal Value object 1065 */ 1066 public StatusSignalValue<Double> getDeviceTemp() 1067 { 1068 return super.lookupStatusSignalValue(SpnValue.PRO_SupplyAndTemp_DeviceTemp.value, Double.class, "DeviceTemp", true); 1069 } 1070 1071 /** 1072 * Temperature of the processor 1073 * <p> 1074 * This is the temperature that the processor measures itself to be 1075 * at. Similar to Device Temperature. 1076 * 1077 * <ul> 1078 * <li> <b>Minimum Value:</b> 0.0 1079 * <li> <b>Maximum Value:</b> 255.0 1080 * <li> <b>Default Value:</b> 0 1081 * <li> <b>Units:</b> ℃ 1082 * </ul> 1083 * 1084 * Default Rates: 1085 * <ul> 1086 * <li> <b>CAN 2.0:</b> 5.0 Hz 1087 * <li> <b>CAN FD:</b> 100.0 Hz 1088 * </ul> 1089 * 1090 * @return ProcessorTemp Status Signal Value object 1091 */ 1092 public StatusSignalValue<Double> getProcessorTemp() 1093 { 1094 return super.lookupStatusSignalValue(SpnValue.PRO_SupplyAndTemp_ProcessorTemp.value, Double.class, "ProcessorTemp", true); 1095 } 1096 1097 /** 1098 * Velocity of motor rotor. 1099 * 1100 * <ul> 1101 * <li> <b>Minimum Value:</b> -512.0 1102 * <li> <b>Maximum Value:</b> 511.998046875 1103 * <li> <b>Default Value:</b> 0 1104 * <li> <b>Units:</b> rotations per second 1105 * </ul> 1106 * 1107 * Default Rates: 1108 * <ul> 1109 * <li> <b>CAN 2.0:</b> 5.0 Hz 1110 * <li> <b>CAN FD:</b> 100.0 Hz 1111 * </ul> 1112 * 1113 * @return RotorVelocity Status Signal Value object 1114 */ 1115 public StatusSignalValue<Double> getRotorVelocity() 1116 { 1117 return super.lookupStatusSignalValue(SpnValue.PRO_RotorPosAndVel_Velocity.value, Double.class, "RotorVelocity", true); 1118 } 1119 1120 /** 1121 * Position of motor rotor. 1122 * 1123 * <ul> 1124 * <li> <b>Minimum Value:</b> -16384.0 1125 * <li> <b>Maximum Value:</b> 16383.999755859375 1126 * <li> <b>Default Value:</b> 0 1127 * <li> <b>Units:</b> rotations 1128 * </ul> 1129 * 1130 * Default Rates: 1131 * <ul> 1132 * <li> <b>CAN 2.0:</b> 5.0 Hz 1133 * <li> <b>CAN FD:</b> 100.0 Hz 1134 * </ul> 1135 * 1136 * @return RotorPosition Status Signal Value object 1137 */ 1138 public StatusSignalValue<Double> getRotorPosition() 1139 { 1140 return super.lookupStatusSignalValue(SpnValue.PRO_RotorPosAndVel_Position.value, Double.class, "RotorPosition", true); 1141 } 1142 1143 /** 1144 * Velocity of device. 1145 * 1146 * <ul> 1147 * <li> <b>Minimum Value:</b> -512.0 1148 * <li> <b>Maximum Value:</b> 511.998046875 1149 * <li> <b>Default Value:</b> 0 1150 * <li> <b>Units:</b> rotations per second 1151 * </ul> 1152 * 1153 * Default Rates: 1154 * <ul> 1155 * <li> <b>CAN 2.0:</b> 50.0 Hz 1156 * <li> <b>CAN FD:</b> 100.0 Hz 1157 * </ul> 1158 * 1159 * @return Velocity Status Signal Value object 1160 */ 1161 public StatusSignalValue<Double> getVelocity() 1162 { 1163 return super.lookupStatusSignalValue(SpnValue.PRO_PosAndVel_Velocity.value, Double.class, "Velocity", true); 1164 } 1165 1166 /** 1167 * Position of device. 1168 * 1169 * <ul> 1170 * <li> <b>Minimum Value:</b> -16384.0 1171 * <li> <b>Maximum Value:</b> 16383.999755859375 1172 * <li> <b>Default Value:</b> 0 1173 * <li> <b>Units:</b> rotations 1174 * </ul> 1175 * 1176 * Default Rates: 1177 * <ul> 1178 * <li> <b>CAN 2.0:</b> 50.0 Hz 1179 * <li> <b>CAN FD:</b> 100.0 Hz 1180 * </ul> 1181 * 1182 * @return Position Status Signal Value object 1183 */ 1184 public StatusSignalValue<Double> getPosition() 1185 { 1186 return super.lookupStatusSignalValue(SpnValue.PRO_PosAndVel_Position.value, Double.class, "Position", true); 1187 } 1188 1189 /** 1190 * The active control mode of the motor controller 1191 * 1192 * 1193 * Default Rates: 1194 * <ul> 1195 * <li> <b>CAN 2.0:</b> 5.0 Hz 1196 * <li> <b>CAN FD:</b> 100.0 Hz 1197 * </ul> 1198 * 1199 * @return ControlMode Status Signal Value object 1200 */ 1201 public StatusSignalValue<ControlModeValue> getControlMode() 1202 { 1203 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, ControlModeValue.class, "ControlMode", true); 1204 } 1205 1206 /** 1207 * Check if Motion Magic® is running. This is equivalent to checking 1208 * that the reported control mode is a Motion Magic® based mode. 1209 * 1210 * 1211 * Default Rates: 1212 * <ul> 1213 * <li> <b>CAN 2.0:</b> 5.0 Hz 1214 * <li> <b>CAN FD:</b> 100.0 Hz 1215 * </ul> 1216 * 1217 * @return MotionMagicIsRunning Status Signal Value object 1218 */ 1219 public StatusSignalValue<MotionMagicIsRunningValue> getMotionMagicIsRunning() 1220 { 1221 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_IsMotionMagicRunning.value, MotionMagicIsRunningValue.class, "MotionMagicIsRunning", true); 1222 } 1223 1224 /** 1225 * Indicates if device is actuator enabled. 1226 * 1227 * 1228 * Default Rates: 1229 * <ul> 1230 * <li> <b>CAN 2.0:</b> 5.0 Hz 1231 * <li> <b>CAN FD:</b> 100.0 Hz 1232 * </ul> 1233 * 1234 * @return DeviceEnable Status Signal Value object 1235 */ 1236 public StatusSignalValue<DeviceEnableValue> getDeviceEnable() 1237 { 1238 return super.lookupStatusSignalValue(SpnValue.PRO_PIDStateEnables_DeviceEnable.value, DeviceEnableValue.class, "DeviceEnable", true); 1239 } 1240 1241 /** 1242 * Closed loop slot in use 1243 * <p> 1244 * This is the slot that the closed loop PID is using. 1245 * 1246 * <ul> 1247 * <li> <b>Minimum Value:</b> 0 1248 * <li> <b>Maximum Value:</b> 2 1249 * <li> <b>Default Value:</b> 0 1250 * <li> <b>Units:</b> 1251 * </ul> 1252 * 1253 * Default Rates: 1254 * <ul> 1255 * <li> <b>CAN 2.0:</b> 5.0 Hz 1256 * <li> <b>CAN FD:</b> 100.0 Hz 1257 * </ul> 1258 * 1259 * @return ClosedLoopSlot Status Signal Value object 1260 */ 1261 public StatusSignalValue<Integer> getClosedLoopSlot() 1262 { 1263 return super.lookupStatusSignalValue(SpnValue.PRO_PIDOutput_Slot.value, Integer.class, "ClosedLoopSlot", true); 1264 } 1265 1266 /** 1267 * The applied output of the bridge. 1268 * 1269 * 1270 * Default Rates: 1271 * <ul> 1272 * <li> <b>CAN:</b> 100.0 Hz 1273 * </ul> 1274 * 1275 * @return BridgeOuput Status Signal Value object 1276 */ 1277 public StatusSignalValue<BridgeOuputValue> getBridgeOuput() 1278 { 1279 return super.lookupStatusSignalValue(SpnValue.PRO_MotorOutput_BridgeType_Public.value, BridgeOuputValue.class, "BridgeOuput", true); 1280 } 1281 1282 /** 1283 * Hardware fault occurred 1284 * 1285 * <ul> 1286 * <li> <b>Default Value:</b> False 1287 * </ul> 1288 * 1289 * Default Rates: 1290 * <ul> 1291 * <li> <b>CAN:</b> 4.0 Hz 1292 * </ul> 1293 * 1294 * @return Fault_Hardware Status Signal Value object 1295 */ 1296 public StatusSignalValue<Boolean> getFault_Hardware() 1297 { 1298 return super.lookupStatusSignalValue(SpnValue.Fault_Hardware.value, Boolean.class, "Fault_Hardware", true); 1299 } 1300 1301 /** 1302 * Hardware fault occurred 1303 * 1304 * <ul> 1305 * <li> <b>Default Value:</b> False 1306 * </ul> 1307 * 1308 * Default Rates: 1309 * <ul> 1310 * <li> <b>CAN:</b> 4.0 Hz 1311 * </ul> 1312 * 1313 * @return StickyFault_Hardware Status Signal Value object 1314 */ 1315 public StatusSignalValue<Boolean> getStickyFault_Hardware() 1316 { 1317 return super.lookupStatusSignalValue(SpnValue.StickyFault_Hardware.value, Boolean.class, "StickyFault_Hardware", true); 1318 } 1319 1320 /** 1321 * Processor temperature exceeded limit 1322 * 1323 * <ul> 1324 * <li> <b>Default Value:</b> False 1325 * </ul> 1326 * 1327 * Default Rates: 1328 * <ul> 1329 * <li> <b>CAN:</b> 4.0 Hz 1330 * </ul> 1331 * 1332 * @return Fault_ProcTemp Status Signal Value object 1333 */ 1334 public StatusSignalValue<Boolean> getFault_ProcTemp() 1335 { 1336 return super.lookupStatusSignalValue(SpnValue.Fault_ProcTemp.value, Boolean.class, "Fault_ProcTemp", true); 1337 } 1338 1339 /** 1340 * Processor temperature exceeded limit 1341 * 1342 * <ul> 1343 * <li> <b>Default Value:</b> False 1344 * </ul> 1345 * 1346 * Default Rates: 1347 * <ul> 1348 * <li> <b>CAN:</b> 4.0 Hz 1349 * </ul> 1350 * 1351 * @return StickyFault_ProcTemp Status Signal Value object 1352 */ 1353 public StatusSignalValue<Boolean> getStickyFault_ProcTemp() 1354 { 1355 return super.lookupStatusSignalValue(SpnValue.StickyFault_ProcTemp.value, Boolean.class, "StickyFault_ProcTemp", true); 1356 } 1357 1358 /** 1359 * Device temperature exceeded limit 1360 * 1361 * <ul> 1362 * <li> <b>Default Value:</b> False 1363 * </ul> 1364 * 1365 * Default Rates: 1366 * <ul> 1367 * <li> <b>CAN:</b> 4.0 Hz 1368 * </ul> 1369 * 1370 * @return Fault_DeviceTemp Status Signal Value object 1371 */ 1372 public StatusSignalValue<Boolean> getFault_DeviceTemp() 1373 { 1374 return super.lookupStatusSignalValue(SpnValue.Fault_DeviceTemp.value, Boolean.class, "Fault_DeviceTemp", true); 1375 } 1376 1377 /** 1378 * Device temperature exceeded limit 1379 * 1380 * <ul> 1381 * <li> <b>Default Value:</b> False 1382 * </ul> 1383 * 1384 * Default Rates: 1385 * <ul> 1386 * <li> <b>CAN:</b> 4.0 Hz 1387 * </ul> 1388 * 1389 * @return StickyFault_DeviceTemp Status Signal Value object 1390 */ 1391 public StatusSignalValue<Boolean> getStickyFault_DeviceTemp() 1392 { 1393 return super.lookupStatusSignalValue(SpnValue.StickyFault_DeviceTemp.value, Boolean.class, "StickyFault_DeviceTemp", true); 1394 } 1395 1396 /** 1397 * Device supply voltage dropped to near brownout levels 1398 * 1399 * <ul> 1400 * <li> <b>Default Value:</b> False 1401 * </ul> 1402 * 1403 * Default Rates: 1404 * <ul> 1405 * <li> <b>CAN:</b> 4.0 Hz 1406 * </ul> 1407 * 1408 * @return Fault_Undervoltage Status Signal Value object 1409 */ 1410 public StatusSignalValue<Boolean> getFault_Undervoltage() 1411 { 1412 return super.lookupStatusSignalValue(SpnValue.Fault_Undervoltage.value, Boolean.class, "Fault_Undervoltage", true); 1413 } 1414 1415 /** 1416 * Device supply voltage dropped to near brownout levels 1417 * 1418 * <ul> 1419 * <li> <b>Default Value:</b> False 1420 * </ul> 1421 * 1422 * Default Rates: 1423 * <ul> 1424 * <li> <b>CAN:</b> 4.0 Hz 1425 * </ul> 1426 * 1427 * @return StickyFault_Undervoltage Status Signal Value object 1428 */ 1429 public StatusSignalValue<Boolean> getStickyFault_Undervoltage() 1430 { 1431 return super.lookupStatusSignalValue(SpnValue.StickyFault_Undervoltage.value, Boolean.class, "StickyFault_Undervoltage", true); 1432 } 1433 1434 /** 1435 * Device boot while detecting the enable signal 1436 * 1437 * <ul> 1438 * <li> <b>Default Value:</b> False 1439 * </ul> 1440 * 1441 * Default Rates: 1442 * <ul> 1443 * <li> <b>CAN:</b> 4.0 Hz 1444 * </ul> 1445 * 1446 * @return Fault_BootDuringEnable Status Signal Value object 1447 */ 1448 public StatusSignalValue<Boolean> getFault_BootDuringEnable() 1449 { 1450 return super.lookupStatusSignalValue(SpnValue.Fault_BootDuringEnable.value, Boolean.class, "Fault_BootDuringEnable", true); 1451 } 1452 1453 /** 1454 * Device boot while detecting the enable signal 1455 * 1456 * <ul> 1457 * <li> <b>Default Value:</b> False 1458 * </ul> 1459 * 1460 * Default Rates: 1461 * <ul> 1462 * <li> <b>CAN:</b> 4.0 Hz 1463 * </ul> 1464 * 1465 * @return StickyFault_BootDuringEnable Status Signal Value object 1466 */ 1467 public StatusSignalValue<Boolean> getStickyFault_BootDuringEnable() 1468 { 1469 return super.lookupStatusSignalValue(SpnValue.StickyFault_BootDuringEnable.value, Boolean.class, "StickyFault_BootDuringEnable", true); 1470 } 1471 1472 /** 1473 * Supply Voltage has exceeded the maximum voltage rating of device. 1474 * 1475 * <ul> 1476 * <li> <b>Default Value:</b> False 1477 * </ul> 1478 * 1479 * Default Rates: 1480 * <ul> 1481 * <li> <b>CAN:</b> 4.0 Hz 1482 * </ul> 1483 * 1484 * @return Fault_OverSupplyV Status Signal Value object 1485 */ 1486 public StatusSignalValue<Boolean> getFault_OverSupplyV() 1487 { 1488 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_OverSupplyV.value, Boolean.class, "Fault_OverSupplyV", true); 1489 } 1490 1491 /** 1492 * Supply Voltage has exceeded the maximum voltage rating of device. 1493 * 1494 * <ul> 1495 * <li> <b>Default Value:</b> False 1496 * </ul> 1497 * 1498 * Default Rates: 1499 * <ul> 1500 * <li> <b>CAN:</b> 4.0 Hz 1501 * </ul> 1502 * 1503 * @return StickyFault_OverSupplyV Status Signal Value object 1504 */ 1505 public StatusSignalValue<Boolean> getStickyFault_OverSupplyV() 1506 { 1507 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_OverSupplyV.value, Boolean.class, "StickyFault_OverSupplyV", true); 1508 } 1509 1510 /** 1511 * Supply Voltage is unstable. Ensure you are using a battery and 1512 * current limited power supply. 1513 * 1514 * <ul> 1515 * <li> <b>Default Value:</b> False 1516 * </ul> 1517 * 1518 * Default Rates: 1519 * <ul> 1520 * <li> <b>CAN:</b> 4.0 Hz 1521 * </ul> 1522 * 1523 * @return Fault_UnstableSupplyV Status Signal Value object 1524 */ 1525 public StatusSignalValue<Boolean> getFault_UnstableSupplyV() 1526 { 1527 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_UnstableSupplyV.value, Boolean.class, "Fault_UnstableSupplyV", true); 1528 } 1529 1530 /** 1531 * Supply Voltage is unstable. Ensure you are using a battery and 1532 * current limited power supply. 1533 * 1534 * <ul> 1535 * <li> <b>Default Value:</b> False 1536 * </ul> 1537 * 1538 * Default Rates: 1539 * <ul> 1540 * <li> <b>CAN:</b> 4.0 Hz 1541 * </ul> 1542 * 1543 * @return StickyFault_UnstableSupplyV Status Signal Value object 1544 */ 1545 public StatusSignalValue<Boolean> getStickyFault_UnstableSupplyV() 1546 { 1547 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_UnstableSupplyV.value, Boolean.class, "StickyFault_UnstableSupplyV", true); 1548 } 1549 1550 /** 1551 * Reverse limit switch has been asserted. Output is set to neutral. 1552 * 1553 * <ul> 1554 * <li> <b>Default Value:</b> False 1555 * </ul> 1556 * 1557 * Default Rates: 1558 * <ul> 1559 * <li> <b>CAN:</b> 4.0 Hz 1560 * </ul> 1561 * 1562 * @return Fault_ReverseHardLimit Status Signal Value object 1563 */ 1564 public StatusSignalValue<Boolean> getFault_ReverseHardLimit() 1565 { 1566 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_ReverseHardLimit.value, Boolean.class, "Fault_ReverseHardLimit", true); 1567 } 1568 1569 /** 1570 * Reverse limit switch has been asserted. Output is set to neutral. 1571 * 1572 * <ul> 1573 * <li> <b>Default Value:</b> False 1574 * </ul> 1575 * 1576 * Default Rates: 1577 * <ul> 1578 * <li> <b>CAN:</b> 4.0 Hz 1579 * </ul> 1580 * 1581 * @return StickyFault_ReverseHardLimit Status Signal Value object 1582 */ 1583 public StatusSignalValue<Boolean> getStickyFault_ReverseHardLimit() 1584 { 1585 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_ReverseHardLimit.value, Boolean.class, "StickyFault_ReverseHardLimit", true); 1586 } 1587 1588 /** 1589 * Forward limit switch has been asserted. Output is set to neutral. 1590 * 1591 * <ul> 1592 * <li> <b>Default Value:</b> False 1593 * </ul> 1594 * 1595 * Default Rates: 1596 * <ul> 1597 * <li> <b>CAN:</b> 4.0 Hz 1598 * </ul> 1599 * 1600 * @return Fault_ForwardHardLimit Status Signal Value object 1601 */ 1602 public StatusSignalValue<Boolean> getFault_ForwardHardLimit() 1603 { 1604 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_ForwardHardLimit.value, Boolean.class, "Fault_ForwardHardLimit", true); 1605 } 1606 1607 /** 1608 * Forward limit switch has been asserted. Output is set to neutral. 1609 * 1610 * <ul> 1611 * <li> <b>Default Value:</b> False 1612 * </ul> 1613 * 1614 * Default Rates: 1615 * <ul> 1616 * <li> <b>CAN:</b> 4.0 Hz 1617 * </ul> 1618 * 1619 * @return StickyFault_ForwardHardLimit Status Signal Value object 1620 */ 1621 public StatusSignalValue<Boolean> getStickyFault_ForwardHardLimit() 1622 { 1623 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_ForwardHardLimit.value, Boolean.class, "StickyFault_ForwardHardLimit", true); 1624 } 1625 1626 /** 1627 * Reverse soft limit has been asserted. Output is set to neutral. 1628 * 1629 * <ul> 1630 * <li> <b>Default Value:</b> False 1631 * </ul> 1632 * 1633 * Default Rates: 1634 * <ul> 1635 * <li> <b>CAN:</b> 4.0 Hz 1636 * </ul> 1637 * 1638 * @return Fault_ReverseSoftLimit Status Signal Value object 1639 */ 1640 public StatusSignalValue<Boolean> getFault_ReverseSoftLimit() 1641 { 1642 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_ReverseSoftLimit.value, Boolean.class, "Fault_ReverseSoftLimit", true); 1643 } 1644 1645 /** 1646 * Reverse soft limit has been asserted. Output is set to neutral. 1647 * 1648 * <ul> 1649 * <li> <b>Default Value:</b> False 1650 * </ul> 1651 * 1652 * Default Rates: 1653 * <ul> 1654 * <li> <b>CAN:</b> 4.0 Hz 1655 * </ul> 1656 * 1657 * @return StickyFault_ReverseSoftLimit Status Signal Value object 1658 */ 1659 public StatusSignalValue<Boolean> getStickyFault_ReverseSoftLimit() 1660 { 1661 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_ReverseSoftLimit.value, Boolean.class, "StickyFault_ReverseSoftLimit", true); 1662 } 1663 1664 /** 1665 * Forward soft limit has been asserted. Output is set to neutral. 1666 * 1667 * <ul> 1668 * <li> <b>Default Value:</b> False 1669 * </ul> 1670 * 1671 * Default Rates: 1672 * <ul> 1673 * <li> <b>CAN:</b> 4.0 Hz 1674 * </ul> 1675 * 1676 * @return Fault_ForwardSoftLimit Status Signal Value object 1677 */ 1678 public StatusSignalValue<Boolean> getFault_ForwardSoftLimit() 1679 { 1680 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_ForwardSoftLimit.value, Boolean.class, "Fault_ForwardSoftLimit", true); 1681 } 1682 1683 /** 1684 * Forward soft limit has been asserted. Output is set to neutral. 1685 * 1686 * <ul> 1687 * <li> <b>Default Value:</b> False 1688 * </ul> 1689 * 1690 * Default Rates: 1691 * <ul> 1692 * <li> <b>CAN:</b> 4.0 Hz 1693 * </ul> 1694 * 1695 * @return StickyFault_ForwardSoftLimit Status Signal Value object 1696 */ 1697 public StatusSignalValue<Boolean> getStickyFault_ForwardSoftLimit() 1698 { 1699 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_ForwardSoftLimit.value, Boolean.class, "StickyFault_ForwardSoftLimit", true); 1700 } 1701 1702 /** 1703 * The remote sensor is not present on CAN Bus. 1704 * 1705 * <ul> 1706 * <li> <b>Default Value:</b> False 1707 * </ul> 1708 * 1709 * Default Rates: 1710 * <ul> 1711 * <li> <b>CAN:</b> 4.0 Hz 1712 * </ul> 1713 * 1714 * @return Fault_MissingRemoteSensor Status Signal Value object 1715 */ 1716 public StatusSignalValue<Boolean> getFault_MissingRemoteSensor() 1717 { 1718 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_MissingRemoteSensor.value, Boolean.class, "Fault_MissingRemoteSensor", true); 1719 } 1720 1721 /** 1722 * The remote sensor is not present on CAN Bus. 1723 * 1724 * <ul> 1725 * <li> <b>Default Value:</b> False 1726 * </ul> 1727 * 1728 * Default Rates: 1729 * <ul> 1730 * <li> <b>CAN:</b> 4.0 Hz 1731 * </ul> 1732 * 1733 * @return StickyFault_MissingRemoteSensor Status Signal Value object 1734 */ 1735 public StatusSignalValue<Boolean> getStickyFault_MissingRemoteSensor() 1736 { 1737 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_MissingRemoteSensor.value, Boolean.class, "StickyFault_MissingRemoteSensor", true); 1738 } 1739 1740 /** 1741 * The remote sensor used for fusion has fallen out of sync to the 1742 * local sensor. A re-synchronization has occurred, which may cause a 1743 * discontinuity. This typically happens if there is significant slop 1744 * in the mechanism, or if the RotorToSensorRatio configuration 1745 * parameter is incorrect. 1746 * 1747 * <ul> 1748 * <li> <b>Default Value:</b> False 1749 * </ul> 1750 * 1751 * Default Rates: 1752 * <ul> 1753 * <li> <b>CAN:</b> 4.0 Hz 1754 * </ul> 1755 * 1756 * @return Fault_FusedSensorOutOfSync Status Signal Value object 1757 */ 1758 public StatusSignalValue<Boolean> getFault_FusedSensorOutOfSync() 1759 { 1760 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_FusedSensorOutOfSync.value, Boolean.class, "Fault_FusedSensorOutOfSync", true); 1761 } 1762 1763 /** 1764 * The remote sensor used for fusion has fallen out of sync to the 1765 * local sensor. A re-synchronization has occurred, which may cause a 1766 * discontinuity. This typically happens if there is significant slop 1767 * in the mechanism, or if the RotorToSensorRatio configuration 1768 * parameter is incorrect. 1769 * 1770 * <ul> 1771 * <li> <b>Default Value:</b> False 1772 * </ul> 1773 * 1774 * Default Rates: 1775 * <ul> 1776 * <li> <b>CAN:</b> 4.0 Hz 1777 * </ul> 1778 * 1779 * @return StickyFault_FusedSensorOutOfSync Status Signal Value object 1780 */ 1781 public StatusSignalValue<Boolean> getStickyFault_FusedSensorOutOfSync() 1782 { 1783 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_FusedSensorOutOfSync.value, Boolean.class, "StickyFault_FusedSensorOutOfSync", true); 1784 } 1785 1786 /** 1787 * Stator current limit occured. 1788 * 1789 * <ul> 1790 * <li> <b>Default Value:</b> False 1791 * </ul> 1792 * 1793 * Default Rates: 1794 * <ul> 1795 * <li> <b>CAN:</b> 4.0 Hz 1796 * </ul> 1797 * 1798 * @return Fault_StatorCurrLimit Status Signal Value object 1799 */ 1800 public StatusSignalValue<Boolean> getFault_StatorCurrLimit() 1801 { 1802 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_StatorCurrLimit.value, Boolean.class, "Fault_StatorCurrLimit", true); 1803 } 1804 1805 /** 1806 * Stator current limit occured. 1807 * 1808 * <ul> 1809 * <li> <b>Default Value:</b> False 1810 * </ul> 1811 * 1812 * Default Rates: 1813 * <ul> 1814 * <li> <b>CAN:</b> 4.0 Hz 1815 * </ul> 1816 * 1817 * @return StickyFault_StatorCurrLimit Status Signal Value object 1818 */ 1819 public StatusSignalValue<Boolean> getStickyFault_StatorCurrLimit() 1820 { 1821 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_StatorCurrLimit.value, Boolean.class, "StickyFault_StatorCurrLimit", true); 1822 } 1823 1824 /** 1825 * Supply current limit occured. 1826 * 1827 * <ul> 1828 * <li> <b>Default Value:</b> False 1829 * </ul> 1830 * 1831 * Default Rates: 1832 * <ul> 1833 * <li> <b>CAN:</b> 4.0 Hz 1834 * </ul> 1835 * 1836 * @return Fault_SupplyCurrLimit Status Signal Value object 1837 */ 1838 public StatusSignalValue<Boolean> getFault_SupplyCurrLimit() 1839 { 1840 return super.lookupStatusSignalValue(SpnValue.Fault_TALONFX_SupplyCurrLimit.value, Boolean.class, "Fault_SupplyCurrLimit", true); 1841 } 1842 1843 /** 1844 * Supply current limit occured. 1845 * 1846 * <ul> 1847 * <li> <b>Default Value:</b> False 1848 * </ul> 1849 * 1850 * Default Rates: 1851 * <ul> 1852 * <li> <b>CAN:</b> 4.0 Hz 1853 * </ul> 1854 * 1855 * @return StickyFault_SupplyCurrLimit Status Signal Value object 1856 */ 1857 public StatusSignalValue<Boolean> getStickyFault_SupplyCurrLimit() 1858 { 1859 return super.lookupStatusSignalValue(SpnValue.StickyFault_TALONFX_SupplyCurrLimit.value, Boolean.class, "StickyFault_SupplyCurrLimit", true); 1860 } 1861 1862 /** 1863 * Closed loop proportional component 1864 * <p> 1865 * The portion of the closed loop output that is the proportional to 1866 * the error. Alternatively, the p-Contribution of the closed loop 1867 * output. 1868 * 1869 * Default Rates: 1870 * <ul> 1871 * <li> <b>CAN 2.0:</b> 5.0 Hz 1872 * <li> <b>CAN FD:</b> 100.0 Hz 1873 * </ul> 1874 * 1875 * @return ClosedLoopProportionalOutput Status Signal Value object 1876 */ 1877 public StatusSignalValue<Double> getClosedLoopProportionalOutput() 1878 { 1879 MapGenerator<Double> mapFiller = ()->{ 1880 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 1881 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDDutyCycle_ProportionalOutput()); 1882 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDDutyCycle_ProportionalOutput()); 1883 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDDutyCycle_ProportionalOutput()); 1884 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDDutyCycle_ProportionalOutput()); 1885 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDDutyCycle_ProportionalOutput()); 1886 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDDutyCycle_ProportionalOutput()); 1887 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDMotorVoltage_ProportionalOutput()); 1888 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDMotorVoltage_ProportionalOutput()); 1889 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDMotorVoltage_ProportionalOutput()); 1890 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDMotorVoltage_ProportionalOutput()); 1891 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDMotorVoltage_ProportionalOutput()); 1892 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDMotorVoltage_ProportionalOutput()); 1893 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDTorqueCurrent_ProportionalOutput()); 1894 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDTorqueCurrent_ProportionalOutput()); 1895 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDTorqueCurrent_ProportionalOutput()); 1896 return toAdd; 1897 }; 1898 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 1, mapFiller, "ClosedLoopProportionalOutput", true); 1899 } 1900 1901 /** 1902 * Closed loop integrated component 1903 * <p> 1904 * The portion of the closed loop output that is proportional to the 1905 * integrated error. Alternatively, the i-Contribution of the closed 1906 * loop output. 1907 * 1908 * Default Rates: 1909 * <ul> 1910 * <li> <b>CAN 2.0:</b> 5.0 Hz 1911 * <li> <b>CAN FD:</b> 100.0 Hz 1912 * </ul> 1913 * 1914 * @return ClosedLoopIntegratedOutput Status Signal Value object 1915 */ 1916 public StatusSignalValue<Double> getClosedLoopIntegratedOutput() 1917 { 1918 MapGenerator<Double> mapFiller = ()->{ 1919 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 1920 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDDutyCycle_IntegratedAccum()); 1921 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDDutyCycle_IntegratedAccum()); 1922 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDDutyCycle_IntegratedAccum()); 1923 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDDutyCycle_IntegratedAccum()); 1924 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDDutyCycle_IntegratedAccum()); 1925 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDDutyCycle_IntegratedAccum()); 1926 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDMotorVoltage_IntegratedAccum()); 1927 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDMotorVoltage_IntegratedAccum()); 1928 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDMotorVoltage_IntegratedAccum()); 1929 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDMotorVoltage_IntegratedAccum()); 1930 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDMotorVoltage_IntegratedAccum()); 1931 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDMotorVoltage_IntegratedAccum()); 1932 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDTorqueCurrent_IntegratedAccum()); 1933 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDTorqueCurrent_IntegratedAccum()); 1934 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDTorqueCurrent_IntegratedAccum()); 1935 return toAdd; 1936 }; 1937 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 2, mapFiller, "ClosedLoopIntegratedOutput", true); 1938 } 1939 1940 /** 1941 * Feed Forward passed by the user 1942 * <p> 1943 * This is the general feed forward that the user provides for the 1944 * closed loop. 1945 * 1946 * Default Rates: 1947 * <ul> 1948 * <li> <b>CAN 2.0:</b> 5.0 Hz 1949 * <li> <b>CAN FD:</b> 100.0 Hz 1950 * </ul> 1951 * 1952 * @return ClosedLoopFeedForward Status Signal Value object 1953 */ 1954 public StatusSignalValue<Double> getClosedLoopFeedForward() 1955 { 1956 MapGenerator<Double> mapFiller = ()->{ 1957 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 1958 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDDutyCycle_FeedForward()); 1959 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDDutyCycle_FeedForward()); 1960 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDDutyCycle_FeedForward()); 1961 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDDutyCycle_FeedForward()); 1962 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDDutyCycle_FeedForward()); 1963 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDDutyCycle_FeedForward()); 1964 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDMotorVoltage_FeedForward()); 1965 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDMotorVoltage_FeedForward()); 1966 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDMotorVoltage_FeedForward()); 1967 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDMotorVoltage_FeedForward()); 1968 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDMotorVoltage_FeedForward()); 1969 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDMotorVoltage_FeedForward()); 1970 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDTorqueCurrent_FeedForward()); 1971 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDTorqueCurrent_FeedForward()); 1972 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDTorqueCurrent_FeedForward()); 1973 return toAdd; 1974 }; 1975 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 3, mapFiller, "ClosedLoopFeedForward", true); 1976 } 1977 1978 /** 1979 * Closed loop derivative component 1980 * <p> 1981 * The portion of the closed loop output that is the proportional to 1982 * the deriviative the error. Alternatively, the d-Contribution of the 1983 * closed loop output. 1984 * 1985 * Default Rates: 1986 * <ul> 1987 * <li> <b>CAN 2.0:</b> 5.0 Hz 1988 * <li> <b>CAN FD:</b> 100.0 Hz 1989 * </ul> 1990 * 1991 * @return ClosedLoopDerivativeOutput Status Signal Value object 1992 */ 1993 public StatusSignalValue<Double> getClosedLoopDerivativeOutput() 1994 { 1995 MapGenerator<Double> mapFiller = ()->{ 1996 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 1997 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDDutyCycle_DerivativeOutput()); 1998 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDDutyCycle_DerivativeOutput()); 1999 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDDutyCycle_DerivativeOutput()); 2000 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDDutyCycle_DerivativeOutput()); 2001 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDDutyCycle_DerivativeOutput()); 2002 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDDutyCycle_DerivativeOutput()); 2003 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDMotorVoltage_DerivativeOutput()); 2004 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDMotorVoltage_DerivativeOutput()); 2005 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDMotorVoltage_DerivativeOutput()); 2006 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDMotorVoltage_DerivativeOutput()); 2007 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDMotorVoltage_DerivativeOutput()); 2008 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDMotorVoltage_DerivativeOutput()); 2009 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDTorqueCurrent_DerivativeOutput()); 2010 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDTorqueCurrent_DerivativeOutput()); 2011 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDTorqueCurrent_DerivativeOutput()); 2012 return toAdd; 2013 }; 2014 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 4, mapFiller, "ClosedLoopDerivativeOutput", true); 2015 } 2016 2017 /** 2018 * Closed loop total output 2019 * <p> 2020 * The total output of the closed loop output. 2021 * 2022 * Default Rates: 2023 * <ul> 2024 * <li> <b>CAN 2.0:</b> 5.0 Hz 2025 * <li> <b>CAN FD:</b> 100.0 Hz 2026 * </ul> 2027 * 2028 * @return ClosedLoopOutput Status Signal Value object 2029 */ 2030 public StatusSignalValue<Double> getClosedLoopOutput() 2031 { 2032 MapGenerator<Double> mapFiller = ()->{ 2033 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 2034 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDDutyCycle_Output()); 2035 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDDutyCycle_Output()); 2036 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDDutyCycle_Output()); 2037 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDDutyCycle_Output()); 2038 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDDutyCycle_Output()); 2039 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDDutyCycle_Output()); 2040 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDMotorVoltage_Output()); 2041 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDMotorVoltage_Output()); 2042 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDMotorVoltage_Output()); 2043 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDMotorVoltage_Output()); 2044 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDMotorVoltage_Output()); 2045 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDMotorVoltage_Output()); 2046 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDTorqueCurrent_Output()); 2047 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDTorqueCurrent_Output()); 2048 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDTorqueCurrent_Output()); 2049 return toAdd; 2050 }; 2051 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 5, mapFiller, "ClosedLoopOutput", true); 2052 } 2053 2054 /** 2055 * Value that the closed loop is targeting 2056 * <p> 2057 * This is the value that the closed loop PID controller targets. 2058 * 2059 * Default Rates: 2060 * <ul> 2061 * <li> <b>CAN 2.0:</b> 5.0 Hz 2062 * <li> <b>CAN FD:</b> 100.0 Hz 2063 * </ul> 2064 * 2065 * @return ClosedLoopReference Status Signal Value object 2066 */ 2067 public StatusSignalValue<Double> getClosedLoopReference() 2068 { 2069 MapGenerator<Double> mapFiller = ()->{ 2070 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 2071 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDPosition_Reference()); 2072 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDPosition_Reference()); 2073 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDPosition_Reference()); 2074 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDPosition_Reference()); 2075 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDPosition_Reference()); 2076 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDPosition_Reference()); 2077 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDPosition_Reference()); 2078 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDPosition_Reference()); 2079 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDPosition_Reference()); 2080 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDPosition_Reference()); 2081 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDVelocity_Reference()); 2082 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDVelocity_Reference()); 2083 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDVelocity_Reference()); 2084 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDVelocity_Reference()); 2085 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDVelocity_Reference()); 2086 return toAdd; 2087 }; 2088 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 6, mapFiller, "ClosedLoopReference", true); 2089 } 2090 2091 /** 2092 * Derivative of the target that the closed loop is targeting 2093 * <p> 2094 * This is the change in the closed loop reference. This may be used 2095 * in the feed-forward calculation, the derivative-error, or in 2096 * application of the signage for kS. Typically, this represents the 2097 * target velocity during Motion Magic®. 2098 * 2099 * Default Rates: 2100 * <ul> 2101 * <li> <b>CAN 2.0:</b> 5.0 Hz 2102 * <li> <b>CAN FD:</b> 100.0 Hz 2103 * </ul> 2104 * 2105 * @return ClosedLoopReferenceSlope Status Signal Value object 2106 */ 2107 public StatusSignalValue<Double> getClosedLoopReferenceSlope() 2108 { 2109 MapGenerator<Double> mapFiller = ()->{ 2110 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 2111 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDPosition_ReferenceSlope()); 2112 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDPosition_ReferenceSlope()); 2113 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDPosition_ReferenceSlope()); 2114 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDPosition_ReferenceSlope()); 2115 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDPosition_ReferenceSlope()); 2116 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDPosition_ReferenceSlope()); 2117 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDPosition_ReferenceSlope()); 2118 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDPosition_ReferenceSlope()); 2119 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDPosition_ReferenceSlope()); 2120 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDPosition_ReferenceSlope()); 2121 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDVelocity_ReferenceSlope()); 2122 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDVelocity_ReferenceSlope()); 2123 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDVelocity_ReferenceSlope()); 2124 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDVelocity_ReferenceSlope()); 2125 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDVelocity_ReferenceSlope()); 2126 return toAdd; 2127 }; 2128 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 7, mapFiller, "ClosedLoopReferenceSlope", true); 2129 } 2130 2131 /** 2132 * The difference between target reference and current measurement 2133 * <p> 2134 * This is the value that is treated as the error in the PID loop. 2135 * 2136 * Default Rates: 2137 * <ul> 2138 * <li> <b>CAN 2.0:</b> 5.0 Hz 2139 * <li> <b>CAN FD:</b> 100.0 Hz 2140 * </ul> 2141 * 2142 * @return ClosedLoopError Status Signal Value object 2143 */ 2144 public StatusSignalValue<Double> getClosedLoopError() 2145 { 2146 MapGenerator<Double> mapFiller = ()->{ 2147 Map<Integer, StatusSignalValue<Double>> toAdd = new HashMap<Integer, StatusSignalValue<Double>>(); 2148 toAdd.put(ControlModeValue.PositionDutyCycle.value, getPIDPosition_ClosedLoopError()); 2149 toAdd.put(ControlModeValue.PositionDutyCycleFOC.value, getPIDPosition_ClosedLoopError()); 2150 toAdd.put(ControlModeValue.MotionMagicDutyCycle.value, getPIDPosition_ClosedLoopError()); 2151 toAdd.put(ControlModeValue.MotionMagicDutyCycleFOC.value, getPIDPosition_ClosedLoopError()); 2152 toAdd.put(ControlModeValue.PositionVoltage.value, getPIDPosition_ClosedLoopError()); 2153 toAdd.put(ControlModeValue.PositionVoltageFOC.value, getPIDPosition_ClosedLoopError()); 2154 toAdd.put(ControlModeValue.MotionMagicVoltage.value, getPIDPosition_ClosedLoopError()); 2155 toAdd.put(ControlModeValue.MotionMagicVoltageFOC.value, getPIDPosition_ClosedLoopError()); 2156 toAdd.put(ControlModeValue.PositionTorqueCurrentFOC.value, getPIDPosition_ClosedLoopError()); 2157 toAdd.put(ControlModeValue.MotionMagicTorqueCurrentFOC.value, getPIDPosition_ClosedLoopError()); 2158 toAdd.put(ControlModeValue.VelocityDutyCycle.value, getPIDVelocity_ClosedLoopError()); 2159 toAdd.put(ControlModeValue.VelocityDutyCycleFOC.value, getPIDVelocity_ClosedLoopError()); 2160 toAdd.put(ControlModeValue.VelocityVoltage.value, getPIDVelocity_ClosedLoopError()); 2161 toAdd.put(ControlModeValue.VelocityVoltageFOC.value, getPIDVelocity_ClosedLoopError()); 2162 toAdd.put(ControlModeValue.VelocityTorqueCurrentFOC.value, getPIDVelocity_ClosedLoopError()); 2163 return toAdd; 2164 }; 2165 return super.lookupStatusSignalValue(SpnValue.TalonFX_ControlMode.value, Double.class, 8, mapFiller, "ClosedLoopError", true); 2166 } 2167 2168 2169 /** 2170 * Request a specified motor duty cycle. 2171 * <p> 2172 * This control mode will output a proportion of the supplied voltage 2173 * which is supplied by the user. 2174 * 2175 * <ul> 2176 * <li> <b>DutyCycleOut Parameters:</b> 2177 * <ul> 2178 * <li> <b>Output:</b> Proportion of supply voltage to apply in fractional units 2179 * between -1 and +1 2180 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2181 * peak power by ~15%. Set to false to use trapezoidal 2182 * commutation. FOC improves motor performance by 2183 * leveraging torque (current) control. However, this may 2184 * be inconvenient for applications that require 2185 * specifying duty cycle or voltage. CTR-Electronics has 2186 * developed a hybrid method that combines the 2187 * performances gains of FOC while still allowing 2188 * applications to provide duty cycle or voltage demand. 2189 * This not to be confused with simple sinusoidal control 2190 * or phase voltage control which lacks the performance 2191 * gains. 2192 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2193 * when output is zero (or within deadband). 2194 * Set to false to use the NeutralMode 2195 * configuration setting (default). This 2196 * flag exists to provide the fundamental 2197 * behavior of this control when output is 2198 * zero, which is to provide 0V to the 2199 * motor. 2200 * </ul> 2201 * </ul> 2202 * 2203 * @param request Control object to request of the device 2204 * @return Code response of the request 2205 */ 2206 public StatusCode setControl(DutyCycleOut request) 2207 { 2208 return setControlPrivate(request); 2209 } 2210 2211 /** 2212 * Request a specified motor current (field oriented control). 2213 * <p> 2214 * This control request will drive the motor to the requested motor 2215 * (stator) current value. This leverages field oriented control 2216 * (FOC), which means greater peak power than what is documented. 2217 * This scales to torque based on Motor's kT constant. 2218 * 2219 * <ul> 2220 * <li> <b>TorqueCurrentFOC Parameters:</b> 2221 * <ul> 2222 * <li> <b>Output:</b> Amount of motor current in Amperes 2223 * <li> <b>MaxAbsDutyCycle:</b> The maximum absolute motor output that can be 2224 * applied, which effectively limits the velocity. 2225 * For example, 0.50 means no more than 50% output 2226 * in either direction. This is useful for 2227 * preventing the motor from spinning to its 2228 * terminal velocity when there is no external 2229 * torque applied unto the rotor. Note this is 2230 * absolute maximum, so the value should be between 2231 * zero and one. 2232 * <li> <b>Deadband:</b> Deadband in Amperes. If torque request is within 2233 * deadband, the bridge output is neutral. If deadband is 2234 * set to zero then there is effectively no deadband. Note 2235 * if deadband is zero, a free spinning motor will spin for 2236 * quite a while as the firmware attempts to hold the 2237 * motor's bemf. If user expects motor to cease spinning 2238 * quickly with a demand of zero, we recommend a deadband 2239 * of one Ampere. This value will be converted to an 2240 * integral value of amps. 2241 * <li> <b>OverrideCoastDurNeutral:</b> Set to true to coast the rotor when 2242 * output is zero (or within deadband). Set 2243 * to false to use the NeutralMode 2244 * configuration setting (default). This 2245 * flag exists to provide the fundamental 2246 * behavior of this control when output is 2247 * zero, which is to provide 0A (zero 2248 * torque). 2249 * </ul> 2250 * </ul> 2251 * 2252 * @param request Control object to request of the device 2253 * @return Code response of the request 2254 */ 2255 public StatusCode setControl(TorqueCurrentFOC request) 2256 { 2257 return setControlPrivate(request); 2258 } 2259 2260 /** 2261 * Request a specified voltage. 2262 * <p> 2263 * This control mode will attempt to apply the specified voltage to 2264 * the motor. If the supply voltage is below the requested voltage, 2265 * the motor controller will output the supply voltage. 2266 * 2267 * <ul> 2268 * <li> <b>VoltageOut Parameters:</b> 2269 * <ul> 2270 * <li> <b>Output:</b> Voltage to attempt to drive at 2271 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2272 * peak power by ~15%. Set to false to use trapezoidal 2273 * commutation. FOC improves motor performance by 2274 * leveraging torque (current) control. However, this may 2275 * be inconvenient for applications that require 2276 * specifying duty cycle or voltage. CTR-Electronics has 2277 * developed a hybrid method that combines the 2278 * performances gains of FOC while still allowing 2279 * applications to provide duty cycle or voltage demand. 2280 * This not to be confused with simple sinusoidal control 2281 * or phase voltage control which lacks the performance 2282 * gains. 2283 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2284 * when output is zero (or within deadband). 2285 * Set to false to use the NeutralMode 2286 * configuration setting (default). This 2287 * flag exists to provide the fundamental 2288 * behavior of this control when output is 2289 * zero, which is to provide 0V to the 2290 * motor. 2291 * </ul> 2292 * </ul> 2293 * 2294 * @param request Control object to request of the device 2295 * @return Code response of the request 2296 */ 2297 public StatusCode setControl(VoltageOut request) 2298 { 2299 return setControlPrivate(request); 2300 } 2301 2302 /** 2303 * Request PID to target position with duty cycle feedforward. 2304 * <p> 2305 * This control mode will set the motor's position setpoint to the 2306 * position specified by the user. In addition, it will apply an 2307 * additional duty cycle as an arbitrary feedforward value. 2308 * 2309 * <ul> 2310 * <li> <b>PositionDutyCycle Parameters:</b> 2311 * <ul> 2312 * <li> <b>Position:</b> Position to drive toward in rotations. 2313 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2314 * peak power by ~15%. Set to false to use trapezoidal 2315 * commutation. FOC improves motor performance by 2316 * leveraging torque (current) control. However, this may 2317 * be inconvenient for applications that require 2318 * specifying duty cycle or voltage. CTR-Electronics has 2319 * developed a hybrid method that combines the 2320 * performances gains of FOC while still allowing 2321 * applications to provide duty cycle or voltage demand. 2322 * This not to be confused with simple sinusoidal control 2323 * or phase voltage control which lacks the performance 2324 * gains. 2325 * <li> <b>FeedForward:</b> Feedforward to apply in fractional units between -1 2326 * and +1. 2327 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2328 * the configuration api to set the gain values for the 2329 * selected slot before enabling this feature. Slot must be 2330 * within [0,2]. 2331 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2332 * when output is zero (or within deadband). 2333 * Set to false to use the NeutralMode 2334 * configuration setting (default). This 2335 * flag exists to provide the fundamental 2336 * behavior of this control when output is 2337 * zero, which is to provide 0V to the 2338 * motor. 2339 * </ul> 2340 * </ul> 2341 * 2342 * @param request Control object to request of the device 2343 * @return Code response of the request 2344 */ 2345 public StatusCode setControl(PositionDutyCycle request) 2346 { 2347 return setControlPrivate(request); 2348 } 2349 2350 /** 2351 * Request PID to target position with voltage feedforward 2352 * <p> 2353 * This control mode will set the motor's position setpoint to the 2354 * position specified by the user. In addition, it will apply an 2355 * additional voltage as an arbitrary feedforward value. 2356 * 2357 * <ul> 2358 * <li> <b>PositionVoltage Parameters:</b> 2359 * <ul> 2360 * <li> <b>Position:</b> Position to drive toward in rotations. 2361 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2362 * peak power by ~15%. Set to false to use trapezoidal 2363 * commutation. FOC improves motor performance by 2364 * leveraging torque (current) control. However, this may 2365 * be inconvenient for applications that require 2366 * specifying duty cycle or voltage. CTR-Electronics has 2367 * developed a hybrid method that combines the 2368 * performances gains of FOC while still allowing 2369 * applications to provide duty cycle or voltage demand. 2370 * This not to be confused with simple sinusoidal control 2371 * or phase voltage control which lacks the performance 2372 * gains. 2373 * <li> <b>FeedForward:</b> Feedforward to apply in volts 2374 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2375 * the configuration api to set the gain values for the 2376 * selected slot before enabling this feature. Slot must be 2377 * within [0,2]. 2378 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2379 * when output is zero (or within deadband). 2380 * Set to false to use the NeutralMode 2381 * configuration setting (default). This 2382 * flag exists to provide the fundamental 2383 * behavior of this control when output is 2384 * zero, which is to provide 0V to the 2385 * motor. 2386 * </ul> 2387 * </ul> 2388 * 2389 * @param request Control object to request of the device 2390 * @return Code response of the request 2391 */ 2392 public StatusCode setControl(PositionVoltage request) 2393 { 2394 return setControlPrivate(request); 2395 } 2396 2397 /** 2398 * Request PID to target position with torque current feedforward. 2399 * <p> 2400 * This control mode will set the motor's position setpoint to the 2401 * position specified by the user. In addition, it will apply an 2402 * additional torque current as an arbitrary feedforward value. 2403 * 2404 * <ul> 2405 * <li> <b>PositionTorqueCurrentFOC Parameters:</b> 2406 * <ul> 2407 * <li> <b>Position:</b> Position to drive toward in rotations. 2408 * <li> <b>FeedForward:</b> Feedforward to apply in torque current in Amperes. 2409 * User can use motor's kT to scale Newton-meter to 2410 * Amperes. 2411 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2412 * the configuration api to set the gain values for the 2413 * selected slot before enabling this feature. Slot must be 2414 * within [0,2]. 2415 * <li> <b>OverrideCoastDurNeutral:</b> Set to true to coast the rotor when 2416 * output is zero (or within deadband). Set 2417 * to false to use the NeutralMode 2418 * configuration setting (default). This 2419 * flag exists to provide the fundamental 2420 * behavior of this control when output is 2421 * zero, which is to provide 0A (zero 2422 * torque). 2423 * </ul> 2424 * </ul> 2425 * 2426 * @param request Control object to request of the device 2427 * @return Code response of the request 2428 */ 2429 public StatusCode setControl(PositionTorqueCurrentFOC request) 2430 { 2431 return setControlPrivate(request); 2432 } 2433 2434 /** 2435 * Request PID to target velocity with duty cycle feedforward. 2436 * <p> 2437 * This control mode will set the motor's velocity setpoint to the 2438 * velocity specified by the user. In addition, it will apply an 2439 * additional voltage as an arbitrary feedforward value. 2440 * 2441 * <ul> 2442 * <li> <b>VelocityDutyCycle Parameters:</b> 2443 * <ul> 2444 * <li> <b>Velocity:</b> Velocity to drive toward in rotations per second. 2445 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2446 * peak power by ~15%. Set to false to use trapezoidal 2447 * commutation. FOC improves motor performance by 2448 * leveraging torque (current) control. However, this may 2449 * be inconvenient for applications that require 2450 * specifying duty cycle or voltage. CTR-Electronics has 2451 * developed a hybrid method that combines the 2452 * performances gains of FOC while still allowing 2453 * applications to provide duty cycle or voltage demand. 2454 * This not to be confused with simple sinusoidal control 2455 * or phase voltage control which lacks the performance 2456 * gains. 2457 * <li> <b>FeedForward:</b> Feedforward to apply in fractional units between -1 2458 * and +1. 2459 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2460 * the configuration api to set the gain values for the 2461 * selected slot before enabling this feature. Slot must be 2462 * within [0,2]. 2463 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2464 * when output is zero (or within deadband). 2465 * Set to false to use the NeutralMode 2466 * configuration setting (default). This 2467 * flag exists to provide the fundamental 2468 * behavior of this control when output is 2469 * zero, which is to provide 0V to the 2470 * motor. 2471 * </ul> 2472 * </ul> 2473 * 2474 * @param request Control object to request of the device 2475 * @return Code response of the request 2476 */ 2477 public StatusCode setControl(VelocityDutyCycle request) 2478 { 2479 return setControlPrivate(request); 2480 } 2481 2482 /** 2483 * Request PID to target velocity with voltage feedforward. 2484 * <p> 2485 * This control mode will set the motor's velocity setpoint to the 2486 * velocity specified by the user. In addition, it will apply an 2487 * additional voltage as an arbitrary feedforward value. 2488 * 2489 * <ul> 2490 * <li> <b>VelocityVoltage Parameters:</b> 2491 * <ul> 2492 * <li> <b>Velocity:</b> Velocity to drive toward in rotations per second. 2493 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2494 * peak power by ~15%. Set to false to use trapezoidal 2495 * commutation. FOC improves motor performance by 2496 * leveraging torque (current) control. However, this may 2497 * be inconvenient for applications that require 2498 * specifying duty cycle or voltage. CTR-Electronics has 2499 * developed a hybrid method that combines the 2500 * performances gains of FOC while still allowing 2501 * applications to provide duty cycle or voltage demand. 2502 * This not to be confused with simple sinusoidal control 2503 * or phase voltage control which lacks the performance 2504 * gains. 2505 * <li> <b>FeedForward:</b> Feedforward to apply in volts 2506 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2507 * the configuration api to set the gain values for the 2508 * selected slot before enabling this feature. Slot must be 2509 * within [0,2]. 2510 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2511 * when output is zero (or within deadband). 2512 * Set to false to use the NeutralMode 2513 * configuration setting (default). This 2514 * flag exists to provide the fundamental 2515 * behavior of this control when output is 2516 * zero, which is to provide 0V to the 2517 * motor. 2518 * </ul> 2519 * </ul> 2520 * 2521 * @param request Control object to request of the device 2522 * @return Code response of the request 2523 */ 2524 public StatusCode setControl(VelocityVoltage request) 2525 { 2526 return setControlPrivate(request); 2527 } 2528 2529 /** 2530 * Request PID to target velocity with torque current feedforward. 2531 * <p> 2532 * This control mode will set the motor's velocity setpoint to the 2533 * velocity specified by the user. In addition, it will apply an 2534 * additional torque current as an arbitrary feedforward value. 2535 * 2536 * <ul> 2537 * <li> <b>VelocityTorqueCurrentFOC Parameters:</b> 2538 * <ul> 2539 * <li> <b>Velocity:</b> Velocity to drive toward in rotations per second. 2540 * <li> <b>FeedForward:</b> Feedforward to apply in torque current in Amperes. 2541 * User can use motor's kT to scale Newton-meter to 2542 * Amperes. 2543 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2544 * the configuration api to set the gain values for the 2545 * selected slot before enabling this feature. Slot must be 2546 * within [0,2]. 2547 * <li> <b>OverrideCoastDurNeutral:</b> Set to true to coast the rotor when 2548 * output is zero (or within deadband). Set 2549 * to false to use the NeutralMode 2550 * configuration setting (default). This 2551 * flag exists to provide the fundamental 2552 * behavior of this control when output is 2553 * zero, which is to provide 0A (zero 2554 * torque). 2555 * </ul> 2556 * </ul> 2557 * 2558 * @param request Control object to request of the device 2559 * @return Code response of the request 2560 */ 2561 public StatusCode setControl(VelocityTorqueCurrentFOC request) 2562 { 2563 return setControlPrivate(request); 2564 } 2565 2566 /** 2567 * Requests Motion Magic® to target a final position using a motion 2568 * profile. Users can optionally provide a duty cycle feedforward. 2569 * <p> 2570 * Motion Magic® produces a motion profile in real-time while 2571 * attempting to honor the Cruise Velocity, Acceleration, and Jerk 2572 * value specified via the Motion Magic® configuration values. Target 2573 * position can be changed on-the-fly and Motion Magic® will do its 2574 * best to adjust the profile. This control mode is duty cycled 2575 * based, so relevant closed-loop gains will use fractional duty cycle 2576 * for the numerator: +1.0 represents full forward output. 2577 * 2578 * <ul> 2579 * <li> <b>MotionMagicDutyCycle Parameters:</b> 2580 * <ul> 2581 * <li> <b>Position:</b> Position to drive toward in rotations. 2582 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2583 * peak power by ~15%. Set to false to use trapezoidal 2584 * commutation. FOC improves motor performance by 2585 * leveraging torque (current) control. However, this may 2586 * be inconvenient for applications that require 2587 * specifying duty cycle or voltage. CTR-Electronics has 2588 * developed a hybrid method that combines the 2589 * performances gains of FOC while still allowing 2590 * applications to provide duty cycle or voltage demand. 2591 * This not to be confused with simple sinusoidal control 2592 * or phase voltage control which lacks the performance 2593 * gains. 2594 * <li> <b>FeedForward:</b> Feedforward to apply in fractional units between -1 2595 * and +1. 2596 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2597 * the configuration api to set the gain values for the 2598 * selected slot before enabling this feature. Slot must be 2599 * within [0,2]. 2600 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2601 * when output is zero (or within deadband). 2602 * Set to false to use the NeutralMode 2603 * configuration setting (default). This 2604 * flag exists to provide the fundamental 2605 * behavior of this control when output is 2606 * zero, which is to provide 0V to the 2607 * motor. 2608 * </ul> 2609 * </ul> 2610 * 2611 * @param request Control object to request of the device 2612 * @return Code response of the request 2613 */ 2614 public StatusCode setControl(MotionMagicDutyCycle request) 2615 { 2616 return setControlPrivate(request); 2617 } 2618 2619 /** 2620 * Requests Motion Magic® to target a final position using a motion 2621 * profile. Users can optionally provide a voltage feedforward. 2622 * <p> 2623 * Motion Magic® produces a motion profile in real-time while 2624 * attempting to honor the Cruise Velocity, Acceleration, and Jerk 2625 * value specified via the Motion Magic® configuration values. Target 2626 * position can be changed on-the-fly and Motion Magic® will do its 2627 * best to adjust the profile. This control mode is voltage-based, so 2628 * relevant closed-loop gains will use Volts for the numerator. 2629 * 2630 * <ul> 2631 * <li> <b>MotionMagicVoltage Parameters:</b> 2632 * <ul> 2633 * <li> <b>Position:</b> Position to drive toward in rotations. 2634 * <li> <b>EnableFOC:</b> Set to true to use FOC commutation, which increases 2635 * peak power by ~15%. Set to false to use trapezoidal 2636 * commutation. FOC improves motor performance by 2637 * leveraging torque (current) control. However, this may 2638 * be inconvenient for applications that require 2639 * specifying duty cycle or voltage. CTR-Electronics has 2640 * developed a hybrid method that combines the 2641 * performances gains of FOC while still allowing 2642 * applications to provide duty cycle or voltage demand. 2643 * This not to be confused with simple sinusoidal control 2644 * or phase voltage control which lacks the performance 2645 * gains. 2646 * <li> <b>FeedForward:</b> Feedforward to apply in volts 2647 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2648 * the configuration api to set the gain values for the 2649 * selected slot before enabling this feature. Slot must be 2650 * within [0,2]. 2651 * <li> <b>OverrideBrakeDurNeutral:</b> Set to true to static-brake the rotor 2652 * when output is zero (or within deadband). 2653 * Set to false to use the NeutralMode 2654 * configuration setting (default). This 2655 * flag exists to provide the fundamental 2656 * behavior of this control when output is 2657 * zero, which is to provide 0V to the 2658 * motor. 2659 * </ul> 2660 * </ul> 2661 * 2662 * @param request Control object to request of the device 2663 * @return Code response of the request 2664 */ 2665 public StatusCode setControl(MotionMagicVoltage request) 2666 { 2667 return setControlPrivate(request); 2668 } 2669 2670 /** 2671 * Requests Motion Magic® to target a final position using a motion 2672 * profile. Users can optionally provide a torque current 2673 * feedforward. 2674 * <p> 2675 * Motion Magic® produces a motion profile in real-time while 2676 * attempting to honor the Cruise Velocity, Acceleration, and Jerk 2677 * value specified via the Motion Magic® configuration values. Target 2678 * position can be changed on-the-fly and Motion Magic® will do its 2679 * best to adjust the profile. This control mode is based on torque 2680 * current, so relevant closed-loop gains will use Amperes for the 2681 * numerator. 2682 * 2683 * <ul> 2684 * <li> <b>MotionMagicTorqueCurrentFOC Parameters:</b> 2685 * <ul> 2686 * <li> <b>Position:</b> Position to drive toward in rotations. 2687 * <li> <b>FeedForward:</b> Feedforward to apply in torque current in Amperes. 2688 * User can use motor's kT to scale Newton-meter to 2689 * Amperes. 2690 * <li> <b>Slot:</b> Select which gains are applied by selecting the slot. Use 2691 * the configuration api to set the gain values for the 2692 * selected slot before enabling this feature. Slot must be 2693 * within [0,2]. 2694 * <li> <b>OverrideCoastDurNeutral:</b> Set to true to coast the rotor when 2695 * output is zero (or within deadband). Set 2696 * to false to use the NeutralMode 2697 * configuration setting (default). This 2698 * flag exists to provide the fundamental 2699 * behavior of this control when output is 2700 * zero, which is to provide 0A (zero 2701 * torque). 2702 * </ul> 2703 * </ul> 2704 * 2705 * @param request Control object to request of the device 2706 * @return Code response of the request 2707 */ 2708 public StatusCode setControl(MotionMagicTorqueCurrentFOC request) 2709 { 2710 return setControlPrivate(request); 2711 } 2712 2713 /** 2714 * Follow the motor output of another Talon. 2715 * <p> 2716 * If Talon is in torque control, the torque is copied - which will 2717 * increase the total torque applied. If Talon is in percent supply 2718 * output control, the duty cycle is matched. Motor direction either 2719 * matches master's configured direction or opposes it based on 2720 * OpposeMasterDirection. 2721 * 2722 * <ul> 2723 * <li> <b>Follower Parameters:</b> 2724 * <ul> 2725 * <li> <b>MasterID:</b> Device ID of the master to follow. 2726 * <li> <b>OpposeMasterDirection:</b> Set to false for motor invert to match the 2727 * master's configured Invert - which is 2728 * typical when master and follower are 2729 * mechanically linked and spin in the same 2730 * direction. Set to true for motor invert to 2731 * oppose the master's configured Invert - 2732 * this is typical where the the master and 2733 * follower mechanically spin in opposite 2734 * directions. 2735 * </ul> 2736 * </ul> 2737 * 2738 * @param request Control object to request of the device 2739 * @return Code response of the request 2740 */ 2741 public StatusCode setControl(Follower request) 2742 { 2743 return setControlPrivate(request); 2744 } 2745 2746 /** 2747 * Follow the motor output of another Talon while ignoring the 2748 * master's invert setting. 2749 * <p> 2750 * If Talon is in torque control, the torque is copied - which will 2751 * increase the total torque applied. If Talon is in percent supply 2752 * output control, the duty cycle is matched. Motor direction is 2753 * strictly determined by the configured invert and not the master. 2754 * If you want motor direction to match or oppose the master, use 2755 * FollowerRequest instead. 2756 * 2757 * <ul> 2758 * <li> <b>StrictFollower Parameters:</b> 2759 * <ul> 2760 * <li> <b>MasterID:</b> Device ID of the master to follow. 2761 * </ul> 2762 * </ul> 2763 * 2764 * @param request Control object to request of the device 2765 * @return Code response of the request 2766 */ 2767 public StatusCode setControl(StrictFollower request) 2768 { 2769 return setControlPrivate(request); 2770 } 2771 2772 /** 2773 * Request neutral output of actuator. The applied brake type is 2774 * determined by the NeutralMode configuration. 2775 * 2776 * <ul> 2777 * <li> <b>NeutralOut Parameters:</b> 2778 * </ul> 2779 * 2780 * @param request Control object to request of the device 2781 * @return Code response of the request 2782 */ 2783 public StatusCode setControl(NeutralOut request) 2784 { 2785 return setControlPrivate(request); 2786 } 2787 2788 /** 2789 * Request coast neutral output of actuator. The bridge is disabled 2790 * and the rotor is allowed to coast. 2791 * 2792 * <ul> 2793 * <li> <b>CoastOut Parameters:</b> 2794 * </ul> 2795 * 2796 * @param request Control object to request of the device 2797 * @return Code response of the request 2798 */ 2799 public StatusCode setControl(CoastOut request) 2800 { 2801 return setControlPrivate(request); 2802 } 2803 2804 /** 2805 * Applies full neutral-brake by shorting motor leads together. 2806 * 2807 * <ul> 2808 * <li> <b>StaticBrake Parameters:</b> 2809 * </ul> 2810 * 2811 * @param request Control object to request of the device 2812 * @return Code response of the request 2813 */ 2814 public StatusCode setControl(StaticBrake request) 2815 { 2816 return setControlPrivate(request); 2817 } 2818 2819 /** 2820 * Control motor with generic control request object. 2821 * <p> 2822 * User must make sure the specified object is castable to a valid control request, 2823 * otherwise this function will fail at run-time and return the NotSupported StatusCode 2824 * 2825 * @param request Control object to request of the device 2826 * @return Status Code of the request, 0 is OK 2827 */ 2828 public StatusCode setControl(ControlRequest request) 2829 { 2830 if (request instanceof DutyCycleOut) 2831 return setControl((DutyCycleOut)request); 2832 if (request instanceof TorqueCurrentFOC) 2833 return setControl((TorqueCurrentFOC)request); 2834 if (request instanceof VoltageOut) 2835 return setControl((VoltageOut)request); 2836 if (request instanceof PositionDutyCycle) 2837 return setControl((PositionDutyCycle)request); 2838 if (request instanceof PositionVoltage) 2839 return setControl((PositionVoltage)request); 2840 if (request instanceof PositionTorqueCurrentFOC) 2841 return setControl((PositionTorqueCurrentFOC)request); 2842 if (request instanceof VelocityDutyCycle) 2843 return setControl((VelocityDutyCycle)request); 2844 if (request instanceof VelocityVoltage) 2845 return setControl((VelocityVoltage)request); 2846 if (request instanceof VelocityTorqueCurrentFOC) 2847 return setControl((VelocityTorqueCurrentFOC)request); 2848 if (request instanceof MotionMagicDutyCycle) 2849 return setControl((MotionMagicDutyCycle)request); 2850 if (request instanceof MotionMagicVoltage) 2851 return setControl((MotionMagicVoltage)request); 2852 if (request instanceof MotionMagicTorqueCurrentFOC) 2853 return setControl((MotionMagicTorqueCurrentFOC)request); 2854 if (request instanceof Follower) 2855 return setControl((Follower)request); 2856 if (request instanceof StrictFollower) 2857 return setControl((StrictFollower)request); 2858 if (request instanceof NeutralOut) 2859 return setControl((NeutralOut)request); 2860 if (request instanceof CoastOut) 2861 return setControl((CoastOut)request); 2862 if (request instanceof StaticBrake) 2863 return setControl((StaticBrake)request); 2864 return StatusCode.NotSupported; 2865 } 2866 2867 2868 /** 2869 * The position to set the rotor position to right now. 2870 * 2871 * @param newValue Value to set to. 2872 * @param timeoutSeconds Maximum time to wait up to in seconds. 2873 * @return StatusCode of the set command 2874 */ 2875 public StatusCode setRotorPosition(double newValue, double timeoutSeconds) { 2876 return getConfigurator().setRotorPosition(newValue, timeoutSeconds); 2877 } 2878 /** 2879 * The position to set the rotor position to right now. 2880 * <p> 2881 * This will wait up to 0.050 seconds (50ms) by default. 2882 * 2883 * @param newValue Value to set to. 2884 * @return StatusCode of the set command 2885 */ 2886 public StatusCode setRotorPosition(double newValue) { 2887 return setRotorPosition(newValue, 0.050); 2888 } 2889 2890 /** 2891 * Clear the sticky faults in the device. 2892 * <p> 2893 * This typically has no impact on the device functionality. Instead, 2894 * it just clears telemetry faults that are accessible via API and 2895 * Tuner Self-Test. 2896 * @param timeoutSeconds Maximum time to wait up to in seconds. 2897 * @return StatusCode of the set command 2898 */ 2899 public StatusCode clearStickyFaults(double timeoutSeconds) { 2900 return getConfigurator().clearStickyFaults(timeoutSeconds); 2901 } 2902 /** 2903 * Clear the sticky faults in the device. 2904 * <p> 2905 * This typically has no impact on the device functionality. Instead, 2906 * it just clears telemetry faults that are accessible via API and 2907 * Tuner Self-Test. 2908 * <p> 2909 * This will wait up to 0.050 seconds (50ms) by default. 2910 * @return StatusCode of the set command 2911 */ 2912 public StatusCode clearStickyFaults() { 2913 return clearStickyFaults(0.050); 2914 } 2915} 2916