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 155 m_description = "Talon FX (v6) " + deviceId; 156 SendableRegistry.addLW(this, "Talon FX (v6) ", deviceId); 157 158 if (RobotBase.isSimulation()) { 159 /* run in both swsim and hwsim */ 160 AutoFeedEnable.getInstance().start(); 161 } 162 if (Utils.isReplay()) { 163 ReplayAutoEnable.getInstance().start(); 164 } 165 166 m_simMotor = SimDevice.create("CANMotor:Talon FX (v6)", deviceId); 167 168 final String base = "Talon FX (v6)[" + deviceId + "]/"; 169 m_simRotor = SimDevice.create("CANEncoder:" + base + "Rotor Sensor"); 170 m_simForwardLimit = SimDevice.create("CANDIO:" + base + "Fwd Limit"); 171 m_simReverseLimit = SimDevice.create("CANDIO:" + base + "Rev Limit"); 172 173 if (m_simMotor != null) { 174 /* First make sure our simulated device gets enabled */ 175 m_simPeriodicBeforeCallback = HAL.registerSimPeriodicBeforeCallback(this::onPeriodic); 176 177 m_simSupplyVoltage = m_simMotor.createDouble("supplyVoltage", Direction.kInput, 12.0); 178 179 m_simDutyCycle = m_simMotor.createDouble("dutyCycle", Direction.kOutput, 0); 180 m_simMotorVoltage = m_simMotor.createDouble("motorVoltage", Direction.kOutput, 0); 181 m_simTorqueCurrent = m_simMotor.createDouble("torqueCurrent", Direction.kOutput, 0); 182 m_simSupplyCurrent = m_simMotor.createDouble("supplyCurrent", Direction.kOutput, 0); 183 184 final SimDeviceSim sim = new SimDeviceSim("CANMotor:Talon FX (v6)"); 185 m_simValueChangedCallbacks.add( 186 sim.registerValueChangedCallback(m_simSupplyVoltage, this::onValueChanged, true) 187 ); 188 } 189 if (m_simRotor != null) { 190 m_simRotorPos = m_simRotor.createDouble("position", Direction.kOutput, 0); 191 192 m_simRotorRawPos = m_simRotor.createDouble("rawPositionInput", Direction.kInput, 0); 193 m_simRotorVel = m_simRotor.createDouble("velocity", Direction.kInput, 0); 194 m_simRotorAccel = m_simRotor.createDouble("acceleration", Direction.kInput, 0); 195 196 final SimDeviceSim sim = new SimDeviceSim("CANEncoder:" + base + "Rotor Sensor"); 197 m_simValueChangedCallbacks.add( 198 sim.registerValueChangedCallback(m_simRotorRawPos, this::onValueChanged, true) 199 ); 200 m_simValueChangedCallbacks.add( 201 sim.registerValueChangedCallback(m_simRotorVel, this::onValueChanged, true) 202 ); 203 m_simValueChangedCallbacks.add( 204 sim.registerValueChangedCallback(m_simRotorAccel, this::onValueChanged, true) 205 ); 206 } 207 if (m_simForwardLimit != null) { 208 m_simForwardLimit.createBoolean("init", Direction.kOutput, true); 209 m_simForwardLimit.createBoolean("input", Direction.kOutput, true); 210 211 m_simForwardLimitValue = m_simForwardLimit.createBoolean("value", Direction.kBidir, false); 212 213 final SimDeviceSim sim = new SimDeviceSim("CANDIO:" + base + "Fwd Limit"); 214 m_simValueChangedCallbacks.add( 215 sim.registerValueChangedCallback(m_simForwardLimitValue, this::onValueChanged, true) 216 ); 217 } 218 if (m_simReverseLimit != null) { 219 m_simReverseLimit.createBoolean("init", Direction.kOutput, true); 220 m_simReverseLimit.createBoolean("input", Direction.kOutput, true); 221 222 m_simReverseLimitValue = m_simReverseLimit.createBoolean("value", Direction.kBidir, false); 223 224 final SimDeviceSim sim = new SimDeviceSim("CANDIO:" + base + "Rev Limit"); 225 m_simValueChangedCallbacks.add( 226 sim.registerValueChangedCallback(m_simReverseLimitValue, this::onValueChanged, true) 227 ); 228 } 229 } 230 231 // ----- Callbacks for Sim ----- // 232 private void onValueChanged(String name, int handle, int direction, HALValue value) { 233 String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle)); 234 String physType = deviceName + ":" + name; 235 PlatformJNI.JNI_SimSetPhysicsInput( 236 kSimDeviceType.value, getDeviceID(), 237 physType, CallbackHelper.getRawValue(value) 238 ); 239 } 240 241 private void onPeriodic() { 242 double value = 0; 243 int err = 0; 244 245 final int deviceID = getDeviceID(); 246 247 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "SupplyVoltage"); 248 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 249 if (err == 0) { 250 m_simSupplyVoltage.set(value); 251 } 252 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "DutyCycle"); 253 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 254 if (err == 0) { 255 m_simDutyCycle.set(value); 256 } 257 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "MotorVoltage"); 258 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 259 if (err == 0) { 260 m_simMotorVoltage.set(value); 261 } 262 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "TorqueCurrent"); 263 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 264 if (err == 0) { 265 m_simTorqueCurrent.set(value); 266 } 267 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "SupplyCurrent"); 268 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 269 if (err == 0) { 270 m_simSupplyCurrent.set(value); 271 } 272 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorPosition"); 273 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 274 if (err == 0) { 275 m_simRotorPos.set(value); 276 } 277 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RawRotorPosition"); 278 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 279 if (err == 0) { 280 m_simRotorRawPos.set(value); 281 } 282 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorVelocity"); 283 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 284 if (err == 0) { 285 m_simRotorVel.set(value); 286 } 287 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RotorAcceleration"); 288 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 289 if (err == 0) { 290 m_simRotorAccel.set(value); 291 } 292 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "ForwardLimit"); 293 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 294 if (err == 0) { 295 m_simForwardLimitValue.set((int) value != 0); 296 } 297 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "ReverseLimit"); 298 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 299 if (err == 0) { 300 m_simReverseLimitValue.set((int) value != 0); 301 } 302 } 303 304 // ------- AutoCloseable ----- // 305 @Override 306 public void close() { 307 SendableRegistry.remove(this); 308 if (m_simPeriodicBeforeCallback != null) { 309 m_simPeriodicBeforeCallback.close(); 310 m_simPeriodicBeforeCallback = null; 311 } 312 if (m_simMotor != null) { 313 m_simMotor.close(); 314 m_simMotor = null; 315 } 316 if (m_simRotor != null) { 317 m_simRotor.close(); 318 m_simRotor = null; 319 } 320 if (m_simForwardLimit != null) { 321 m_simForwardLimit.close(); 322 m_simForwardLimit = null; 323 } 324 if (m_simReverseLimit != null) { 325 m_simReverseLimit.close(); 326 m_simReverseLimit = null; 327 } 328 329 for (var callback : m_simValueChangedCallbacks) { 330 callback.close(); 331 } 332 m_simValueChangedCallbacks.clear(); 333 334 AutoFeedEnable.getInstance().stop(); 335 ReplayAutoEnable.getInstance().stop(); 336 } 337 338 // ------ set/get routines for WPILIB interfaces ------// 339 /** 340 * Common interface for setting the speed of a motor controller. 341 * 342 * @param speed The speed to set. Value should be between -1.0 and 1.0. 343 */ 344 public final void set(double speed) { 345 feed(); 346 setControl(m_setterControl.withOutput(speed)); 347 } 348 349 /** 350 * Common interface for seting the direct voltage output of a motor controller. 351 * 352 * @param volts The voltage to output. 353 */ 354 public final void setVoltage(double volts) { 355 feed(); 356 setControl(m_voltageControl.withOutput(volts)); 357 } 358 359 /** 360 * Common interface for getting the current set speed of a motor controller. 361 * 362 * @return The current set speed. Value is between -1.0 and 1.0. 363 */ 364 public final double get() { 365 return m_dutyCycle.refresh().getValue(); 366 } 367 368 // ---------Intercept CTRE calls for motor safety ---------// 369 @Override 370 protected StatusCode setControlPrivate(ControlRequest request) { 371 /* intercept the control setter and feed motor-safety */ 372 feed(); 373 return super.setControlPrivate(request); 374 } 375 376 // ----------------------- turn-motor-off routines-------------------// 377 /** 378 * Common interface for disabling a motor controller. 379 */ 380 public final void disable() { 381 setControl(m_neutralControl); 382 } 383 384 /** 385 * Common interface to stop motor movement until set is called again. 386 */ 387 public final void stopMotor() { 388 disable(); 389 } 390 391 // -------------------- Neutral mode routines ----------------// 392 /** 393 * Sets the mode of operation when output is neutral or disabled. 394 * This is equivalent to setting the {@link MotorOutputConfigs#NeutralMode} 395 * when applying a {@link TalonFXConfiguration} to the motor. 396 * <p> 397 * Since neutral mode is a config, this API is blocking. We recommend 398 * that users avoid calling this API periodically. 399 * <p> 400 * This will wait up to 0.100 seconds (100ms) by default. 401 * 402 * @param neutralMode The state of the motor controller bridge when output is neutral or disabled 403 * @return Status of refreshing and applying the neutral mode config 404 */ 405 public final StatusCode setNeutralMode(NeutralModeValue neutralMode) { 406 return setNeutralMode(neutralMode, 0.100); 407 } 408 409 /** 410 * Sets the mode of operation when output is neutral or disabled. 411 * <p> 412 * Since neutral mode is a config, this API is blocking. We recommend 413 * that users avoid calling this API periodically. 414 * 415 * @param neutralMode The state of the motor controller bridge when output is neutral or disabled 416 * @param timeoutSeconds Maximum amount of time to wait when performing configuration 417 * @return Status of refreshing and applying the neutral mode config 418 */ 419 public final StatusCode setNeutralMode(NeutralModeValue neutralMode, double timeoutSeconds) { 420 /* First read the configs so they're up-to-date */ 421 StatusCode retval = getConfigurator().refresh(m_configs, timeoutSeconds); 422 if (retval.isOK()) { 423 /* Then set the neutral mode config to the appropriate value */ 424 m_configs.NeutralMode = neutralMode; 425 retval = getConfigurator().apply(m_configs, timeoutSeconds); 426 } 427 return retval; 428 } 429 430 // ----- Sendable ----- // 431 @Override 432 public void initSendable(SendableBuilder builder) { 433 builder.setSmartDashboardType("Motor Controller"); 434 builder.setActuator(true); 435 builder.setSafeState(this::stopMotor); 436 builder.addDoubleProperty("Value", this::get, this::set); 437 } 438 439 /** 440 * @return Description of motor controller 441 */ 442 public String getDescription() { 443 return m_description; 444 } 445 446 /* ----- Motor Safety ----- */ 447 /** caller must lock appropriately */ 448 private MotorSafetyImplem GetMotorSafety() { 449 if (m_motorSafety == null) { 450 /* newly created MS object */ 451 m_motorSafety = new MotorSafetyImplem(this::stopMotor, getDescription()); 452 /* apply the expiration timeout */ 453 m_motorSafety.setExpiration(m_motSafeExpiration); 454 } 455 return m_motorSafety; 456 } 457 458 /** 459 * Feed the motor safety object. 460 * <p> 461 * Resets the timer on this object that is used to do the timeouts. 462 */ 463 public final void feed() { 464 m_motorSafetyLock.lock(); 465 try { 466 if (m_motorSafety == null) { 467 /* do nothing, MS features were never enabled */ 468 } else { 469 GetMotorSafety().feed(); 470 } 471 } finally { 472 m_motorSafetyLock.unlock(); 473 } 474 } 475 476 /** 477 * Set the expiration time for the corresponding motor safety object. 478 * 479 * @param expirationTime The timeout value in seconds. 480 */ 481 public final void setExpiration(double expirationTime) { 482 m_motorSafetyLock.lock(); 483 try { 484 /* save the value for if/when we do create the MS object */ 485 m_motSafeExpiration = expirationTime; 486 /* apply it only if MS object exists */ 487 if (m_motorSafety == null) { 488 /* do nothing, MS features were never enabled */ 489 } else { 490 /* this call will trigger creating a registered MS object */ 491 GetMotorSafety().setExpiration(m_motSafeExpiration); 492 } 493 } finally { 494 m_motorSafetyLock.unlock(); 495 } 496 } 497 498 /** 499 * Retrieve the timeout value for the corresponding motor safety object. 500 * 501 * @return the timeout value in seconds. 502 */ 503 public final double getExpiration() { 504 m_motorSafetyLock.lock(); 505 try { 506 /* return the intended expiration time */ 507 return m_motSafeExpiration; 508 } finally { 509 m_motorSafetyLock.unlock(); 510 } 511 } 512 513 /** 514 * Determine of the motor is still operating or has timed out. 515 * 516 * @return a true value if the motor is still operating normally and hasn't 517 * timed out. 518 */ 519 public final boolean isAlive() { 520 m_motorSafetyLock.lock(); 521 try { 522 if (m_motorSafety == null) { 523 /* MC is alive - MS features were never enabled to neutral the MC. */ 524 return true; 525 } else { 526 return GetMotorSafety().isAlive(); 527 } 528 } finally { 529 m_motorSafetyLock.unlock(); 530 } 531 } 532 533 /** 534 * Enable/disable motor safety for this device. 535 * <p> 536 * Turn on and off the motor safety option for this object. 537 * 538 * @param enabled True if motor safety is enforced for this object. 539 */ 540 public final void setSafetyEnabled(boolean enabled) { 541 m_motorSafetyLock.lock(); 542 try { 543 if (m_motorSafety == null && !enabled) { 544 /* 545 * Caller wants to disable MS, 546 * but MS features were nevere enabled, 547 * so it doesn't need to be disabled. 548 */ 549 } else { 550 /* MS will be created if it does not exist */ 551 GetMotorSafety().setSafetyEnabled(enabled); 552 } 553 } finally { 554 m_motorSafetyLock.unlock(); 555 } 556 } 557 558 /** 559 * Return the state of the motor safety enabled flag. 560 * <p> 561 * Return if the motor safety is currently enabled for this device. 562 * 563 * @return True if motor safety is enforced for this device 564 */ 565 public final boolean isSafetyEnabled() { 566 m_motorSafetyLock.lock(); 567 try { 568 if (m_motorSafety == null) { 569 /* MS features were never enabled. */ 570 return false; 571 } else { 572 return GetMotorSafety().isSafetyEnabled(); 573 } 574 } finally { 575 m_motorSafetyLock.unlock(); 576 } 577 } 578}