001/*----------------------------------------------------------------------------*/
002/* Copyright (c) FIRST 2008-2017. 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.hal.FRCNetComm.tResourceType;
011import edu.wpi.first.wpilibj.hal.HAL;
012import edu.wpi.first.wpilibj.livewindow.LiveWindow;
013
014/**
015 * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control.
016 */
017public class TalonSRX extends PWMSpeedController {
018
019  /**
020   * Constructor for a TalonSRX connected via PWM.
021   *
022   * <p>Note that the TalonSRX uses the following bounds for PWM values. These values should work
023   * reasonably well for most controllers, but if users experience issues such as asymmetric
024   * behavior around the deadband or inability to saturate the controller in either direction,
025   * calibration is recommended. The calibration procedure can be found in the TalonSRX User Manual
026   * available from CTRE.
027   *
028   * <p>- 2.0004ms = full "forward" - 1.52ms = the "high end" of the deadband range - 1.50ms =
029   * center
030   * of the deadband range (off) - 1.48ms = the "low end" of the deadband range - .997ms = full
031   * "reverse"
032   *
033   * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are on-board, 10-19 are
034   *                on the MXP port
035   */
036  public TalonSRX(final int channel) {
037    super(channel);
038
039    setBounds(2.004, 1.52, 1.50, 1.48, .997);
040    setPeriodMultiplier(PeriodMultiplier.k1X);
041    setSpeed(0.0);
042    setZeroLatch();
043
044    LiveWindow.addActuator("TalonSRX", getChannel(), this);
045    HAL.report(tResourceType.kResourceType_TalonSRX, getChannel());
046  }
047}