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; 008 009import java.util.ArrayList; 010 011import com.ctre.phoenixpro.StatusSignalValue; 012import com.ctre.phoenixpro.hardware.core.CoreCANcoder; 013import com.ctre.phoenix6.jni.PlatformJNI; 014import com.ctre.phoenixpro.sim.DeviceType; 015import com.ctre.phoenixpro.wpiutils.AutoFeedEnable; 016import com.ctre.phoenixpro.wpiutils.CallbackHelper; 017 018import edu.wpi.first.hal.HAL; 019import edu.wpi.first.hal.HALValue; 020import edu.wpi.first.hal.SimDevice; 021import edu.wpi.first.hal.SimDouble; 022import edu.wpi.first.hal.HAL.SimPeriodicBeforeCallback; 023import edu.wpi.first.hal.SimDevice.Direction; 024import edu.wpi.first.hal.simulation.SimDeviceDataJNI; 025import edu.wpi.first.hal.simulation.SimValueCallback; 026import edu.wpi.first.util.sendable.Sendable; 027import edu.wpi.first.util.sendable.SendableBuilder; 028import edu.wpi.first.util.sendable.SendableRegistry; 029import edu.wpi.first.wpilibj.simulation.CallbackStore; 030import edu.wpi.first.wpilibj.simulation.SimDeviceSim; 031 032/** 033 * @deprecated Classes in the phoenixpro package will be removed in 2024. 034 * Users should instead use classes from the phoenix6 package. 035 */ 036@Deprecated(forRemoval = true) 037public class CANcoder extends CoreCANcoder implements Sendable, AutoCloseable { 038 /** 039 * The StatusSignalValue getters are copies so that calls 040 * to the WPI interface do not update any references 041 */ 042 private final StatusSignalValue<Double> m_positionGetter = getPosition().clone(); 043 044 private static final DeviceType kSimDeviceType = DeviceType.PRO_CANcoderType; 045 046 private SimDevice m_simCANCoder; 047 private SimDouble m_simSupplyVoltage; 048 private SimDouble m_simPosition; 049 private SimDouble m_simRawPosition; 050 private SimDouble m_simVelocity; 051 052 // callbacks to register 053 private final SimValueCallback m_onValueChangedCallback = new OnValueChangedCallback(); 054 private final Runnable m_onPeriodicCallback = new OnPeriodicCallback(); 055 056 // returned registered callbacks 057 private final ArrayList<CallbackStore> m_simValueChangedCallbacks = new ArrayList<CallbackStore>(); 058 private SimPeriodicBeforeCallback m_simPeriodicBeforeCallback = null; 059 060 /** 061 * Constructs a new CANcoder object. 062 * <p> 063 * Constructs the device using the default CAN bus for the system: 064 * <ul> 065 * <li>"rio" on roboRIO 066 * <li>"can0" on Linux 067 * <li>"*" on Windows 068 * </ul> 069 * 070 * @param deviceId ID of the device, as configured in Phoenix Tuner. 071 * 072 * @deprecated Classes in the phoenixpro package will be removed in 2024. 073 * Users should instead use classes from the phoenix6 package. 074 */ 075 @Deprecated(forRemoval = true) 076 public CANcoder(int deviceId) { 077 this(deviceId, ""); 078 } 079 080 /** 081 * Constructs a new CANcoder object. 082 * 083 * @param deviceId ID of the device, as configured in Phoenix Tuner. 084 * @param canbus Name of the CAN bus this device is on. Possible CAN bus 085 * strings are: 086 * <ul> 087 * <li>"rio" for the native roboRIO CAN bus 088 * <li>CANivore name or serial number 089 * <li>SocketCAN interface (non-FRC Linux only) 090 * <li>"*" for any CANivore seen by the program 091 * <li>empty string (default) to select the default for the 092 * system: 093 * <ul> 094 * <li>"rio" on roboRIO 095 * <li>"can0" on Linux 096 * <li>"*" on Windows 097 * </ul> 098 * </ul> 099 * 100 * @deprecated Classes in the phoenixpro package will be removed in 2024. 101 * Users should instead use classes from the phoenix6 package. 102 */ 103 @Deprecated(forRemoval = true) 104 public CANcoder(int deviceId, String canbus) { 105 super(deviceId, canbus); 106 SendableRegistry.addLW(this, "CANCoder (Pro) ", deviceId); 107 108 m_simCANCoder = SimDevice.create("CANEncoder:CANCoder (Pro)", deviceId); 109 if (m_simCANCoder != null) { 110 AutoFeedEnable.getInstance(); 111 m_simPeriodicBeforeCallback = HAL.registerSimPeriodicBeforeCallback(m_onPeriodicCallback); 112 113 m_simSupplyVoltage = m_simCANCoder.createDouble("supplyVoltage", Direction.kInput, 12.0); 114 115 m_simPosition = m_simCANCoder.createDouble("position", Direction.kOutput, 0); 116 117 m_simRawPosition = m_simCANCoder.createDouble("rawPositionInput", Direction.kInput, 0); 118 m_simVelocity = m_simCANCoder.createDouble("velocity", Direction.kInput, 0); 119 120 final SimDeviceSim sim = new SimDeviceSim("CANEncoder:CANCoder (Pro)"); 121 m_simValueChangedCallbacks 122 .add(sim.registerValueChangedCallback(m_simSupplyVoltage, m_onValueChangedCallback, true)); 123 m_simValueChangedCallbacks 124 .add(sim.registerValueChangedCallback(m_simRawPosition, m_onValueChangedCallback, true)); 125 m_simValueChangedCallbacks.add(sim.registerValueChangedCallback(m_simVelocity, m_onValueChangedCallback, true)); 126 } 127 } 128 129 // ----- Auto-Closable ----- // 130 @Override 131 public void close() { 132 SendableRegistry.remove(this); 133 if (m_simPeriodicBeforeCallback != null) { 134 m_simPeriodicBeforeCallback.close(); 135 m_simPeriodicBeforeCallback = null; 136 } 137 if (m_simCANCoder != null) { 138 m_simCANCoder.close(); 139 m_simCANCoder = null; 140 } 141 142 for (var callback : m_simValueChangedCallbacks) { 143 callback.close(); 144 } 145 m_simValueChangedCallbacks.clear(); 146 } 147 148 // ----- Callbacks for Sim ----- // 149 private class OnValueChangedCallback implements SimValueCallback { 150 @Override 151 public void callback(String name, int handle, int direction, HALValue value) { 152 String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle)); 153 String physType = deviceName + ":" + name; 154 PlatformJNI.JNI_SimSetPhysicsInput(kSimDeviceType.value, getDeviceID(), 155 physType, CallbackHelper.getRawValue(value)); 156 } 157 } 158 159 private class OnPeriodicCallback implements Runnable { 160 @Override 161 public void run() { 162 double value = 0; 163 int err = 0; 164 165 final int deviceID = getDeviceID(); 166 167 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "SupplyVoltage"); 168 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 169 if (err == 0) { 170 m_simSupplyVoltage.set(value); 171 } 172 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "Position"); 173 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 174 if (err == 0) { 175 m_simPosition.set(value); 176 } 177 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "RawPosition"); 178 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 179 if (err == 0) { 180 m_simRawPosition.set(value); 181 } 182 value = PlatformJNI.JNI_SimGetPhysicsValue(kSimDeviceType.value, deviceID, "Velocity"); 183 err = PlatformJNI.JNI_SimGetLastError(kSimDeviceType.value, deviceID); 184 if (err == 0) { 185 m_simVelocity.set(value); 186 } 187 } 188 } 189 190 // ----- Sendable ----- // 191 @Override 192 public void initSendable(SendableBuilder builder) { 193 builder.setSmartDashboardType("CANCoder"); 194 builder.addDoubleProperty("Position", m_positionGetter.asSupplier()::get, this::setPosition); 195 } 196}