001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj.motorcontrol;
006
007import edu.wpi.first.hal.FRCNetComm.tResourceType;
008import edu.wpi.first.hal.HAL;
009import edu.wpi.first.wpilibj.PWM;
010
011/**
012 * Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control.
013 *
014 * <p>Note that the TalonSRX uses the following bounds for PWM values. These values should work
015 * reasonably well for most controllers, but if users experience issues such as asymmetric behavior
016 * around the deadband or inability to saturate the controller in either direction, calibration is
017 * recommended. The calibration procedure can be found in the TalonSRX User Manual available from
018 * CTRE.
019 *
020 * <ul>
021 *   <li>2.004ms = full "forward"
022 *   <li>1.520ms = the "high end" of the deadband range
023 *   <li>1.500ms = center of the deadband range (off)
024 *   <li>1.480ms = the "low end" of the deadband range
025 *   <li>0.997ms = full "reverse"
026 * </ul>
027 */
028public class PWMTalonSRX extends PWMMotorController {
029  /**
030   * Constructor for a TalonSRX connected via PWM.
031   *
032   * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 are
033   *     on the MXP port
034   */
035  @SuppressWarnings("this-escape")
036  public PWMTalonSRX(final int channel) {
037    super("PWMTalonSRX", channel);
038
039    m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
040    m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
041    m_pwm.setSpeed(0.0);
042    m_pwm.setZeroLatch();
043
044    HAL.report(tResourceType.kResourceType_PWMTalonSRX, getChannel() + 1);
045  }
046}