001    /*----------------------------------------------------------------------------*/
002    /* Copyright (c) FIRST 2008-2012. All Rights Reserved.                        */
003    /* Open Source Software - may be modified and shared by FRC teams. The code   */
004    /* must be accompanied by the FIRST BSD license file in the root directory of */
005    /* the project.                                                               */
006    /*----------------------------------------------------------------------------*/
007    
008    package edu.wpi.first.wpilibj;
009    
010    import edu.wpi.first.wpilibj.communication.UsageReporting;
011    import edu.wpi.first.wpilibj.livewindow.LiveWindow;
012    import edu.wpi.first.wpilibj.parsing.IDeviceController;
013    
014    /**
015     * CTRE Talon Speed Controller
016     */
017    public class Talon extends SafePWM implements SpeedController, IDeviceController {
018    
019        /**
020         * Common initialization code called by all constructors.
021         *
022         * Note that the Talon uses the following bounds for PWM values. These values should work reasonably well for
023         * most controllers, but if users experience issues such as asymmetric behavior around
024         * the deadband or inability to saturate the controller in either direction, calibration is recommended.
025         * The calibration procedure can be found in the Talon User Manual available from CTRE.
026         * 
027         *   - 2.037ms = full "forward"
028         *   - 1.539ms = the "high end" of the deadband range
029         *   - 1.513ms = center of the deadband range (off)
030         *   - 1.487ms = the "low end" of the deadband range
031         *   - .989ms = full "reverse"
032         */
033        private void initTalon() {
034            setBounds(2.037, 1.539, 1.513, 1.487, .989);
035            setPeriodMultiplier(PeriodMultiplier.k2X);
036            setRaw(m_centerPwm);
037    
038            LiveWindow.addActuator("Talon", getModuleNumber(), getChannel(), this);
039            UsageReporting.report(UsageReporting.kResourceType_Talon, getChannel(), getModuleNumber()-1);
040        }
041    
042        /**
043         * Constructor that assumes the default digital module.
044         *
045         * @param channel The PWM channel on the digital module that the Victor is attached to.
046         */
047        public Talon(final int channel) {
048            super(channel);
049            initTalon();
050        }
051    
052        /**
053         * Constructor that specifies the digital module.
054         *
055         * @param slot The slot in the chassis that the digital module is plugged into.
056         * @param channel The PWM channel on the digital module that the Victor is attached to.
057         */
058        public Talon(final int slot, final int channel) {
059            super(slot, channel);
060            initTalon();
061        }
062    
063        /**
064         * Set the PWM value.
065         *
066         * @deprecated For compatibility with CANJaguar
067         *
068         * The PWM value is set using a range of -1.0 to 1.0, appropriately
069         * scaling the value for the FPGA.
070         *
071         * @param speed The speed to set.  Value should be between -1.0 and 1.0.
072         * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup().  If 0, update immediately.
073         */
074        public void set(double speed, byte syncGroup) {
075            setSpeed(speed);
076                    Feed();
077        }
078    
079        /**
080         * Set the PWM value.
081         *
082         * The PWM value is set using a range of -1.0 to 1.0, appropriately
083         * scaling the value for the FPGA.
084         *
085         * @param speed The speed value between -1.0 and 1.0 to set.
086         */
087        public void set(double speed) {
088            setSpeed(speed);
089                    Feed();
090        }
091    
092        /**
093         * Get the recently set value of the PWM.
094         *
095         * @return The most recently set value for the PWM between -1.0 and 1.0.
096         */
097        public double get() {
098            return getSpeed();
099        }
100    
101        /**
102         * Write out the PID value as seen in the PIDOutput base object.
103         *
104         * @param output Write out the PWM value as was found in the PIDController
105         */
106        public void pidWrite(double output) {
107            set(output);
108        }
109    }