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 * - Software PID loops running in the robot controller
007 * - LiveWindow/Test mode features
008 * - Motor Safety (auto-turn off of motor if Set stops getting called)
009 * - Single Parameter set that assumes a simple motor controller.
010 */
011package com.ctre.phoenix.motorcontrol.can;
012
013import com.ctre.phoenix.motorcontrol.ControlMode;
014import com.ctre.phoenix.motorcontrol.DemandType;
015import com.ctre.phoenix.motorcontrol.WPI_AutoFeedEnable;
016import com.ctre.phoenix.motorcontrol.WPI_MotorSafetyImplem;
017import com.ctre.phoenix.platform.DeviceType;
018import com.ctre.phoenix.platform.PlatformJNI;
019import com.ctre.phoenix.Logger;
020import com.ctre.phoenix.ErrorCode;
021import com.ctre.phoenix.WPI_CallbackHelper;
022
023import java.util.ArrayList;
024
025import edu.wpi.first.wpilibj.RobotController;
026import edu.wpi.first.wpilibj.motorcontrol.MotorController;
027import edu.wpi.first.util.sendable.SendableRegistry;
028import edu.wpi.first.wpilibj.DriverStation;
029import edu.wpi.first.util.sendable.Sendable;
030import edu.wpi.first.util.sendable.SendableBuilder;
031import edu.wpi.first.hal.FRCNetComm.tResourceType;
032import edu.wpi.first.hal.SimDevice.Direction;
033import edu.wpi.first.hal.HAL;
034import edu.wpi.first.hal.HALValue;
035import edu.wpi.first.hal.SimDevice;
036import edu.wpi.first.hal.SimDouble;
037import edu.wpi.first.hal.SimBoolean;
038import edu.wpi.first.wpilibj.simulation.CallbackStore;
039import edu.wpi.first.wpilibj.simulation.SimDeviceSim;
040import edu.wpi.first.hal.simulation.SimDeviceDataJNI;
041import edu.wpi.first.hal.simulation.SimValueCallback;
042import edu.wpi.first.hal.simulation.SimulatorJNI;
043import edu.wpi.first.hal.HAL.SimPeriodicBeforeCallback;
044
045/**
046 * VEX Victor SPX Motor Controller when used on CAN Bus.
047 */
048public class WPI_VictorSPX extends VictorSPX implements MotorController, Sendable, AutoCloseable {
049
050        private String _description;
051        private double _speed;
052
053        private SimDevice m_simMotor;
054        private SimDouble m_simPercOut;
055        private SimDouble m_simMotorOutputLeadVoltage;
056        private SimDouble m_simVbat;
057
058        // callbacks to register
059        private SimValueCallback onValueChangedCallback = new OnValueChangedCallback();
060        private Runnable onPeriodicCallback = new OnPeriodicCallback();
061
062        // returned registered callbacks
063        private ArrayList<CallbackStore> simValueChangedCallbacks = new ArrayList<CallbackStore>();
064        private SimPeriodicBeforeCallback simPeriodicCallback;
065
066        /**
067         * The default motor safety timeout IF calling application
068         * enables the feature.
069         */
070        public static final double kDefaultSafetyExpiration = 0.1;
071
072        /**
073         * Late-constructed motor safety, which ensures feature is off unless calling
074         * applications explicitly enables it.
075         */
076        private WPI_MotorSafetyImplem _motorSafety = null;
077        private final Object _lockMotorSaf = new Object();
078        private double _motSafeExpiration = kDefaultSafetyExpiration;
079
080        /**
081         * Constructor for motor controller
082         * @param deviceNumber device ID of motor controller
083         */
084        public WPI_VictorSPX(int deviceNumber) {
085                super(deviceNumber);
086                _description = "Victor SPX " + deviceNumber;
087
088                SendableRegistry.addLW(this, "Victor SPX ", deviceNumber);
089
090                m_simMotor = SimDevice.create("CANMotor:Victor SPX", deviceNumber);
091                if(m_simMotor != null){
092                        WPI_AutoFeedEnable.getInstance();
093                        simPeriodicCallback = HAL.registerSimPeriodicBeforeCallback(onPeriodicCallback);
094
095                        m_simPercOut = m_simMotor.createDouble("percentOutput", Direction.kOutput, 0);
096                        m_simMotorOutputLeadVoltage = m_simMotor.createDouble("motorOutputLeadVoltage", Direction.kOutput, 0);
097
098                        m_simVbat = m_simMotor.createDouble("busVoltage", Direction.kInput, 12.0);
099
100                        SimDeviceSim sim = new SimDeviceSim("CANMotor:Victor SPX");
101                        simValueChangedCallbacks.add(sim.registerValueChangedCallback(m_simVbat, onValueChangedCallback, true));
102                }
103        }
104
105    // ----- Auto-Closable ----- //
106    @Override 
107    public void close(){
108        SendableRegistry.remove(this);
109        if(m_simMotor != null) { 
110            m_simMotor.close();
111            m_simMotor = null;
112        }
113        super.DestroyObject(); //Destroy the device
114    }
115
116        // ----- Callbacks for Sim ----- //
117        private class OnValueChangedCallback implements SimValueCallback {
118                @Override
119                public void callback(String name, int handle, int direction, HALValue value) {
120                        String deviceName = SimDeviceDataJNI.getSimDeviceName(SimDeviceDataJNI.getSimValueDeviceHandle(handle));
121                        String physType = deviceName + ":" + name;
122                        PlatformJNI.JNI_SimSetPhysicsInput(DeviceType.VictorSPX.value, getDeviceID(),
123                                                                               physType, WPI_CallbackHelper.getRawValue(value));
124                }
125        }
126
127        private class OnPeriodicCallback implements Runnable {
128                @Override
129                public void run() {
130                        double value = 0;
131                        int err = 0;
132
133                        int deviceID = getDeviceID();
134
135                        value = PlatformJNI.JNI_SimGetPhysicsValue(DeviceType.VictorSPX.value, deviceID, "PercentOutput");
136                        err = PlatformJNI.JNI_SimGetLastError(DeviceType.VictorSPX.value, deviceID);
137                        if (err == 0) {
138                                m_simPercOut.set(value);
139                        }
140                        value = PlatformJNI.JNI_SimGetPhysicsValue(DeviceType.VictorSPX.value, deviceID, "MotorOutputLeadVoltage");
141                        err = PlatformJNI.JNI_SimGetLastError(DeviceType.VictorSPX.value, deviceID);
142                        if (err == 0) {
143                                m_simMotorOutputLeadVoltage.set(value);
144                        }
145                }
146        }
147
148        // ------ set/get routines for WPILIB interfaces ------//
149        /**
150         * Common interface for setting the speed of a simple speed controller.
151         *
152         * @param speed The speed to set.  Value should be between -1.0 and 1.0.
153         *                                                                      Value is also saved for Get().
154         */
155        @Override
156        public void set(double speed) {
157                _speed = speed;
158                set(ControlMode.PercentOutput, _speed);
159                feed();
160        }
161
162        /**
163         * Common interface for getting the current set speed of a speed controller.
164         *
165         * @return The current set speed. Value is between -1.0 and 1.0.
166         */
167        @Override
168        public double get() {
169                return _speed;
170        }
171
172        // ---------Intercept CTRE calls for motor safety ---------//
173        /**
174         * Sets the appropriate output on the talon, depending on the mode.
175         * @param mode The output mode to apply.
176         * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
177         * In Current mode, output value is in amperes.
178         * In Velocity mode, output value is in position change / 100ms.
179         * In Position mode, output value is in encoder ticks or an analog value,
180         *   depending on the sensor.
181         * In Follower mode, the output value is the integer device ID of the talon to
182         * duplicate.
183         *
184         * @param value The setpoint value, as described above.
185         *
186         *
187         *      Standard Driving Example:
188         *      _talonLeft.set(ControlMode.PercentOutput, leftJoy);
189         *      _talonRght.set(ControlMode.PercentOutput, rghtJoy);
190         */
191        public void set(ControlMode mode, double value) {
192                /* intercept the advanced Set and feed motor-safety */
193                super.set(mode, value);
194                feed();
195        }
196
197        /**
198         * @param mode Sets the appropriate output on the talon, depending on the mode.
199         * @param demand0 The output value to apply.
200         *      such as advanced feed forward and/or auxiliary close-looping in firmware.
201         * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
202         * In Current mode, output value is in amperes.
203         * In Velocity mode, output value is in position change / 100ms.
204         * In Position mode, output value is in encoder ticks or an analog value,
205         *   depending on the sensor. See
206         * In Follower mode, the output value is the integer device ID of the talon to
207         * duplicate.
208         *
209         * @param demand1Type The demand type for demand1.
210         * Neutral: Ignore demand1 and apply no change to the demand0 output.
211         * AuxPID: Use demand1 to set the target for the auxiliary PID 1.
212         * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
213         *       demand0 output.  In PercentOutput the demand0 output is the motor output,
214         *   and in closed-loop modes the demand0 output is the output of PID0.
215         * @param demand1 Supplmental output value.  Units match the set mode.
216         *
217         *
218         *  Arcade Drive Example:
219         *              _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
220         *              _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
221         *
222         *      Drive Straight Example:
223         *      Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
224         *              _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
225         *              _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
226         *
227         *      Drive Straight to a Distance Example:
228         *      Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
229         *              _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
230         *              _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
231         */
232        public void set(ControlMode mode, double demand0, DemandType demand1Type, double demand1){
233                /* intercept the advanced Set and feed motor-safety */
234                super.set(mode, demand0, demand1Type, demand1);
235                feed();
236        }
237
238        /**
239         * Sets the voltage output of the MotorController.  Compensates for the current bus
240         * voltage to ensure that the desired voltage is output even if the battery voltage is below
241         * 12V - highly useful when the voltage outputs are "meaningful" (e.g. they come from a
242         * feedforward calculation).
243         *
244         * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
245         * properly - unlike the ordinary set function, it is not "set it and forget it."
246         *
247         * @param outputVolts The voltage to output.
248         */
249        @Override
250        public void setVoltage(double outputVolts) {
251                if(super.isVoltageCompensationEnabled())
252                {
253                        com.ctre.phoenix.Logger.log(ErrorCode.DoubleVoltageCompensatingWPI, _description + ": setVoltage ");
254                }
255                set(outputVolts / RobotController.getBatteryVoltage());
256        }
257
258        // ----------------------- Invert routines -------------------//
259        /**
260         * Common interface for inverting direction of a speed controller.
261         *
262         * @param isInverted The state of inversion, true is inverted.
263         */
264        @Override
265        public void setInverted(boolean isInverted) {
266                super.setInverted(isInverted);
267        }
268
269        /**
270         * Common interface for returning the inversion state of a speed controller.
271         *
272         * @return The state of inversion, true is inverted.
273         */
274        @Override
275        public boolean getInverted() {
276                return super.getInverted();
277        }
278
279        // ----------------------- turn-motor-off routines-------------------//
280        /**
281         * Common interface for disabling a motor.
282         */
283        @Override
284        public void disable() {
285                neutralOutput();
286        }
287
288        /**
289         * Common interface to stop the motor until Set is called again.
290         */
291        @Override
292        public void stopMotor() {
293                neutralOutput();
294        }
295
296        // ---- Sendable -------//
297
298        /**
299         * Initialize sendable
300         * @param builder Base sendable to build on
301         */
302        @Override
303        public void initSendable(SendableBuilder builder) {
304                builder.setSmartDashboardType("Motor Controller");
305                builder.setActuator(true);
306                builder.setSafeState(this::stopMotor);
307                builder.addDoubleProperty("Value", this::get, this::set);
308        }
309
310        /**
311         * @return description of controller
312         */
313        public String getDescription() {
314                return _description;
315        }
316
317        /* ----- Motor Safety ----- */
318        /** caller must lock appropriately */
319        private WPI_MotorSafetyImplem GetMotorSafety() {
320                if (_motorSafety == null) {
321                        /* newly created MS object */
322                        _motorSafety = new WPI_MotorSafetyImplem(this, getDescription());
323                        /* apply the expiration timeout */
324                        _motorSafety.setExpiration(_motSafeExpiration);
325                }
326                return _motorSafety;
327        }
328        /**
329         * Feed the motor safety object.
330         *
331         * <p>Resets the timer on this object that is used to do the timeouts.
332         */
333        public void feed() {
334                synchronized (_lockMotorSaf) {
335                        if (_motorSafety == null) {
336                                /* do nothing, MS features were never enabled */
337                        } else {
338                                GetMotorSafety().feed();
339                        }
340                }
341        }
342
343        /**
344         * Set the expiration time for the corresponding motor safety object.
345         *
346         * @param expirationTime The timeout value in seconds.
347         */
348        public void setExpiration(double expirationTime) {
349                synchronized (_lockMotorSaf) {
350                        /* save the value for if/when we do create the MS object */
351                        _motSafeExpiration = expirationTime;
352                        /* apply it only if MS object exists */
353                        if (_motorSafety == null) {
354                                /* do nothing, MS features were never enabled */
355                        } else {
356                                /* this call will trigger creating a registered MS object */
357                                GetMotorSafety().setExpiration(_motSafeExpiration);
358                        }
359                }
360        }
361
362        /**
363         * Retrieve the timeout value for the corresponding motor safety object.
364         *
365         * @return the timeout value in seconds.
366         */
367        public double getExpiration() {
368                synchronized (_lockMotorSaf) {
369                        /* return the intended expiration time */
370                        return _motSafeExpiration;
371                }
372        }
373
374        /**
375         * Determine of the motor is still operating or has timed out.
376         *
377         * @return a true value if the motor is still operating normally and hasn't timed out.
378         */
379        public boolean isAlive() {
380                synchronized (_lockMotorSaf) {
381                        if (_motorSafety == null) {
382                                /* MC is alive - MS features were never enabled to neutral the MC. */
383                                return true;
384                        } else {
385                                return GetMotorSafety().isAlive();
386                        }
387                }
388        }
389
390        /**
391         * Enable/disable motor safety for this device.
392         *
393         * <p>Turn on and off the motor safety option for this PWM object.
394         *
395         * @param enabled True if motor safety is enforced for this object
396         */
397        public void setSafetyEnabled(boolean enabled) {
398                synchronized (_lockMotorSaf) {
399                        if (_motorSafety == null && !enabled) {
400                                /* Caller wants to disable MS,
401                                        but MS features were nevere enabled, 
402                                        so it doesn't need to be disabled. */
403                        } else {
404                                /* MS will be created if it does not exist */
405                                GetMotorSafety().setSafetyEnabled(enabled);
406                        }
407                }
408        }
409
410        /**
411         * Return the state of the motor safety enabled flag.
412         *
413         * <p>Return if the motor safety is currently enabled for this device.
414         *
415         * @return True if motor safety is enforced for this device
416         */
417        public boolean isSafetyEnabled() {
418                synchronized (_lockMotorSaf) {
419                        if (_motorSafety == null) {
420                                /* MS features were never enabled. */
421                                return false;
422                        } else {
423                                return GetMotorSafety().isSafetyEnabled();
424                        }
425                }
426        }
427}