001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) FIRST 2008-2012. 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.communication.FRCNetworkCommunicationsLibrary.tResourceType; 011import edu.wpi.first.wpilibj.communication.UsageReporting; 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 SafePWM implements SpeedController { 018 019 /** 020 * Common initialization code called by all constructors. 021 * 022 * Note that the Talon uses the following bounds for PWM values. These values should work reasonably well for 023 * most controllers, but if users experience issues such as asymmetric behavior around 024 * the deadband or inability to saturate the controller in either direction, calibration is recommended. 025 * The calibration procedure can be found in the Talon User Manual available from CTRE. 026 * 027 * - 2.037ms = full "forward" 028 * - 1.539ms = the "high end" of the deadband range 029 * - 1.513ms = center of the deadband range (off) 030 * - 1.487ms = the "low end" of the deadband range 031 * - .989ms = full "reverse" 032 */ 033 private void initTalon() { 034 setBounds(2.037, 1.539, 1.513, 1.487, .989); 035 setPeriodMultiplier(PeriodMultiplier.k1X); 036 setRaw(m_centerPwm); 037 setZeroLatch(); 038 039 LiveWindow.addActuator("Talon", getChannel(), this); 040 UsageReporting.report(tResourceType.kResourceType_Talon, getChannel()); 041 } 042 043 /** 044 * Constructor for a Talon (original or Talon SR) 045 * 046 * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on the MXP port 047 */ 048 public Talon(final int channel) { 049 super(channel); 050 initTalon(); 051 } 052 053 /** 054 * Set the PWM value. 055 * 056 * @deprecated For compatibility with CANJaguar 057 * 058 * The PWM value is set using a range of -1.0 to 1.0, appropriately 059 * scaling the value for the FPGA. 060 * 061 * @param speed The speed to set. Value should be between -1.0 and 1.0. 062 * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately. 063 */ 064 public void set(double speed, byte syncGroup) { 065 setSpeed(speed); 066 Feed(); 067 } 068 069 /** 070 * Set the PWM value. 071 * 072 * The PWM value is set using a range of -1.0 to 1.0, appropriately 073 * scaling the value for the FPGA. 074 * 075 * @param speed The speed value between -1.0 and 1.0 to set. 076 */ 077 public void set(double speed) { 078 setSpeed(speed); 079 Feed(); 080 } 081 082 /** 083 * Get the recently set value of the PWM. 084 * 085 * @return The most recently set value for the PWM between -1.0 and 1.0. 086 */ 087 public double get() { 088 return getSpeed(); 089 } 090 091 /** 092 * Write out the PID value as seen in the PIDOutput base object. 093 * 094 * @param output Write out the PWM value as was found in the PIDController 095 */ 096 public void pidWrite(double output) { 097 set(output); 098 } 099}