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