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 and Talon SR Speed Controller. 015 */ 016public class Talon extends PWMSpeedController { 017 /** 018 * Constructor for a Talon (original or Talon SR). 019 * 020 * <p>Note that the Talon 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 Talon User Manual 024 * available from CTRE. 025 * 026 * <p>- 2.037ms = full "forward" - 1.539ms = the "high end" of the deadband range - 1.513ms = 027 * center of the deadband range (off) - 1.487ms = the "low end" of the deadband range - .989ms 028 * = full "reverse" 029 * 030 * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on 031 * the MXP port 032 */ 033 public Talon(final int channel) { 034 super(channel); 035 036 setBounds(2.037, 1.539, 1.513, 1.487, .989); 037 setPeriodMultiplier(PeriodMultiplier.k1X); 038 setSpeed(0.0); 039 setZeroLatch(); 040 041 HAL.report(tResourceType.kResourceType_Talon, getChannel()); 042 setName("Talon", getChannel()); 043 } 044}