001/*----------------------------------------------------------------------------*/
002/* Copyright (c) FIRST 2008-2014. 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
008package edu.wpi.first.wpilibj;
009
010import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
011import edu.wpi.first.wpilibj.communication.UsageReporting;
012import edu.wpi.first.wpilibj.livewindow.LiveWindow;
013
014/**
015 * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control
016 * @see CANTalon CANTalon for CAN control of Talon SRX
017 */
018public class TalonSRX extends SafePWM implements SpeedController {
019
020    /**
021     * Common initialization code called by all constructors.
022     *
023     * Note that the TalonSRX uses the following bounds for PWM values. These values should work reasonably well for
024     * most controllers, but if users experience issues such as asymmetric behavior around
025     * the deadband or inability to saturate the controller in either direction, calibration is recommended.
026     * The calibration procedure can be found in the TalonSRX User Manual available from CTRE.
027     *
028     *   - 2.0004ms = full "forward"
029     *   - 1.52ms = the "high end" of the deadband range
030     *   - 1.50ms = center of the deadband range (off)
031     *   - 1.48ms = the "low end" of the deadband range
032     *   - .997ms = full "reverse"
033     */
034    protected void initTalonSRX() {
035        setBounds(2.004, 1.52, 1.50, 1.48, .997);
036        setPeriodMultiplier(PeriodMultiplier.k1X);
037        setRaw(m_centerPwm);
038                setZeroLatch();
039
040        LiveWindow.addActuator("TalonSRX", getChannel(), this);
041        UsageReporting.report(tResourceType.kResourceType_Talon, getChannel());
042    }
043
044    /**
045     * Constructor for a TalonSRX connected via PWM
046     *
047     * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are on-board, 10-19 are on the MXP port
048     */
049    public TalonSRX(final int channel) {
050        super(channel);
051        initTalonSRX();
052    }
053
054    /**
055     * Set the PWM value.
056     *
057     * @deprecated For compatibility with CANJaguar
058     *
059     * The PWM value is set using a range of -1.0 to 1.0, appropriately
060     * scaling the value for the FPGA.
061     *
062     * @param speed The speed to set.  Value should be between -1.0 and 1.0.
063     * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup().  If 0, update immediately.
064     */
065    public void set(double speed, byte syncGroup) {
066        setSpeed(speed);
067        Feed();
068    }
069
070    /**
071     * Set the PWM value.
072     *
073     * The PWM value is set using a range of -1.0 to 1.0, appropriately
074     * scaling the value for the FPGA.
075     *
076     * @param speed The speed value between -1.0 and 1.0 to set.
077     */
078    public void set(double speed) {
079        setSpeed(speed);
080        Feed();
081    }
082
083    /**
084     * Get the recently set value of the PWM.
085     *
086     * @return The most recently set value for the PWM between -1.0 and 1.0.
087     */
088    public double get() {
089        return getSpeed();
090    }
091
092    /**
093     * Write out the PID value as seen in the PIDOutput base object.
094     *
095     * @param output Write out the PWM value as was found in the PIDController
096     */
097    public void pidWrite(double output) {
098        set(output);
099    }
100}