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.Pigeon2;
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_Pigeon2 extends Pigeon2 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_simYaw;
046    private SimDouble m_simRawYaw;
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 2.
059     * @param deviceNumber device ID of Pigeon 2
060     * @param canbus Name of the CANbus; can be a CANivore device name or serial number.
061     *               Pass in nothing or "rio" to use the roboRIO.
062     */
063    public WPI_Pigeon2(int deviceNumber, String canbus) {
064        super(deviceNumber, canbus);
065        m_type = DeviceType.PigeonIMU;
066        SendableRegistry.addLW(this, "Pigeon 2 ", deviceNumber);
067        init();
068    }
069    /**
070     * Constructor for Pigeon 2.
071     * @param deviceNumber device ID of Pigeon 2
072     */
073    public WPI_Pigeon2(int deviceNumber) {
074        this(deviceNumber, "");
075    }
076
077    private void init(){
078        _xyz_dps = new double[3];
079
080        m_simPigeon = SimDevice.create("CANGyro:Pigeon 2", getDeviceID());
081        if(m_simPigeon != null) {
082            simPeriodicCallback = HAL.registerSimPeriodicBeforeCallback(onPeriodicCallback);
083
084            m_simYaw = m_simPigeon.createDouble("yaw", Direction.kOutput, 0);
085
086            m_simRawYaw = m_simPigeon.createDouble("rawYawInput", Direction.kInput, 0);
087
088            SimDeviceSim sim = new SimDeviceSim("CANGyro:Pigeon 2");
089            simValueChangedCallbacks.add(sim.registerValueChangedCallback(m_simRawYaw, onValueChangedCallback, true));
090        }
091    }
092
093    // ----- Auto-Closable, from Gyro ----- //
094    @Override
095    public void close(){
096        SendableRegistry.remove(this);
097        if(m_simPigeon != null) {
098            m_simPigeon.close();
099            m_simPigeon = null;
100        }
101        super.DestroyObject(); //Pigeon device, replace with super.close() once implemented
102    }
103
104
105    // ----- Callbacks for Sim ----- //
106    private class OnValueChangedCallback implements SimValueCallback {
107                @Override
108                public void callback(String name, int handle, int direction, HALValue value) {
109                        String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle));
110                        String physType = deviceName + ":" + name;
111                        PlatformJNI.JNI_SimSetPhysicsInput(m_type.value, getDeviceID(),
112                                                                               physType, WPI_CallbackHelper.getRawValue(value));
113                }
114        }
115
116        private class OnPeriodicCallback implements Runnable {
117                @Override
118                public void run() {
119                        double value = 0;
120                        int err = 0;
121
122                        int deviceID = getDeviceID();
123
124                        value = PlatformJNI.JNI_SimGetPhysicsValue(m_type.value, deviceID, "FusedHeading");
125                        err = PlatformJNI.JNI_SimGetLastError(m_type.value, deviceID);
126                        if (err == 0) {
127                                m_simYaw.set(value);
128                        }
129                        value = PlatformJNI.JNI_SimGetPhysicsValue(m_type.value, deviceID, "HeadingRaw");
130                        err = PlatformJNI.JNI_SimGetLastError(m_type.value, deviceID);
131                        if (err == 0) {
132                                m_simRawYaw.set(value);
133                        }
134                }
135        }
136
137
138    // ----- WPILib Gyro Interface ----- //
139
140    /**
141     * This function does nothing, it exists
142     * to satisfy the WPILib Gyro interface.
143     *
144     * Pigeon does calibration on boot and any
145     * one-time calibrations (like temperature)
146     * are done via Phoenix Tuner.
147     */
148    public void calibrate(){} //Pigeon calibration is done on boot and one-time cals via Tuner
149
150    public void reset(){
151        setYaw(0);
152    }
153
154    public double getAngle(){
155        //Negate since getAngle requires cw+ and Pigeon is ccw+
156        return -getYaw();
157    }
158
159    public double getRate(){
160        getRawGyro(_xyz_dps);
161        //Expected to return cw+
162        return -_xyz_dps[2];
163    }
164
165    public Rotation2d getRotation2d() {
166        //Rotation2d and Pigeon are both ccw+
167        return Rotation2d.fromDegrees(getYaw());
168    }
169
170    // ----- Sendable ----- //
171    @Override
172  public void initSendable(SendableBuilder builder) {
173    builder.setSmartDashboardType("Pigeon 2");
174    builder.addDoubleProperty("Heading", this::getYaw, null);
175  }
176}