blob: 07438c40c3c37e52bf0134a0a83502dc13e58339 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2008. All Rights Reserved.
3 */
4/* Open Source Software - may be modified and shared by FRC teams. The code */
5/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
6/*----------------------------------------------------------------------------*/
7
8#include "TalonSRX.h"
9
10#include "LiveWindow/LiveWindow.h"
11
12/**
13 * Construct a TalonSRX connected via PWM
14 * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are
15 * on-board, 10-19 are on the MXP port
16 */
17TalonSRX::TalonSRX(uint32_t channel) : SafePWM(channel) {
18 /* Note that the TalonSRX uses the following bounds for PWM values. These
19 * values should work reasonably well for most controllers, but if users
20 * experience issues such as asymmetric behavior around the deadband or
21 * inability to saturate the controller in either direction, calibration is
22 * recommended. The calibration procedure can be found in the TalonSRX User
23 * Manual available from Cross The Road Electronics.
24 * 2.004ms = full "forward"
25 * 1.52ms = the "high end" of the deadband range
26 * 1.50ms = center of the deadband range (off)
27 * 1.48ms = the "low end" of the deadband range
28 * 0.997ms = full "reverse"
29 */
30 SetBounds(2.004, 1.52, 1.50, 1.48, .997);
31 SetPeriodMultiplier(kPeriodMultiplier_1X);
32 SetRaw(m_centerPwm);
33 SetZeroLatch();
34
35 HALReport(HALUsageReporting::kResourceType_TalonSRX, GetChannel());
36 LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this);
37}
38
39/**
40 * Set the PWM value.
41 *
42 * The PWM value is set using a range of -1.0 to 1.0, appropriately
43 * scaling the value for the FPGA.
44 *
45 * @param speed The speed value between -1.0 and 1.0 to set.
46 * @param syncGroup Unused interface.
47 */
48void TalonSRX::Set(float speed, uint8_t syncGroup) { SetSpeed(speed); }
49
50/**
51 * Get the recently set value of the PWM.
52 *
53 * @return The most recently set value for the PWM between -1.0 and 1.0.
54 */
55float TalonSRX::Get() const { return GetSpeed(); }
56
57/**
58 * Common interface for disabling a motor.
59 */
60void TalonSRX::Disable() { SetRaw(kPwmDisabled); }
61
62/**
63* Common interface for inverting direction of a speed controller.
64* @param isInverted The state of inversion, true is inverted.
65*/
66void TalonSRX::SetInverted(bool isInverted) { m_isInverted = isInverted; }
67
68/**
69 * Common interface for the inverting direction of a speed controller.
70 *
71 * @return isInverted The state of inversion, true is inverted.
72 *
73 */
74bool TalonSRX::GetInverted() const { return m_isInverted; }
75
76/**
77 * Write out the PID value as seen in the PIDOutput base object.
78 *
79 * @param output Write out the PWM value as was found in the PIDController
80 */
81void TalonSRX::PIDWrite(float output) { Set(output); }