blob: 71b1b0243e6466d03a2e30da782e718981f13ca0 [file] [log] [blame]
Brian Silvermanf7f267a2017-02-04 16:16:08 -08001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2008-2017. All Rights Reserved. */
3/* Open Source Software - may be modified and shared by FRC teams. The code */
4/* must be accompanied by the FIRST BSD license file in the root directory of */
5/* the project. */
6/*----------------------------------------------------------------------------*/
7
8#include "TalonSRX.h"
9
10#include "HAL/HAL.h"
11#include "LiveWindow/LiveWindow.h"
12
13using namespace frc;
14
15/**
16 * Construct a TalonSRX connected via PWM.
17 *
18 * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are
19 * on-board, 10-19 are on the MXP port
20 */
21TalonSRX::TalonSRX(int channel) : PWMSpeedController(channel) {
22 /* Note that the TalonSRX uses the following bounds for PWM values. These
23 * values should work reasonably well for most controllers, but if users
24 * experience issues such as asymmetric behavior around the deadband or
25 * inability to saturate the controller in either direction, calibration is
26 * recommended. The calibration procedure can be found in the TalonSRX User
27 * Manual available from Cross The Road Electronics.
28 * 2.004ms = full "forward"
29 * 1.52ms = the "high end" of the deadband range
30 * 1.50ms = center of the deadband range (off)
31 * 1.48ms = the "low end" of the deadband range
32 * 0.997ms = full "reverse"
33 */
34 SetBounds(2.004, 1.52, 1.50, 1.48, .997);
35 SetPeriodMultiplier(kPeriodMultiplier_1X);
36 SetSpeed(0.0);
37 SetZeroLatch();
38
39 HAL_Report(HALUsageReporting::kResourceType_TalonSRX, GetChannel());
40 LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this);
41}