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 005// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY 006 007package edu.wpi.first.wpilibj.motorcontrol; 008 009import edu.wpi.first.hal.FRCNetComm.tResourceType; 010import edu.wpi.first.hal.HAL; 011import edu.wpi.first.wpilibj.PWM; 012 013/** 014 * Cross the Road Electronics (CTRE) Talon SRX Motor Controller. 015 * 016 * <p>Note that the Talon SRX uses the following bounds for PWM values. These values should work 017 * reasonably well for most controllers, but if users experience issues such as asymmetric behavior 018 * around the deadband or inability to saturate the controller in either direction, calibration is 019 * recommended. The calibration procedure can be found in the Talon SRX User Manual available from 020 * Cross the Road Electronics (CTRE). 021 * 022 * <ul> 023 * <li>2.004ms = full "forward" 024 * <li>1.520ms = the "high end" of the deadband range 025 * <li>1.500ms = center of the deadband range (off) 026 * <li>1.480ms = the "low end" of the deadband range 027 * <li>0.997ms = full "reverse" 028 * </ul> 029 */ 030public class PWMTalonSRX extends PWMMotorController { 031 /** 032 * Constructor. 033 * 034 * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 035 * are on the MXP port 036 */ 037 @SuppressWarnings("this-escape") 038 public PWMTalonSRX(final int channel) { 039 super("PWMTalonSRX", channel); 040 041 m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997); 042 m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X); 043 m_pwm.setSpeed(0.0); 044 m_pwm.setZeroLatch(); 045 046 HAL.report(tResourceType.kResourceType_PWMTalonSRX, getChannel() + 1); 047 } 048}