blob: c18800c112e1579d4ba249a0695be80d41f66e0e [file] [log] [blame]
Brian Silverman890a32a2018-03-11 15:41:56 -07001#include "ctre/phoenix/MotorControl/CAN/TalonSRX.h"
2#include "ctre/phoenix/CCI/MotController_CCI.h"
3#include "HAL/HAL.h"
4
5using namespace ctre::phoenix;
6using namespace ctre::phoenix::motorcontrol::can;
7using namespace ctre::phoenix::motorcontrol;
8
9/**
10 * Constructor
11 * @param deviceNumber [0,62]
12 */
13TalonSRX::TalonSRX(int deviceNumber) :
14 BaseMotorController(deviceNumber | 0x02040000) {
15 HAL_Report(HALUsageReporting::kResourceType_CANTalonSRX, deviceNumber + 1);
16}
17/**
18 * Select the feedback device for the motor controller.
19 *
20 * @param feedbackDevice
21 * Feedback Device to select.
22 * @param pidIdx
23 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
24 * @param timeoutMs
25 * Timeout value in ms. If nonzero, function will wait for
26 * config success and report an error if it times out.
27 * If zero, no blocking or checking is performed.
28 * @return Error Code generated by function. 0 indicates no error.
29 */
30ctre::phoenix::ErrorCode TalonSRX::ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice,
31 int pidIdx, int timeoutMs) {
32 return BaseMotorController::ConfigSelectedFeedbackSensor(feedbackDevice,
33 pidIdx, timeoutMs);
34}
35/**
36 * Select the remote feedback device for the motor controller.
37 * Most CTRE CAN motor controllers will support remote sensors over CAN.
38 *
39 * @param feedbackDevice
40 * Remote Feedback Device to select.
41 * @param pidIdx
42 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
43 * @param timeoutMs
44 * Timeout value in ms. If nonzero, function will wait for
45 * config success and report an error if it times out.
46 * If zero, no blocking or checking is performed.
47 * @return Error Code generated by function. 0 indicates no error.
48 */
49ctre::phoenix::ErrorCode TalonSRX::ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice,
50 int pidIdx, int timeoutMs) {
51 return BaseMotorController::ConfigSelectedFeedbackSensor(feedbackDevice,
52 pidIdx, timeoutMs);
53}
54/**
55 * Sets the period of the given status frame.
56 *
57 * User ensure CAN Bus utilization is not high.
58 *
59 * This setting is not persistent and is lost when device is reset.
60 * If this is a concern, calling application can use HasReset()
61 * to determine if the status frame needs to be reconfigured.
62 *
63 * @param frame
64 * Frame whose period is to be changed.
65 * @param periodMs
66 * Period in ms for the given frame.
67 * @param timeoutMs
68 * Timeout value in ms. If nonzero, function will wait for
69 * config success and report an error if it times out.
70 * If zero, no blocking or checking is performed.
71 * @return Error Code generated by function. 0 indicates no error.
72 */
73ctre::phoenix::ErrorCode TalonSRX::SetStatusFramePeriod(StatusFrameEnhanced frame,
74 int periodMs, int timeoutMs) {
75 return BaseMotorController::SetStatusFramePeriod(frame, periodMs, timeoutMs);
76}
77/**
78 * Sets the period of the given status frame.
79 *
80 * User ensure CAN Bus utilization is not high.
81 *
82 * This setting is not persistent and is lost when device is reset.
83 * If this is a concern, calling application can use HasReset()
84 * to determine if the status frame needs to be reconfigured.
85 *
86 * @param frame
87 * Frame whose period is to be changed.
88 * @param periodMs
89 * Period in ms for the given frame.
90 * @param timeoutMs
91 * Timeout value in ms. If nonzero, function will wait for
92 * config success and report an error if it times out.
93 * If zero, no blocking or checking is performed.
94 * @return Error Code generated by function. 0 indicates no error.
95 */
96ctre::phoenix::ErrorCode TalonSRX::SetStatusFramePeriod(StatusFrame frame,
97 int periodMs, int timeoutMs) {
98 return BaseMotorController::SetStatusFramePeriod(frame, periodMs, timeoutMs);
99}
100/**
101 * Gets the period of the given status frame.
102 *
103 * @param frame
104 * Frame to get the period of.
105 * @param timeoutMs
106 * Timeout value in ms. If nonzero, function will wait for
107 * config success and report an error if it times out.
108 * If zero, no blocking or checking is performed.
109 * @return Period of the given status frame.
110 */
111int TalonSRX::GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs) {
112 return BaseMotorController::GetStatusFramePeriod(frame, timeoutMs);
113}
114/**
115 * Gets the period of the given status frame.
116 *
117 * @param frame
118 * Frame to get the period of.
119 * @param timeoutMs
120 * Timeout value in ms. If nonzero, function will wait for
121 * config success and report an error if it times out.
122 * If zero, no blocking or checking is performed.
123 * @return Period of the given status frame.
124 */
125int TalonSRX::GetStatusFramePeriod(StatusFrame frame, int timeoutMs) {
126 return BaseMotorController::GetStatusFramePeriod(frame, timeoutMs);
127}
128/**
129 * Configures the period of each velocity sample.
130 * Every 1ms a position value is sampled, and the delta between that sample
131 * and the position sampled kPeriod ms ago is inserted into a filter.
132 * kPeriod is configured with this function.
133 *
134 * @param period
135 * Desired period for the velocity measurement. @see
136 * #VelocityMeasPeriod
137 * @param timeoutMs
138 * Timeout value in ms. If nonzero, function will wait for
139 * config success and report an error if it times out.
140 * If zero, no blocking or checking is performed.
141 * @return Error Code generated by function. 0 indicates no error.
142 */
143ctre::phoenix::ErrorCode TalonSRX::ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period,
144 int timeoutMs) {
145 return BaseMotorController::ConfigVelocityMeasurementPeriod(period,
146 timeoutMs);
147}
148/**
149 * Sets the number of velocity samples used in the rolling average velocity
150 * measurement.
151 *
152 * @param windowSize
153 * Number of samples in the rolling average of velocity
154 * measurement. Valid values are 1,2,4,8,16,32. If another
155 * value is specified, it will truncate to nearest support value.
156 * @param timeoutMs
157 * Timeout value in ms. If nonzero, function will wait for
158 * config success and report an error if it times out.
159 * If zero, no blocking or checking is performed.
160 * @return Error Code generated by function. 0 indicates no error.
161 */
162ctre::phoenix::ErrorCode TalonSRX::ConfigVelocityMeasurementWindow(int windowSize,
163 int timeoutMs) {
164 return BaseMotorController::ConfigVelocityMeasurementWindow(windowSize,
165 timeoutMs);
166}
167/**
168 * Configures a limit switch for a local/remote source.
169 *
170 * For example, a CAN motor controller may need to monitor the Limit-R pin
171 * of another Talon, CANifier, or local Gadgeteer feedback connector.
172 *
173 * If the sensor is remote, a device ID of zero is assumed.
174 * If that's not desired, use the four parameter version of this function.
175 *
176 * @param limitSwitchSource
177 * Limit switch source.
178 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
179 * @param normalOpenOrClose
180 * Setting for normally open, normally closed, or disabled. This setting
181 * matches the web-based configuration drop down.
182 * @param timeoutMs
183 * Timeout value in ms. If nonzero, function will wait for
184 * config success and report an error if it times out.
185 * If zero, no blocking or checking is performed.
186 * @return Error Code generated by function. 0 indicates no error.
187 */
188ctre::phoenix::ErrorCode TalonSRX::ConfigForwardLimitSwitchSource(
189 LimitSwitchSource limitSwitchSource,
190 LimitSwitchNormal normalOpenOrClose, int timeoutMs) {
191
192 return BaseMotorController::ConfigForwardLimitSwitchSource(
193 limitSwitchSource, normalOpenOrClose, timeoutMs);
194}
195/**
196 * Configures a limit switch for a local/remote source.
197 *
198 * For example, a CAN motor controller may need to monitor the Limit-R pin
199 * of another Talon, CANifier, or local Gadgeteer feedback connector.
200 *
201 * If the sensor is remote, a device ID of zero is assumed.
202 * If that's not desired, use the four parameter version of this function.
203 *
204 * @param limitSwitchSource
205 * Limit switch source. @see #LimitSwitchSource
206 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
207 * @param normalOpenOrClose
208 * Setting for normally open, normally closed, or disabled. This setting
209 * matches the web-based configuration drop down.
210 * @param timeoutMs
211 * Timeout value in ms. If nonzero, function will wait for
212 * config success and report an error if it times out.
213 * If zero, no blocking or checking is performed.
214 * @return Error Code generated by function. 0 indicates no error.
215 */
216ctre::phoenix::ErrorCode TalonSRX::ConfigReverseLimitSwitchSource(
217 LimitSwitchSource limitSwitchSource,
218 LimitSwitchNormal normalOpenOrClose, int timeoutMs) {
219 return BaseMotorController::ConfigReverseLimitSwitchSource(
220 limitSwitchSource, normalOpenOrClose, timeoutMs);
221}
222/**
223 * Configures the forward limit switch for a remote source.
224 * For example, a CAN motor controller may need to monitor the Limit-F pin
225 * of another Talon or CANifier.
226 *
227 * @param limitSwitchSource
228 * Remote limit switch source.
229 * User can choose between a remote Talon SRX, CANifier, or deactivate the feature.
230 * @param normalOpenOrClose
231 * Setting for normally open, normally closed, or disabled. This setting
232 * matches the web-based configuration drop down.
233 * @param deviceID
234 * Device ID of remote source (Talon SRX or CANifier device ID).
235 * @param timeoutMs
236 * Timeout value in ms. If nonzero, function will wait for
237 * config success and report an error if it times out.
238 * If zero, no blocking or checking is performed.
239 * @return Error Code generated by function. 0 indicates no error.
240 */
241ctre::phoenix::ErrorCode TalonSRX::ConfigForwardLimitSwitchSource(
242 RemoteLimitSwitchSource limitSwitchSource,
243 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs) {
244
245 return BaseMotorController::ConfigForwardLimitSwitchSource(
246 limitSwitchSource, normalOpenOrClose, deviceID, timeoutMs);
247}
248/**
249 * Configures the reverse limit switch for a remote source.
250 * For example, a CAN motor controller may need to monitor the Limit-R pin
251 * of another Talon or CANifier.
252 *
253 * @param limitSwitchSource
254 * Remote limit switch source.
255 * User can choose between a remote Talon SRX, CANifier, or deactivate the feature.
256 * @param normalOpenOrClose
257 * Setting for normally open, normally closed, or disabled. This setting
258 * matches the web-based configuration drop down.
259 * @param deviceID
260 * Device ID of remote source (Talon SRX or CANifier device ID).
261 * @param timeoutMs
262 * Timeout value in ms. If nonzero, function will wait for
263 * config success and report an error if it times out.
264 * If zero, no blocking or checking is performed.
265 * @return Error Code generated by function. 0 indicates no error.
266 */
267ctre::phoenix::ErrorCode TalonSRX::ConfigReverseLimitSwitchSource(
268 RemoteLimitSwitchSource limitSwitchSource,
269 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs) {
270
271 return BaseMotorController::ConfigReverseLimitSwitchSource(
272 limitSwitchSource, normalOpenOrClose, deviceID, timeoutMs);
273}
274
275//------ Current Lim ----------//
276/**
277 * Configure the peak allowable current (when current limit is enabled).
278 *
279 * Current limit is activated when current exceeds the peak limit for longer than the peak duration.
280 * Then software will limit to the continuous limit.
281 * This ensures current limiting while allowing for momentary excess current events.
282 *
283 * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit()
284 * and set the peak to zero: ConfigPeakCurrentLimit(0).
285 *
286 * @param amps Amperes to limit.
287 * @param timeoutMs
288 * Timeout value in ms. If nonzero, function will wait for
289 * config success and report an error if it times out.
290 * If zero, no blocking or checking is performed.
291 */
292ctre::phoenix::ErrorCode TalonSRX::ConfigPeakCurrentLimit(int amps, int timeoutMs) {
293 return c_MotController_ConfigPeakCurrentLimit(m_handle, amps, timeoutMs);
294}
295/**
296 * Configure the peak allowable duration (when current limit is enabled).
297 *
298 * Current limit is activated when current exceeds the peak limit for longer than the peak duration.
299 * Then software will limit to the continuous limit.
300 * This ensures current limiting while allowing for momentary excess current events.
301 *
302 * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit()
303 * and set the peak to zero: ConfigPeakCurrentLimit(0).
304 *
305 * @param milliseconds How long to allow current-draw past peak limit.
306 * @param timeoutMs
307 * Timeout value in ms. If nonzero, function will wait for
308 * config success and report an error if it times out.
309 * If zero, no blocking or checking is performed.
310 */
311ctre::phoenix::ErrorCode TalonSRX::ConfigPeakCurrentDuration(int milliseconds, int timeoutMs) {
312 return c_MotController_ConfigPeakCurrentDuration(m_handle, milliseconds,
313 timeoutMs);
314}
315/**
316 * Configure the continuous allowable current-draw (when current limit is enabled).
317 *
318 * Current limit is activated when current exceeds the peak limit for longer than the peak duration.
319 * Then software will limit to the continuous limit.
320 * This ensures current limiting while allowing for momentary excess current events.
321 *
322 * For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit()
323 * and set the peak to zero: ConfigPeakCurrentLimit(0).
324 *
325 * @param amps Amperes to limit.
326 * @param timeoutMs
327 * Timeout value in ms. If nonzero, function will wait for
328 * config success and report an error if it times out.
329 * If zero, no blocking or checking is performed.
330 */
331ctre::phoenix::ErrorCode TalonSRX::ConfigContinuousCurrentLimit(int amps, int timeoutMs) {
332 return c_MotController_ConfigContinuousCurrentLimit(m_handle, amps, timeoutMs);
333}
334/**
335 * Enable or disable Current Limit.
336 * @param enable
337 * Enable state of current limit.
338 * @see ConfigPeakCurrentLimit, ConfigPeakCurrentDuration, ConfigContinuousCurrentLimit
339 */
340void TalonSRX::EnableCurrentLimit(bool enable) {
341 c_MotController_EnableCurrentLimit(m_handle, enable);
342}
343