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