001/* 002 * Copyright (C) Cross The Road Electronics. All rights reserved. 003 * License information can be found in CTRE_LICENSE.txt 004 * For support and suggestions contact support@ctr-electronics.com or file 005 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases 006 */ 007package com.ctre.phoenix6.hardware; 008 009import java.util.ArrayList; 010import java.util.concurrent.locks.Lock; 011import java.util.concurrent.locks.ReentrantLock; 012 013import com.ctre.phoenix6.CANBus; 014import com.ctre.phoenix6.StatusCode; 015import com.ctre.phoenix6.StatusSignal; 016import com.ctre.phoenix6.Utils; 017import com.ctre.phoenix6.configs.MotorOutputConfigs; 018import com.ctre.phoenix6.configs.TalonFXConfiguration; 019import com.ctre.phoenix6.controls.ControlRequest; 020import com.ctre.phoenix6.controls.DutyCycleOut; 021import com.ctre.phoenix6.controls.NeutralOut; 022import com.ctre.phoenix6.controls.VoltageOut; 023import com.ctre.phoenix6.hardware.core.CoreTalonFX; 024import com.ctre.phoenix6.jni.PlatformJNI; 025import com.ctre.phoenix6.signals.NeutralModeValue; 026import com.ctre.phoenix6.sim.DeviceType; 027import com.ctre.phoenix6.wpiutils.AutoFeedEnable; 028import com.ctre.phoenix6.wpiutils.CallbackHelper; 029import com.ctre.phoenix6.wpiutils.MotorSafetyImplem; 030import com.ctre.phoenix6.wpiutils.ReplayAutoEnable; 031 032import edu.wpi.first.hal.HAL; 033import edu.wpi.first.hal.HAL.SimPeriodicBeforeCallback; 034import edu.wpi.first.hal.HALValue; 035import edu.wpi.first.hal.SimBoolean; 036import edu.wpi.first.hal.SimDevice; 037import edu.wpi.first.hal.SimDevice.Direction; 038import edu.wpi.first.hal.SimDouble; 039import edu.wpi.first.hal.simulation.SimDeviceDataJNI; 040import edu.wpi.first.util.sendable.Sendable; 041import edu.wpi.first.util.sendable.SendableBuilder; 042import edu.wpi.first.util.sendable.SendableRegistry; 043import edu.wpi.first.wpilibj.RobotBase; 044import edu.wpi.first.wpilibj.simulation.CallbackStore; 045import edu.wpi.first.wpilibj.simulation.SimDeviceSim; 046 047/** 048 * WPILib-integrated version of {@link CoreTalonFX}. 049 */ 050public class TalonFX extends CoreTalonFX implements Sendable, AutoCloseable { 051 /** 052 * The StatusSignal getters are copies so that calls 053 * to the WPI interface do not update any references 054 */ 055 @SuppressWarnings("this-escape") 056 private final StatusSignal<Double> m_dutyCycle = getDutyCycle(false).clone(); 057 058 private final DutyCycleOut m_setterControl = new DutyCycleOut(0); 059 private final NeutralOut m_neutralControl = new NeutralOut(); 060 private final VoltageOut m_voltageControl = new VoltageOut(0); 061 062 private final MotorOutputConfigs m_configs = new MotorOutputConfigs(); 063 064 private String m_description; 065 066 private static final DeviceType kSimDeviceType = DeviceType.P6_TalonFXType; 067 068 private SimDevice m_simMotor; 069 private SimDouble m_simSupplyVoltage; 070 private SimDouble m_simDutyCycle; 071 private SimDouble m_simMotorVoltage; 072 private SimDouble m_simTorqueCurrent; 073 private SimDouble m_simSupplyCurrent; 074 075 private SimDevice m_simForwardLimit; 076 private SimBoolean m_simForwardLimitValue; 077 078 private SimDevice m_simReverseLimit; 079 private SimBoolean m_simReverseLimitValue; 080 081 private SimDevice m_simRotor; 082 private SimDouble m_simRotorPos; 083 private SimDouble m_simRotorRawPos; 084 private SimDouble m_simRotorVel; 085 private SimDouble m_simRotorAccel; 086 087 // returned registered callbacks 088 private final ArrayList<CallbackStore> m_simValueChangedCallbacks = new ArrayList<CallbackStore>(); 089 private SimPeriodicBeforeCallback m_simPeriodicBeforeCallback = null; 090 091 /** 092 * The default motor safety timeout IF calling application 093 * enables the feature. 094 */ 095 public static final double kDefaultSafetyExpiration = 0.1; 096 097 /** 098 * Late-constructed motor safety, which ensures feature is off unless calling 099 * applications explicitly enables it. 100 */ 101 private MotorSafetyImplem m_motorSafety = null; 102 private double m_motSafeExpiration = kDefaultSafetyExpiration; 103 private final Lock m_motorSafetyLock = new ReentrantLock(); 104 105 /** 106 * Constructs a new Talon FX motor controller object. 107 * <p> 108 * Constructs the device using the default CAN bus for the system 109 * (see {@link CANBus#CANBus()}). 110 * 111 * @param deviceId ID of the device, as configured in Phoenix Tuner 112 */ 113 public TalonFX(int deviceId) { 114 this(deviceId, new CANBus()); 115 } 116 117 /** 118 * Constructs a new Talon FX motor controller object. 119 * 120 * @param deviceId ID of the device, as configured in Phoenix Tuner 121 * @param canbus Name of the CAN bus this device is on. Possible CAN bus 122 * strings are: 123 * <ul> 124 * <li>"rio" for the native roboRIO CAN bus 125 * <li>CANivore name or serial number 126 * <li>SocketCAN interface (non-FRC Linux only) 127 * <li>"*" for any CANivore seen by the program 128 * <li>empty string (default) to select the default for the 129 * system: 130 * <ul> 131 * <li>"rio" on roboRIO 132 * <li>"can0" on Linux 133 * <li>"*" on Windows 134 * </ul> 135 * </ul> 136 * 137 * @deprecated Constructing devices with a CAN bus string is deprecated for removal 138 * in the 2027 season. Construct devices using a {@link CANBus} instance instead. 139 */ 140 @Deprecated(since = "2026", forRemoval = true) 141 public TalonFX(int deviceId, String canbus) { 142 this(deviceId, new CANBus(canbus)); 143 } 144 145 /** 146 * Constructs a new Talon FX motor controller object. 147 * 148 * @param deviceId ID of the device, as configured in Phoenix Tuner 149 * @param canbus The CAN bus this device is on 150 */ 151 @SuppressWarnings("this-escape") 152 public TalonFX(int deviceId, CANBus canbus) { 153 super(deviceId, canbus); 154 m_description = "Talon FX (v6) " + deviceId; 155 156 if (RobotBase.isSimulation()) { 157 /* run in both swsim and hwsim */ 158 AutoFeedEnable.getInstance().start(); 159 } 160 if (Utils.isReplay()) { 161 ReplayAutoEnable.getInstance().start(); 162 } 163 if (deviceId == -1) return; 164 165 SendableRegistry.addLW(this, "Talon FX (v6) ", deviceId); 166 167 m_simMotor = SimDevice.create("CANMotor:Talon FX (v6)", deviceId); 168 169 final String base = "Talon FX (v6)[" + deviceId + "]/"; 170 m_simRotor = SimDevice.create("CANEncoder:" + base + "Rotor Sensor"); 171 m_simForwardLimit = SimDevice.create("CANDIO:" + base + "Fwd Limit"); 172 m_simReverseLimit = SimDevice.create("CANDIO:" + base + "Rev Limit"); 173 174 if (m_simMotor != null) { 175 /* First make sure our simulated device gets enabled */ 176 m_simPeriodicBeforeCallback = HAL.registerSimPeriodicBeforeCallback(this::onPeriodic); 177 178 m_simSupplyVoltage = m_simMotor.createDouble("supplyVoltage", Direction.kInput, 12.0); 179 180 m_simDutyCycle = m_simMotor.createDouble("dutyCycle", Direction.kOutput, 0); 181 m_simMotorVoltage = m_simMotor.createDouble("motorVoltage", Direction.kOutput, 0); 182 m_simTorqueCurrent = m_simMotor.createDouble("torqueCurrent", Direction.kOutput, 0); 183 m_simSupplyCurrent = m_simMotor.createDouble("supplyCurrent", Direction.kOutput, 0); 184 185 final SimDeviceSim sim = new SimDeviceSim("CANMotor:Talon FX (v6)"); 186 m_simValueChangedCallbacks.add( 187 sim.registerValueChangedCallback(m_simSupplyVoltage, this::onValueChanged, true) 188 ); 189 } 190 if (m_simRotor != null) { 191 m_simRotorPos = m_simRotor.createDouble("position", Direction.kOutput, 0); 192 193 m_simRotorRawPos = m_simRotor.createDouble("rawPositionInput", Direction.kInput, 0); 194 m_simRotorVel = m_simRotor.createDouble("velocity", Direction.kInput, 0); 195 m_simRotorAccel = m_simRotor.createDouble("acceleration", Direction.kInput, 0); 196 197 final SimDeviceSim sim = new SimDeviceSim("CANEncoder:" + base + "Rotor Sensor"); 198 m_simValueChangedCallbacks.add( 199 sim.registerValueChangedCallback(m_simRotorRawPos, this::onValueChanged, true) 200 ); 201 m_simValueChangedCallbacks.add( 202 sim.registerValueChangedCallback(m_simRotorVel, this::onValueChanged, true) 203 ); 204 m_simValueChangedCallbacks.add( 205 sim.registerValueChangedCallback(m_simRotorAccel, this::onValueChanged, true) 206 ); 207 } 208 if (m_simForwardLimit != null) { 209 m_simForwardLimit.createBoolean("init", Direction.kOutput, true); 210 m_simForwardLimit.createBoolean("input", Direction.kOutput, true); 211 212 m_simForwardLimitValue = m_simForwardLimit.createBoolean("value", Direction.kBidir, false); 213 214 final SimDeviceSim sim = new SimDeviceSim("CANDIO:" + base + "Fwd Limit"); 215 m_simValueChangedCallbacks.add( 216 sim.registerValueChangedCallback(m_simForwardLimitValue, this::onValueChanged, true) 217 ); 218 } 219 if (m_simReverseLimit != null) { 220 m_simReverseLimit.createBoolean("init", Direction.kOutput, true); 221 m_simReverseLimit.createBoolean("input", Direction.kOutput, true); 222 223 m_simReverseLimitValue = m_simReverseLimit.createBoolean("value", Direction.kBidir, false); 224 225 final SimDeviceSim sim = new SimDeviceSim("CANDIO:" + base + "Rev Limit"); 226 m_simValueChangedCallbacks.add( 227 sim.registerValueChangedCallback(m_simReverseLimitValue, this::onValueChanged, true) 228 ); 229 } 230 } 231 232 /** 233 * Constructs a stubbed-out TalonFX, where all status signals, controls, configs, 234 * etc. perform no action and immediately return OK. This can be used to silence 235 * error messages for devices that have been completely removed from the robot. 236 * 237 * @return Stubbed-out TalonFX 238 */ 239 public static TalonFX none() { 240 return new TalonFX(-1, new CANBus()); 241 } 242 243 // ----- Callbacks for Sim ----- // 244 private void onValueChanged(String name, int handle, int direction, HALValue value) { 245 String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle)); 246 String physType = deviceName + ":" + name; 247 PlatformJNI.JNI_SimSetPhysicsInput( 248 kSimDeviceType.value, getDeviceID(), 249 physType, CallbackHelper.getRawValue(value) 250 ); 251 } 252 253 private void onPeriodic() { 254 double value = 0; 255 int err = 0; 256 257 final int deviceID = getDeviceID(); 258 259 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "SupplyVoltage"); 260 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 261 if (err == 0) { 262 m_simSupplyVoltage.set(value); 263 } 264 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "DutyCycle"); 265 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 266 if (err == 0) { 267 m_simDutyCycle.set(value); 268 } 269 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "MotorVoltage"); 270 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 271 if (err == 0) { 272 m_simMotorVoltage.set(value); 273 } 274 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "TorqueCurrent"); 275 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 276 if (err == 0) { 277 m_simTorqueCurrent.set(value); 278 } 279 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "SupplyCurrent"); 280 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 281 if (err == 0) { 282 m_simSupplyCurrent.set(value); 283 } 284 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorPosition"); 285 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 286 if (err == 0) { 287 m_simRotorPos.set(value); 288 } 289 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RawRotorPosition"); 290 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 291 if (err == 0) { 292 m_simRotorRawPos.set(value); 293 } 294 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorVelocity"); 295 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 296 if (err == 0) { 297 m_simRotorVel.set(value); 298 } 299 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorAcceleration"); 300 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 301 if (err == 0) { 302 m_simRotorAccel.set(value); 303 } 304 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "ForwardLimit"); 305 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 306 if (err == 0) { 307 m_simForwardLimitValue.set((int) value != 0); 308 } 309 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "ReverseLimit"); 310 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 311 if (err == 0) { 312 m_simReverseLimitValue.set((int) value != 0); 313 } 314 } 315 316 // ------- AutoCloseable ----- // 317 @Override 318 public void close() { 319 SendableRegistry.remove(this); 320 if (m_simPeriodicBeforeCallback != null) { 321 m_simPeriodicBeforeCallback.close(); 322 m_simPeriodicBeforeCallback = null; 323 } 324 if (m_simMotor != null) { 325 m_simMotor.close(); 326 m_simMotor = null; 327 } 328 if (m_simRotor != null) { 329 m_simRotor.close(); 330 m_simRotor = null; 331 } 332 if (m_simForwardLimit != null) { 333 m_simForwardLimit.close(); 334 m_simForwardLimit = null; 335 } 336 if (m_simReverseLimit != null) { 337 m_simReverseLimit.close(); 338 m_simReverseLimit = null; 339 } 340 341 for (var callback : m_simValueChangedCallbacks) { 342 callback.close(); 343 } 344 m_simValueChangedCallbacks.clear(); 345 346 AutoFeedEnable.getInstance().stop(); 347 ReplayAutoEnable.getInstance().stop(); 348 } 349 350 // ------ set/get routines for WPILIB interfaces ------// 351 /** 352 * Common interface for setting the speed of a motor controller. 353 * 354 * @param speed The speed to set. Value should be between -1.0 and 1.0. 355 */ 356 public final void set(double speed) { 357 feed(); 358 setControl(m_setterControl.withOutput(speed)); 359 } 360 361 /** 362 * Common interface for seting the direct voltage output of a motor controller. 363 * 364 * @param volts The voltage to output. 365 */ 366 public final void setVoltage(double volts) { 367 feed(); 368 setControl(m_voltageControl.withOutput(volts)); 369 } 370 371 /** 372 * Common interface for getting the current set speed of a motor controller. 373 * 374 * @return The current set speed. Value is between -1.0 and 1.0. 375 */ 376 public final double get() { 377 return m_dutyCycle.refresh().getValue(); 378 } 379 380 // ---------Intercept CTRE calls for motor safety ---------// 381 @Override 382 protected StatusCode setControlPrivate(ControlRequest request) { 383 /* intercept the control setter and feed motor-safety */ 384 feed(); 385 return super.setControlPrivate(request); 386 } 387 388 // ----------------------- turn-motor-off routines-------------------// 389 /** 390 * Common interface for disabling a motor controller. 391 */ 392 public final void disable() { 393 setControl(m_neutralControl); 394 } 395 396 /** 397 * Common interface to stop motor movement until set is called again. 398 */ 399 public final void stopMotor() { 400 disable(); 401 } 402 403 // -------------------- Neutral mode routines ----------------// 404 /** 405 * Sets the mode of operation when output is neutral or disabled. 406 * This is equivalent to setting the {@link MotorOutputConfigs#NeutralMode} 407 * when applying a {@link TalonFXConfiguration} to the motor. 408 * <p> 409 * Since neutral mode is a config, this API is blocking. We recommend 410 * that users avoid calling this API periodically. 411 * <p> 412 * This will wait up to 0.100 seconds (100ms) by default. 413 * 414 * @param neutralMode The state of the motor controller bridge when output is neutral or disabled 415 * @return Status of refreshing and applying the neutral mode config 416 */ 417 public final StatusCode setNeutralMode(NeutralModeValue neutralMode) { 418 return setNeutralMode(neutralMode, 0.100); 419 } 420 421 /** 422 * Sets the mode of operation when output is neutral or disabled. 423 * <p> 424 * Since neutral mode is a config, this API is blocking. We recommend 425 * that users avoid calling this API periodically. 426 * 427 * @param neutralMode The state of the motor controller bridge when output is neutral or disabled 428 * @param timeoutSeconds Maximum amount of time to wait when performing configuration 429 * @return Status of refreshing and applying the neutral mode config 430 */ 431 public final StatusCode setNeutralMode(NeutralModeValue neutralMode, double timeoutSeconds) { 432 /* First read the configs so they're up-to-date */ 433 StatusCode retval = getConfigurator().refresh(m_configs, timeoutSeconds); 434 if (retval.isOK()) { 435 /* Then set the neutral mode config to the appropriate value */ 436 m_configs.NeutralMode = neutralMode; 437 retval = getConfigurator().apply(m_configs, timeoutSeconds); 438 } 439 return retval; 440 } 441 442 // ----- Sendable ----- // 443 @Override 444 public void initSendable(SendableBuilder builder) { 445 builder.setSmartDashboardType("Motor Controller"); 446 builder.setActuator(true); 447 builder.setSafeState(this::stopMotor); 448 builder.addDoubleProperty("Value", this::get, this::set); 449 } 450 451 /** 452 * @return Description of motor controller 453 */ 454 public String getDescription() { 455 return m_description; 456 } 457 458 /* ----- Motor Safety ----- */ 459 /** caller must lock appropriately */ 460 private MotorSafetyImplem GetMotorSafety() { 461 if (m_motorSafety == null) { 462 /* newly created MS object */ 463 m_motorSafety = new MotorSafetyImplem(this::stopMotor, getDescription()); 464 /* apply the expiration timeout */ 465 m_motorSafety.setExpiration(m_motSafeExpiration); 466 } 467 return m_motorSafety; 468 } 469 470 /** 471 * Feed the motor safety object. 472 * <p> 473 * Resets the timer on this object that is used to do the timeouts. 474 */ 475 public final void feed() { 476 m_motorSafetyLock.lock(); 477 try { 478 if (m_motorSafety == null) { 479 /* do nothing, MS features were never enabled */ 480 } else { 481 GetMotorSafety().feed(); 482 } 483 } finally { 484 m_motorSafetyLock.unlock(); 485 } 486 } 487 488 /** 489 * Set the expiration time for the corresponding motor safety object. 490 * 491 * @param expirationTime The timeout value in seconds. 492 */ 493 public final void setExpiration(double expirationTime) { 494 m_motorSafetyLock.lock(); 495 try { 496 /* save the value for if/when we do create the MS object */ 497 m_motSafeExpiration = expirationTime; 498 /* apply it only if MS object exists */ 499 if (m_motorSafety == null) { 500 /* do nothing, MS features were never enabled */ 501 } else { 502 /* this call will trigger creating a registered MS object */ 503 GetMotorSafety().setExpiration(m_motSafeExpiration); 504 } 505 } finally { 506 m_motorSafetyLock.unlock(); 507 } 508 } 509 510 /** 511 * Retrieve the timeout value for the corresponding motor safety object. 512 * 513 * @return the timeout value in seconds. 514 */ 515 public final double getExpiration() { 516 m_motorSafetyLock.lock(); 517 try { 518 /* return the intended expiration time */ 519 return m_motSafeExpiration; 520 } finally { 521 m_motorSafetyLock.unlock(); 522 } 523 } 524 525 /** 526 * Determine of the motor is still operating or has timed out. 527 * 528 * @return a true value if the motor is still operating normally and hasn't 529 * timed out. 530 */ 531 public final boolean isAlive() { 532 m_motorSafetyLock.lock(); 533 try { 534 if (m_motorSafety == null) { 535 /* MC is alive - MS features were never enabled to neutral the MC. */ 536 return true; 537 } else { 538 return GetMotorSafety().isAlive(); 539 } 540 } finally { 541 m_motorSafetyLock.unlock(); 542 } 543 } 544 545 /** 546 * Enable/disable motor safety for this device. 547 * <p> 548 * Turn on and off the motor safety option for this object. 549 * 550 * @param enabled True if motor safety is enforced for this object. 551 */ 552 public final void setSafetyEnabled(boolean enabled) { 553 m_motorSafetyLock.lock(); 554 try { 555 if (m_motorSafety == null && !enabled) { 556 /* 557 * Caller wants to disable MS, 558 * but MS features were nevere enabled, 559 * so it doesn't need to be disabled. 560 */ 561 } else { 562 /* MS will be created if it does not exist */ 563 GetMotorSafety().setSafetyEnabled(enabled); 564 } 565 } finally { 566 m_motorSafetyLock.unlock(); 567 } 568 } 569 570 /** 571 * Return the state of the motor safety enabled flag. 572 * <p> 573 * Return if the motor safety is currently enabled for this device. 574 * 575 * @return True if motor safety is enforced for this device 576 */ 577 public final boolean isSafetyEnabled() { 578 m_motorSafetyLock.lock(); 579 try { 580 if (m_motorSafety == null) { 581 /* MS features were never enabled. */ 582 return false; 583 } else { 584 return GetMotorSafety().isSafetyEnabled(); 585 } 586 } finally { 587 m_motorSafetyLock.unlock(); 588 } 589 } 590}