001/** 002 * WPI Compliant motor controller class. 003 * WPILIB's object model requires many interfaces to be implemented to use 004 * the various features. 005 * This includes... 006 * - LiveWindow/Test mode features 007 * - getRotation2d/Gyro Interface 008 * - Simulation Hooks 009 */ 010 011package com.ctre.phoenix.sensors; 012 013import com.ctre.phoenix.motorcontrol.can.TalonSRX; 014import com.ctre.phoenix.platform.DeviceType; 015import com.ctre.phoenix.platform.PlatformJNI; 016import com.ctre.phoenix.sensors.PigeonIMU; 017import com.ctre.phoenix.WPI_CallbackHelper; 018 019import edu.wpi.first.wpilibj.DriverStation; 020import edu.wpi.first.util.sendable.Sendable; 021import edu.wpi.first.util.sendable.SendableBuilder; 022import edu.wpi.first.util.sendable.SendableRegistry; 023import edu.wpi.first.math.geometry.Rotation2d; 024import edu.wpi.first.wpilibj.interfaces.Gyro; 025 026import edu.wpi.first.hal.SimDevice.Direction; 027import edu.wpi.first.hal.HALValue; 028import edu.wpi.first.hal.SimDevice; 029import edu.wpi.first.hal.SimDouble; 030import edu.wpi.first.wpilibj.simulation.CallbackStore; 031import edu.wpi.first.wpilibj.simulation.SimDeviceSim; 032import edu.wpi.first.hal.simulation.SimDeviceDataJNI; 033import edu.wpi.first.hal.simulation.SimValueCallback; 034import edu.wpi.first.hal.simulation.SimulatorJNI; 035import edu.wpi.first.hal.HAL; 036import edu.wpi.first.hal.HAL.SimPeriodicBeforeCallback; 037 038import java.util.ArrayList; 039 040public class WPI_PigeonIMU extends PigeonIMU implements Sendable, Gyro { 041 042 private double[] _xyz_dps; //instance this so we don't alloc when getRate is called. 043 044 private SimDevice m_simPigeon; 045 private SimDouble m_simFusedHeading; 046 private SimDouble m_simRawHeading; 047 private DeviceType m_type; 048 049 // callbacks to register 050 private SimValueCallback onValueChangedCallback = new OnValueChangedCallback(); 051 private Runnable onPeriodicCallback = new OnPeriodicCallback(); 052 053 // returned registered callbacks 054 private ArrayList<CallbackStore> simValueChangedCallbacks = new ArrayList<CallbackStore>(); 055 private SimPeriodicBeforeCallback simPeriodicCallback; 056 057 /** 058 * Constructor for Pigeon IMU. 059 * @param deviceNumber device ID of Pigeon IMU 060 */ 061 public WPI_PigeonIMU(int deviceNumber) { 062 super(deviceNumber); 063 m_type = DeviceType.PigeonIMU; 064 SendableRegistry.addLW(this, "Pigeon IMU ", deviceNumber); 065 init(); 066 } 067 068 /** 069 * Construtor for WPI_PigeonIMU. 070 * 071 * @param talon The Talon SRX ribbon-cabled to Pigeon. 072 */ 073 public WPI_PigeonIMU(TalonSRX talon) { 074 super(talon); 075 m_type = DeviceType.RibbonPigeonIMU; 076 SendableRegistry.addLW(this, "Pigeon IMU ", talon.getDeviceID()); 077 init(); 078 } 079 080 private void init(){ 081 _xyz_dps = new double[3]; 082 083 m_simPigeon = SimDevice.create("CANGyro:Pigeon IMU", getDeviceID()); 084 if(m_simPigeon != null) { 085 simPeriodicCallback = HAL.registerSimPeriodicBeforeCallback(onPeriodicCallback); 086 087 m_simFusedHeading = m_simPigeon.createDouble("fusedHeading", Direction.kOutput, 0); 088 089 m_simRawHeading = m_simPigeon.createDouble("rawHeadingInput", Direction.kInput, 0); 090 091 SimDeviceSim sim = new SimDeviceSim("CANGyro:Pigeon IMU"); 092 simValueChangedCallbacks.add(sim.registerValueChangedCallback(m_simRawHeading, onValueChangedCallback, true)); 093 } 094 } 095 096 // ----- Auto-Closable, from Gyro ----- // 097 @Override 098 public void close(){ 099 SendableRegistry.remove(this); 100 if(m_simPigeon != null) { 101 m_simPigeon.close(); 102 m_simPigeon = null; 103 } 104 super.DestroyObject(); //Pigeon device, replace with super.close() once implemented 105 } 106 107 108 // ----- Callbacks for Sim ----- // 109 private class OnValueChangedCallback implements SimValueCallback { 110 @Override 111 public void callback(String name, int handle, int direction, HALValue value) { 112 String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle)); 113 String physType = deviceName + ":" + name; 114 PlatformJNI.JNI_SimSetPhysicsInput(m_type.value, getDeviceID(), 115 physType, WPI_CallbackHelper.getRawValue(value)); 116 } 117 } 118 119 private class OnPeriodicCallback implements Runnable { 120 @Override 121 public void run() { 122 double value = 0; 123 int err = 0; 124 125 int deviceID = getDeviceID(); 126 127 value = PlatformJNI.JNI_SimGetPhysicsValue(m_type.value, deviceID, "FusedHeading"); 128 err = PlatformJNI.JNI_SimGetLastError(m_type.value, deviceID); 129 if (err == 0) { 130 m_simFusedHeading.set(value); 131 } 132 value = PlatformJNI.JNI_SimGetPhysicsValue(m_type.value, deviceID, "HeadingRaw"); 133 err = PlatformJNI.JNI_SimGetLastError(m_type.value, deviceID); 134 if (err == 0) { 135 m_simRawHeading.set(value); 136 } 137 } 138 } 139 140 141 // ----- WPILib Gyro Interface ----- // 142 143 /** 144 * This function does nothing, it exists 145 * to satisfy the WPILib Gyro interface. 146 * 147 * Pigeon does calibration on boot and any 148 * one-time calibrations (like temperature) 149 * are done via Phoenix Tuner. 150 */ 151 public void calibrate(){} //Pigeon calibration is done on boot and one-time cals via Tuner 152 153 public void reset(){ 154 setFusedHeading(0); 155 } 156 157 public double getAngle(){ 158 //Negate since getAngle requires cw+ and Pigeon is ccw+ 159 return -getFusedHeading(); 160 } 161 162 public double getRate(){ 163 getRawGyro(_xyz_dps); 164 //Expected to return cw+ 165 return -_xyz_dps[2]; 166 } 167 168 public Rotation2d getRotation2d() { 169 //Rotation2d and Pigeon are both ccw+ 170 return Rotation2d.fromDegrees(getFusedHeading()); 171 } 172 173 // ----- Sendable ----- // 174 @Override 175 public void initSendable(SendableBuilder builder) { 176 builder.setSmartDashboardType("Pigeon IMU"); 177 builder.addDoubleProperty("Heading", this::getFusedHeading, null); 178 } 179}