Brian Silverman | 41cdd3e | 2019-01-19 19:48:58 -0800 | [diff] [blame^] | 1 | /*----------------------------------------------------------------------------*/ |
| 2 | /* Copyright (c) 2008-2018 FIRST. 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 "frc/PWMTalonSRX.h" |
| 9 | |
| 10 | #include <hal/HAL.h> |
| 11 | |
| 12 | using namespace frc; |
| 13 | |
| 14 | PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) { |
| 15 | /* Note that the PWMTalonSRX uses the following bounds for PWM values. These |
| 16 | * values should work reasonably well for most controllers, but if users |
| 17 | * experience issues such as asymmetric behavior around the deadband or |
| 18 | * inability to saturate the controller in either direction, calibration is |
| 19 | * recommended. The calibration procedure can be found in the TalonSRX User |
| 20 | * Manual available from Cross The Road Electronics. |
| 21 | * 2.004ms = full "forward" |
| 22 | * 1.52ms = the "high end" of the deadband range |
| 23 | * 1.50ms = center of the deadband range (off) |
| 24 | * 1.48ms = the "low end" of the deadband range |
| 25 | * 0.997ms = full "reverse" |
| 26 | */ |
| 27 | SetBounds(2.004, 1.52, 1.50, 1.48, .997); |
| 28 | SetPeriodMultiplier(kPeriodMultiplier_1X); |
| 29 | SetSpeed(0.0); |
| 30 | SetZeroLatch(); |
| 31 | |
| 32 | HAL_Report(HALUsageReporting::kResourceType_PWMTalonSRX, GetChannel()); |
| 33 | SetName("PWMTalonSRX", GetChannel()); |
| 34 | } |