blob: 2f6198d4ba48480cb41d9cb641f6532d95b667ba [file] [log] [blame]
Brian Silverman1a675112016-02-20 20:42:49 -05001/**
2 * @brief CAN TALON SRX driver.
3 *
4 * The TALON SRX is designed to instrument all runtime signals periodically.
5 * The default periods are chosen to support 16 TALONs with 10ms update rate
6 * for control (throttle or setpoint). However these can be overridden with
7 * SetStatusFrameRate. @see SetStatusFrameRate
8 * The getters for these unsolicited signals are auto generated at the bottom
9 * of this module.
10 *
11 * Likewise most control signals are sent periodically using the fire-and-forget
12 * CAN API. The setters for these unsolicited signals are auto generated at the
13 * bottom of this module.
14 *
15 * Signals that are not available in an unsolicited fashion are the Close Loop
16 * gains. For teams that have a single profile for their TALON close loop they
17 * can use either the webpage to configure their TALONs once or set the PIDF,
18 * Izone, CloseLoopRampRate, etc... once in the robot application. These
19 * parameters are saved to flash so once they are loaded in the TALON, they
20 * will persist through power cycles and mode changes.
21 *
22 * For teams that have one or two profiles to switch between, they can use the
23 * same strategy since there are two slots to choose from and the
24 * ProfileSlotSelect is periodically sent in the 10 ms control frame.
25 *
26 * For teams that require changing gains frequently, they can use the soliciting
27 * API to get and set those parameters. Most likely they will only need to set
28 * them in a periodic fashion as a function of what motion the application is
29 * attempting. If this API is used, be mindful of the CAN utilization reported
30 * in the driver station.
31 *
32 * If calling application has used the config routines to configure the
33 * selected feedback sensor, then all positions are measured in floating point
34 * precision rotations. All sensor velocities are specified in floating point
35 * precision RPM.
36 * @see ConfigPotentiometerTurns
37 * @see ConfigEncoderCodesPerRev
38 * HOWEVER, if calling application has not called the config routine for
39 * selected feedback sensor, then all getters/setters for position/velocity use
40 * the native engineering units of the Talon SRX firm (just like in 2015).
41 * Signals explained below.
42 *
43 * Encoder position is measured in encoder edges. Every edge is counted
44 * (similar to roboRIO 4X mode). Analog position is 10 bits, meaning 1024
45 * ticks per rotation (0V => 3.3V). Use SetFeedbackDeviceSelect to select
46 * which sensor type you need. Once you do that you can use GetSensorPosition()
47 * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by
48 * default). If a relative sensor is selected, you can zero (or change the
49 * current value) using SetSensorPosition.
50 *
51 * Analog Input and quadrature position (and velocity) are also explicitly
52 * reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
53 * These signals are available all the time, regardless of what sensor is
54 * selected at a rate of 100ms. This allows easy instrumentation for "in the
55 * pits" checking of all sensors regardless of modeselect. The 100ms rate is
56 * overridable for teams who want to acquire sensor data for processing, not
57 * just instrumentation. Or just select the sensor using
58 * SetFeedbackDeviceSelect to get it at 20ms.
59 *
60 * Velocity is in position ticks / 100ms.
61 *
62 * All output units are in respect to duty cycle (throttle) which is -1023(full
63 * reverse) to +1023 (full forward). This includes demand (which specifies
64 * duty cycle when in duty cycle mode) and rampRamp, which is in throttle units
65 * per 10ms (if nonzero).
66 *
67 * Pos and velocity close loops are calc'd as
68 * err = target - posOrVel.
69 * iErr += err;
70 * if( (IZone!=0) and abs(err) > IZone)
71 * ClearIaccum()
72 * output = P X err + I X iErr + D X dErr + F X target
73 * dErr = err - lastErr
74 * P, I, and D gains are always positive. F can be negative.
75 * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if
76 * sensor and motor are out of phase. Similarly feedback sensor can also be
77 * reversed (multiplied by -1) if you prefer the sensor to be inverted.
78 *
79 * P gain is specified in throttle per error tick. For example, a value of 102
80 * is ~9.9% (which is 102/1023) throttle per 1 ADC unit(10bit) or 1 quadrature
81 * encoder edge depending on selected sensor.
82 *
83 * I gain is specified in throttle per integrated error. For example, a value
84 * of 10 equates to ~0.99% (which is 10/1023) for each accumulated ADC unit
85 * (10 bit) or 1 quadrature encoder edge depending on selected sensor.
86 * Close loop and integral accumulator runs every 1ms.
87 *
88 * D gain is specified in throttle per derivative error. For example a value of
89 * 102 equates to ~9.9% (which is 102/1023) per change of 1 unit (ADC or
90 * encoder) per ms.
91 *
92 * I Zone is specified in the same units as sensor position (ADC units or
93 * quadrature edges). If pos/vel error is outside of this value, the
94 * integrated error will auto-clear...
95 * if( (IZone!=0) and abs(err) > IZone)
96 * ClearIaccum()
97 * ...this is very useful in preventing integral windup and is highly
98 * recommended if using full PID to keep stability low.
99 *
100 * CloseLoopRampRate is in throttle units per 1ms. Set to zero to disable
101 * ramping. Works the same as RampThrottle but only is in effect when a close
102 * loop mode and profile slot is selected.
103 *
104 * auto generated using spreadsheet and wpiclassgen.py
105 * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
106 */
107#include "HAL/CanTalonSRX.h"
108#include "FRC_NetworkCommunication/CANSessionMux.h" //CAN Comm
109#include <string.h> // memset
110#include <unistd.h> // usleep
111
112#define STATUS_1 0x02041400
113#define STATUS_2 0x02041440
114#define STATUS_3 0x02041480
115#define STATUS_4 0x020414C0
116#define STATUS_5 0x02041500
117#define STATUS_6 0x02041540
118#define STATUS_7 0x02041580
119#define STATUS_8 0x020415C0
120#define STATUS_9 0x02041600
121
122#define CONTROL_1 0x02040000
123#define CONTROL_2 0x02040040
124#define CONTROL_3 0x02040080
125#define CONTROL_5 0x02040100
126#define CONTROL_6 0x02040140
127
128#define EXPECTED_RESPONSE_TIMEOUT_MS (200)
129#define GET_STATUS1() \
130 CtreCanNode::recMsg<TALON_Status_1_General_10ms_t> rx = \
131 GetRx<TALON_Status_1_General_10ms_t>(STATUS_1 | GetDeviceNumber(), \
132 EXPECTED_RESPONSE_TIMEOUT_MS)
133#define GET_STATUS2() \
134 CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t> rx = \
135 GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2 | GetDeviceNumber(), \
136 EXPECTED_RESPONSE_TIMEOUT_MS)
137#define GET_STATUS3() \
138 CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t> rx = \
139 GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3 | GetDeviceNumber(), \
140 EXPECTED_RESPONSE_TIMEOUT_MS)
141#define GET_STATUS4() \
142 CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx = \
143 GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), \
144 EXPECTED_RESPONSE_TIMEOUT_MS)
145#define GET_STATUS5() \
146 CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t> rx = \
147 GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5 | GetDeviceNumber(), \
148 EXPECTED_RESPONSE_TIMEOUT_MS)
149#define GET_STATUS6() \
150 CtreCanNode::recMsg<TALON_Status_6_Eol_t> rx = GetRx<TALON_Status_6_Eol_t>( \
151 STATUS_6 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
152#define GET_STATUS7() \
153 CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t> rx = \
154 GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7 | GetDeviceNumber(), \
155 EXPECTED_RESPONSE_TIMEOUT_MS)
156#define GET_STATUS8() \
157 CtreCanNode::recMsg<TALON_Status_8_PulseWid_100ms_t> rx = \
158 GetRx<TALON_Status_8_PulseWid_100ms_t>(STATUS_8 | GetDeviceNumber(), \
159 EXPECTED_RESPONSE_TIMEOUT_MS)
160#define GET_STATUS9() \
161 CtreCanNode::recMsg<TALON_Status_9_MotProfBuffer_100ms_t> rx = \
162 GetRx<TALON_Status_9_MotProfBuffer_100ms_t>( \
163 STATUS_9 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
164
165#define PARAM_REQUEST 0x02041800
166#define PARAM_RESPONSE 0x02041840
167#define PARAM_SET 0x02041880
168
169const int kParamArbIdValue = PARAM_RESPONSE;
170const int kParamArbIdMask = 0xFFFFFFFF;
171
172const double FLOAT_TO_FXP_10_22 = (double)0x400000;
173const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625;
174
175const double FLOAT_TO_FXP_0_8 = (double)0x100;
176const double FXP_TO_FLOAT_0_8 = 0.00390625;
177
178CanTalonSRX::CanTalonSRX(int deviceNumber, int controlPeriodMs,
179 int enablePeriodMs)
180 : CtreCanNode(deviceNumber), _can_h(0), _can_stat(0) {
181 _controlPeriodMs = controlPeriodMs;
182 _enablePeriodMs = enablePeriodMs;
183
184 /* bound period to be within [1 ms,95 ms] */
185 if (_controlPeriodMs < 1)
186 _controlPeriodMs = 1;
187 else if (_controlPeriodMs > 95)
188 _controlPeriodMs = 95;
189 if (_enablePeriodMs < 1)
190 _enablePeriodMs = 1;
191 else if (_enablePeriodMs > 95)
192 _enablePeriodMs = 95;
193
194 RegisterRx(STATUS_1 | (UINT8)deviceNumber);
195 RegisterRx(STATUS_2 | (UINT8)deviceNumber);
196 RegisterRx(STATUS_3 | (UINT8)deviceNumber);
197 RegisterRx(STATUS_4 | (UINT8)deviceNumber);
198 RegisterRx(STATUS_5 | (UINT8)deviceNumber);
199 RegisterRx(STATUS_6 | (UINT8)deviceNumber);
200 RegisterRx(STATUS_7 | (UINT8)deviceNumber);
201 /* use the legacy command frame until we have evidence we can use the new
202 * frame.
203 */
204 RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)_controlPeriodMs);
205 _controlFrameArbId = CONTROL_1;
206 /* the only default param that is nonzero is limit switch.
207 * Default to using the flash settings.
208 */
209 SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);
210 /* Check if we can upgrade the control framing */
211 UpdateControlId();
212}
213/* CanTalonSRX D'tor
214 */
215CanTalonSRX::~CanTalonSRX() {
216 if (m_hasBeenMoved) {
217 /* Another CANTalonSRX still exists, so don't un-register the periodic
218 * control frame
219 */
220 } else {
221 /* un-register the control frame so Talon is disabled */
222 RegisterTx(CONTROL_1 | (UINT8)GetDeviceNumber(), 0);
223 RegisterTx(CONTROL_5 | (UINT8)GetDeviceNumber(), 0);
224 }
225 /* free the stream we used for SetParam/GetParamResponse */
226 if (_can_h) {
227 FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);
228 _can_h = 0;
229 }
230}
231/**
232 * @return true if Talon is reporting that it supports control5, and therefore
233 * RIO can send control5 to update control params (even when disabled).
234 */
235bool CanTalonSRX::IsControl5Supported() {
236 /* only bother to poll status2 if we are looking for cmd5allowed */
237 GET_STATUS2();
238 if (rx.err != CTR_OKAY) {
239 /* haven't received it */
240 return false;
241 } else if (0 == rx->Cmd5Allowed) {
242 /* firmware doesn't support it */
243 return false;
244 }
245 /* we can use control5, this gives application the ability to set control
246 * params prior to Talon-enable */
247 return true;
248}
249/**
250 * Get a copy of the control frame to send.
251 * @param [out] pointer to eight byte array to fill.
252 */
253void CanTalonSRX::GetControlFrameCopy(uint8_t *toFill) {
254 /* get the copy of the control frame in control1 */
255 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> task =
256 GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId |
257 GetDeviceNumber());
258 /* control1's payload will move to 5, but update the new sigs in control5 */
259 if (task.IsEmpty())
260 memset(toFill, 0, 8);
261 else
262 memcpy(toFill, task.toSend, 8);
263 /* zero first two bytes - these are reserved. */
264 toFill[0] = 0;
265 toFill[1] = 0;
266}
267/**
268 * Called in various places to double check we are using the best control frame.
269 * If the Talon firmware is too old, use control 1 framing, which does not allow
270 * setting
271 * control signals until robot is enabled. If Talon firmware can suport
272 * control5, use that
273 * since that frame can be transmitted during robot-disable. If calling
274 * application
275 * uses setParam to set the signal eLegacyControlMode, caller can force using
276 * control1
277 * if needed for some reason.
278 */
279void CanTalonSRX::UpdateControlId() {
280 uint8_t work[8];
281 uint32_t frameToUse;
282 /* deduce if we should change IDs. If firm supports the new frame, and
283 * calling app isn't forcing legacy mode
284 * use control5.*/
285 if (_useControl5ifSupported && IsControl5Supported()) {
286 frameToUse = CONTROL_5;
287 } else {
288 frameToUse = CONTROL_1;
289 }
290 /* is there anything to do */
291 if (frameToUse == _controlFrameArbId) {
292 /* nothing to do, we are using the best frame. */
293 } else if (frameToUse == CONTROL_5) {
294 /* get a copy of the control frame */
295 GetControlFrameCopy(work);
296 /* Change control1's DLC to 2. Passing nullptr means all payload bytes are
297 * zero. */
298 RegisterTx(CONTROL_1 | GetDeviceNumber(), _enablePeriodMs, 2, nullptr);
299 /* reregister the control frame using the new ID */
300 RegisterTx(frameToUse | GetDeviceNumber(), _controlPeriodMs, 8, work);
301 /* save the correct frame ArbID */
302 _controlFrameArbId = frameToUse;
303 } else if (frameToUse == CONTROL_1) {
304 GetControlFrameCopy(work);
305 /* stop sending control 5 */
306 UnregisterTx(CONTROL_5 | GetDeviceNumber());
307 /* reregister the control frame using the new ID */
308 RegisterTx(frameToUse | GetDeviceNumber(), _controlPeriodMs, 8, work);
309 /* save the correct frame ArbID */
310 _controlFrameArbId = frameToUse;
311 }
312}
313void CanTalonSRX::OpenSessionIfNeedBe() {
314 _can_stat = 0;
315 if (_can_h == 0) {
316 /* bit30 - bit8 must match $000002XX. Top bit is not masked to get remote
317 * frames */
318 FRC_NetworkCommunication_CANSessionMux_openStreamSession(
319 &_can_h, kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask,
320 kMsgCapacity, &_can_stat);
321 if (_can_stat == 0) {
322 /* success */
323 } else {
324 /* something went wrong, try again later */
325 _can_h = 0;
326 }
327 }
328}
329void CanTalonSRX::ProcessStreamMessages() {
330 if (0 == _can_h) OpenSessionIfNeedBe();
331 /* process receive messages */
332 uint32_t i;
333 uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);
334 uint32_t messagesRead = 0;
335 /* read out latest bunch of messages */
336 _can_stat = 0;
337 if (_can_h) {
338 FRC_NetworkCommunication_CANSessionMux_readStreamSession(
339 _can_h, _msgBuff, messagesToRead, &messagesRead, &_can_stat);
340 }
341 /* loop thru each message of interest */
342 for (i = 0; i < messagesRead; ++i) {
343 tCANStreamMessage *msg = _msgBuff + i;
344 if (msg->messageID == (PARAM_RESPONSE | GetDeviceNumber())) {
345 TALON_Param_Response_t *paramResp = (TALON_Param_Response_t *)msg->data;
346 /* decode value */
347 int32_t val = paramResp->ParamValueH;
348 val <<= 8;
349 val |= paramResp->ParamValueMH;
350 val <<= 8;
351 val |= paramResp->ParamValueML;
352 val <<= 8;
353 val |= paramResp->ParamValueL;
354 /* save latest signal */
355 _sigs[paramResp->ParamEnum] = val;
356 } else {
357 int brkpthere = 42;
358 ++brkpthere;
359 }
360 }
361}
362void CanTalonSRX::Set(double value) {
363 if (value > 1)
364 value = 1;
365 else if (value < -1)
366 value = -1;
367 SetDemand(1023 * value); /* must be within [-1023,1023] */
368}
369/*---------------------setters and getters that use the param
370 * request/response-------------*/
371/**
372 * Send a one shot frame to set an arbitrary signal.
373 * Most signals are in the control frame so avoid using this API unless you have
374 * to.
375 * Use this api for...
376 * -A motor controller profile signal eProfileParam_XXXs. These are backed up
377 * in flash. If you are gain-scheduling then call this periodically.
378 * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this,
379 * use the override signals in the control frame.
380 * Talon will automatically send a PARAM_RESPONSE after the set, so
381 * GetParamResponse will catch the latest value after a couple ms.
382 */
383CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits) {
384 /* caller is using param API. Open session if it hasn'T been done. */
385 if (0 == _can_h) OpenSessionIfNeedBe();
386 TALON_Param_Response_t frame;
387 memset(&frame, 0, sizeof(frame));
388 frame.ParamEnum = paramEnum;
389 frame.ParamValueH = rawBits >> 0x18;
390 frame.ParamValueMH = rawBits >> 0x10;
391 frame.ParamValueML = rawBits >> 0x08;
392 frame.ParamValueL = rawBits;
393 int32_t status = 0;
394 FRC_NetworkCommunication_CANSessionMux_sendMessage(
395 PARAM_SET | GetDeviceNumber(), (const uint8_t *)&frame, 5, 0, &status);
396 /* small hook here if we want the API itself to react to set commands */
397 switch (paramEnum) {
398 case eLegacyControlMode:
399 if (rawBits != 0) {
400 /* caller wants to force legacy framing */
401 _useControl5ifSupported = false;
402 } else {
403 /* caller wants to let the API decide */
404 _useControl5ifSupported = true;
405 }
406 /* recheck IDs now that flag has changed */
407 UpdateControlId();
408 break;
409 }
410 /* for now have a general failure if we can't transmit */
411 if (status) return CTR_TxFailed;
412 return CTR_OKAY;
413}
414/**
415 * Checks cached CAN frames and updating solicited signals.
416 */
417CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int &rawBits) {
418 CTR_Code retval = CTR_OKAY;
419 /* process received param events. We don't expect many since this API is not
420 * used often. */
421 ProcessStreamMessages();
422 /* grab the solicited signal value */
423 sigs_t::iterator i = _sigs.find(paramEnum);
424 if (i == _sigs.end()) {
425 retval = CTR_SigNotUpdated;
426 } else {
427 rawBits = i->second;
428 }
429 return retval;
430}
431/**
432 * Asks TALON to immedietely respond with signal value. This API is only used
433 * for signals that are not sent periodically.
434 * This can be useful for reading params that rarely change like Limit Switch
435 * settings and PIDF values.
436 * @param param to request.
437 */
438CTR_Code CanTalonSRX::RequestParam(param_t paramEnum) {
439 /* process received param events. We don't expect many since this API is not
440 * used often. */
441 ProcessStreamMessages();
442 TALON_Param_Request_t frame;
443 memset(&frame, 0, sizeof(frame));
444 frame.ParamEnum = paramEnum;
445 int32_t status = 0;
446 FRC_NetworkCommunication_CANSessionMux_sendMessage(
447 PARAM_REQUEST | GetDeviceNumber(), (const uint8_t *)&frame, 1, 0,
448 &status);
449 if (status) return CTR_TxFailed;
450 return CTR_OKAY;
451}
452
453CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value) {
454 int32_t rawbits = 0;
455 switch (paramEnum) {
456 case eProfileParamSlot0_P: /* unsigned 10.22 fixed pt value */
457 case eProfileParamSlot0_I:
458 case eProfileParamSlot0_D:
459 case eProfileParamSlot1_P:
460 case eProfileParamSlot1_I:
461 case eProfileParamSlot1_D: {
462 uint32_t urawbits;
463 value = std::min(
464 value, 1023.0); /* bounds check doubles that are outside u10.22 */
465 value = std::max(value, 0.0);
466 urawbits = value * FLOAT_TO_FXP_10_22; /* perform unsign arithmetic */
467 rawbits = urawbits; /* copy bits over. SetParamRaw just stuffs into CAN
468 frame with no sense of signedness */
469 } break;
470 case eProfileParamSlot1_F: /* signed 10.22 fixed pt value */
471 case eProfileParamSlot0_F:
472 value = std::min(
473 value, 512.0); /* bounds check doubles that are outside s10.22 */
474 value = std::max(value, -512.0);
475 rawbits = value * FLOAT_TO_FXP_10_22;
476 break;
477 case eProfileParamVcompRate: /* unsigned 0.8 fixed pt value volts per ms */
478 /* within [0,1) volts per ms.
479 Slowest ramp is 1/256 VperMilliSec or 3.072 seconds from 0-to-12V.
480 Fastest ramp is 255/256 VperMilliSec or 12.1ms from 0-to-12V.
481 */
482 if (value <= 0) {
483 /* negative or zero (disable), send raw value of zero */
484 rawbits = 0;
485 } else {
486 /* nonzero ramping */
487 rawbits = value * FLOAT_TO_FXP_0_8;
488 /* since whole part is cleared, cap to just under whole unit */
489 if (rawbits > (FLOAT_TO_FXP_0_8 - 1)) rawbits = (FLOAT_TO_FXP_0_8 - 1);
490 /* since ramping is nonzero, cap to smallest ramp rate possible */
491 if (rawbits == 0) {
492 /* caller is providing a nonzero ramp rate that's too small
493 to serialize, so cap to smallest possible */
494 rawbits = 1;
495 }
496 }
497 break;
498 default: /* everything else is integral */
499 rawbits = (int32_t)value;
500 break;
501 }
502 return SetParamRaw(paramEnum, rawbits);
503}
504CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double &value) {
505 int32_t rawbits = 0;
506 CTR_Code retval = GetParamResponseRaw(paramEnum, rawbits);
507 switch (paramEnum) {
508 case eProfileParamSlot0_P: /* 10.22 fixed pt value */
509 case eProfileParamSlot0_I:
510 case eProfileParamSlot0_D:
511 case eProfileParamSlot0_F:
512 case eProfileParamSlot1_P:
513 case eProfileParamSlot1_I:
514 case eProfileParamSlot1_D:
515 case eProfileParamSlot1_F:
516 case eCurrent:
517 case eTemp:
518 case eBatteryV:
519 value = ((double)rawbits) * FXP_TO_FLOAT_10_22;
520 break;
521 case eProfileParamVcompRate:
522 value = ((double)rawbits) * FXP_TO_FLOAT_0_8;
523 break;
524 default: /* everything else is integral */
525 value = (double)rawbits;
526 break;
527 }
528 return retval;
529}
530CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int &value) {
531 double dvalue = 0;
532 CTR_Code retval = GetParamResponse(paramEnum, dvalue);
533 value = (int32_t)dvalue;
534 return retval;
535}
536/*----- getters and setters that use param request/response. These signals are
537 * backed up in flash and will survive a power cycle. ---------*/
538/*----- If your application requires changing these values consider using both
539 * slots and switch between slot0 <=> slot1. ------------------*/
540/*----- If your application requires changing these signals frequently then it
541 * makes sense to leverage this API. --------------------------*/
542/*----- Getters don't block, so it may require several calls to get the latest
543 * value. --------------------------*/
544CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx, double gain) {
545 if (slotIdx == 0) return SetParam(eProfileParamSlot0_P, gain);
546 return SetParam(eProfileParamSlot1_P, gain);
547}
548CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx, double gain) {
549 if (slotIdx == 0) return SetParam(eProfileParamSlot0_I, gain);
550 return SetParam(eProfileParamSlot1_I, gain);
551}
552CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx, double gain) {
553 if (slotIdx == 0) return SetParam(eProfileParamSlot0_D, gain);
554 return SetParam(eProfileParamSlot1_D, gain);
555}
556CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx, double gain) {
557 if (slotIdx == 0) return SetParam(eProfileParamSlot0_F, gain);
558 return SetParam(eProfileParamSlot1_F, gain);
559}
560CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx, int zone) {
561 if (slotIdx == 0) return SetParam(eProfileParamSlot0_IZone, zone);
562 return SetParam(eProfileParamSlot1_IZone, zone);
563}
564CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,
565 int closeLoopRampRate) {
566 if (slotIdx == 0)
567 return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
568 return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
569}
570CTR_Code CanTalonSRX::SetVoltageCompensationRate(double voltagePerMs) {
571 return SetParam(eProfileParamVcompRate, voltagePerMs);
572}
573CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx, double &gain) {
574 if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_P, gain);
575 return GetParamResponse(eProfileParamSlot1_P, gain);
576}
577CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx, double &gain) {
578 if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_I, gain);
579 return GetParamResponse(eProfileParamSlot1_I, gain);
580}
581CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx, double &gain) {
582 if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_D, gain);
583 return GetParamResponse(eProfileParamSlot1_D, gain);
584}
585CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx, double &gain) {
586 if (slotIdx == 0) return GetParamResponse(eProfileParamSlot0_F, gain);
587 return GetParamResponse(eProfileParamSlot1_F, gain);
588}
589CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx, int &zone) {
590 if (slotIdx == 0)
591 return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);
592 return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);
593}
594CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,
595 int &closeLoopRampRate) {
596 if (slotIdx == 0)
597 return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate,
598 closeLoopRampRate);
599 return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate,
600 closeLoopRampRate);
601}
602CTR_Code CanTalonSRX::GetVoltageCompensationRate(double &voltagePerMs) {
603 return GetParamResponse(eProfileParamVcompRate, voltagePerMs);
604}
605CTR_Code CanTalonSRX::SetSensorPosition(int pos) {
606 return SetParam(eSensorPosition, pos);
607}
608CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit) {
609 return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);
610}
611CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit) {
612 return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);
613}
614CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable) {
615 return SetParam(eProfileParamSoftLimitForEnable, enable);
616}
617CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable) {
618 return SetParam(eProfileParamSoftLimitRevEnable, enable);
619}
620CTR_Code CanTalonSRX::GetForwardSoftLimit(int &forwardLimit) {
621 return GetParamResponseInt32(eProfileParamSoftLimitForThreshold,
622 forwardLimit);
623}
624CTR_Code CanTalonSRX::GetReverseSoftLimit(int &reverseLimit) {
625 return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold,
626 reverseLimit);
627}
628CTR_Code CanTalonSRX::GetForwardSoftEnable(int &enable) {
629 return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);
630}
631CTR_Code CanTalonSRX::GetReverseSoftEnable(int &enable) {
632 return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);
633}
634/**
635 * @param param [out] Rise to fall time period in microseconds.
636 */
637CTR_Code CanTalonSRX::GetPulseWidthRiseToFallUs(int &param) {
638 int temp = 0;
639 int periodUs = 0;
640 /* first grab our 12.12 position */
641 CTR_Code retval1 = GetPulseWidthPosition(temp);
642 /* mask off number of turns */
643 temp &= 0xFFF;
644 /* next grab the waveform period. This value
645 * will be zero if we stop getting pulses **/
646 CTR_Code retval2 = GetPulseWidthRiseToRiseUs(periodUs);
647 /* now we have 0.12 position that is scaled to the waveform period.
648 Use fixed pt multiply to scale our 0.16 period into us.*/
649 param = (temp * periodUs) / BIT12;
650 /* pass the worst error code to caller.
651 Assume largest value is the most pressing error code.*/
652 return (CTR_Code)std::max((int)retval1, (int)retval2);
653}
654CTR_Code CanTalonSRX::IsPulseWidthSensorPresent(int &param) {
655 int periodUs = 0;
656 CTR_Code retval = GetPulseWidthRiseToRiseUs(periodUs);
657 /* if a nonzero period is present, we are getting good pules.
658 Otherwise the sensor is not present. */
659 if (periodUs != 0)
660 param = 1;
661 else
662 param = 0;
663 return retval;
664}
665/**
666 * @param modeSelect selects which mode.
667 * @param demand setpt or throttle or masterId to follow.
668 * @return error code, 0 iff successful.
669 * This function has the advantage of atomically setting mode and demand.
670 */
671CTR_Code CanTalonSRX::SetModeSelect(int modeSelect, int demand) {
672 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill =
673 GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId |
674 GetDeviceNumber());
675 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
676 toFill->ModeSelect = modeSelect;
677 toFill->DemandH = demand >> 16;
678 toFill->DemandM = demand >> 8;
679 toFill->DemandL = demand >> 0;
680 FlushTx(toFill);
681 return CTR_OKAY;
682}
683/**
684 * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for
685 * what's available.
686 */
687CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum,
688 unsigned periodMs) {
689 CTR_Code retval = CTR_OKAY;
690 int32_t paramEnum = 0;
691 /* bounds check the period */
692 if (periodMs < 1)
693 periodMs = 1;
694 else if (periodMs > 255)
695 periodMs = 255;
696 uint8_t period = (uint8_t)periodMs;
697 /* lookup the correct param enum based on what frame to rate-change */
698 switch (frameEnum) {
699 case kStatusFrame_General:
700 paramEnum = eStatus1FrameRate;
701 break;
702 case kStatusFrame_Feedback:
703 paramEnum = eStatus2FrameRate;
704 break;
705 case kStatusFrame_Encoder:
706 paramEnum = eStatus3FrameRate;
707 break;
708 case kStatusFrame_AnalogTempVbat:
709 paramEnum = eStatus4FrameRate;
710 break;
711 case kStatusFrame_PulseWidthMeas:
712 paramEnum = eStatus8FrameRate;
713 break;
714 case kStatusFrame_MotionProfile:
715 paramEnum = eStatus9FrameRate;
716 break;
717 default:
718 /* caller's request is not support, return an error code */
719 retval = CTR_InvalidParamValue;
720 break;
721 }
722 /* if lookup was succesful, send set-request out */
723 if (retval == CTR_OKAY) {
724 /* paramEnum is updated, sent it out */
725 retval = SetParamRaw(paramEnum, period);
726 }
727 return retval;
728}
729/**
730 * Clear all sticky faults in TALON.
731 */
732CTR_Code CanTalonSRX::ClearStickyFaults() {
733 int32_t status = 0;
734 /* build request frame */
735 TALON_Control_3_ClearFlags_OneShot_t frame;
736 memset(&frame, 0, sizeof(frame));
737 frame.ClearStickyFaults = 1;
738 FRC_NetworkCommunication_CANSessionMux_sendMessage(
739 CONTROL_3 | GetDeviceNumber(), (const uint8_t *)&frame, sizeof(frame), 0,
740 &status);
741 if (status) return CTR_TxFailed;
742 return CTR_OKAY;
743}
744/**
745 * @return the tx task that transmits Control6 (motion profile control).
746 * If it's not scheduled, then schedule it. This is part of firing
747 * the MotionProf framing only when needed to save bandwidth.
748 */
749CtreCanNode::txTask<TALON_Control_6_MotProfAddTrajPoint_t>
750CanTalonSRX::GetControl6() {
751 CtreCanNode::txTask<TALON_Control_6_MotProfAddTrajPoint_t> control6 =
752 GetTx<TALON_Control_6_MotProfAddTrajPoint_t>(CONTROL_6 |
753 GetDeviceNumber());
754 if (control6.IsEmpty()) {
755 /* control6 never started, arm it now */
756 RegisterTx(CONTROL_6 | GetDeviceNumber(), _control6PeriodMs);
757 control6 = GetTx<TALON_Control_6_MotProfAddTrajPoint_t>(CONTROL_6 |
758 GetDeviceNumber());
759 control6->Idx = 0;
760 _motProfFlowControl = 0;
761 FlushTx(control6);
762 }
763 return control6;
764}
765/**
766 * Calling application can opt to speed up the handshaking between the robot API
767 * and the Talon to increase the download rate of the Talon's Motion Profile.
768 * Ideally the period should be no more than half the period of a trajectory
769 * point.
770 */
771void CanTalonSRX::ChangeMotionControlFramePeriod(uint32_t periodMs) {
772 std::unique_lock<std::mutex> lock(_mutMotProf);
773 /* if message is already registered, it will get updated.
774 * Otherwise it will error if it hasn't been setup yet, but that's ok
775 * because the _control6PeriodMs will be used later.
776 * @see GetControl6
777 */
778 _control6PeriodMs = periodMs;
779 ChangeTxPeriod(CONTROL_6 | GetDeviceNumber(), _control6PeriodMs);
780}
781/**
782 * Clear the buffered motion profile in both Talon RAM (bottom), and in the API
783 * (top).
784 */
785void CanTalonSRX::ClearMotionProfileTrajectories() {
786 std::unique_lock<std::mutex> lock(_mutMotProf);
787 /* clear the top buffer */
788 _motProfTopBuffer.Clear();
789 /* send signal to clear bottom buffer */
790 auto toFill = CanTalonSRX::GetControl6();
791 toFill->Idx = 0;
792 _motProfFlowControl = 0; /* match the transmitted flow control */
793 FlushTx(toFill);
794}
795/**
796 * Retrieve just the buffer count for the api-level (top) buffer.
797 * This routine performs no CAN or data structure lookups, so its fast and ideal
798 * if caller needs to quickly poll the progress of trajectory points being
799 * emptied into Talon's RAM. Otherwise just use GetMotionProfileStatus.
800 * @return number of trajectory points in the top buffer.
801 */
802uint32_t CanTalonSRX::GetMotionProfileTopLevelBufferCount() {
803 std::unique_lock<std::mutex> lock(_mutMotProf);
804 uint32_t retval = (uint32_t)_motProfTopBuffer.GetNumTrajectories();
805 return retval;
806}
807/**
808 * Retrieve just the buffer full for the api-level (top) buffer.
809 * This routine performs no CAN or data structure lookups, so its fast and ideal
810 * if caller needs to quickly poll. Otherwise just use GetMotionProfileStatus.
811 * @return number of trajectory points in the top buffer.
812 */
813bool CanTalonSRX::IsMotionProfileTopLevelBufferFull() {
814 std::unique_lock<std::mutex> lock(_mutMotProf);
815 if (_motProfTopBuffer.GetNumTrajectories() >= kMotionProfileTopBufferCapacity)
816 return true;
817 return false;
818}
819/**
820 * Push another trajectory point into the top level buffer (which is emptied
821 * into the Talon's bottom buffer as room allows).
822 * @param targPos servo position in native Talon units (sensor units).
823 * @param targVel velocity to feed-forward in native Talon units (sensor units
824 * per 100ms).
825 * @param profileSlotSelect which slot to pull PIDF gains from. Currently
826 * supports 0 or 1.
827 * @param timeDurMs time in milliseconds of how long to apply this point.
828 * @param velOnly set to nonzero to signal Talon that only the feed-foward
829 * velocity should be used, i.e. do not perform PID on position.
830 * This is equivalent to setting PID gains to zero, but much
831 * more efficient and synchronized to MP.
832 * @param isLastPoint set to nonzero to signal Talon to keep processing this
833 * trajectory point, instead of jumping to the next one
834 * when timeDurMs expires. Otherwise MP executer will
835 * eventually see an empty buffer after the last point
836 * expires, causing it to assert the IsUnderRun flag.
837 * However this may be desired if calling application
838 * never wants to terminate the MP.
839 * @param zeroPos set to nonzero to signal Talon to "zero" the selected
840 * position sensor before executing this trajectory point.
841 * Typically the first point should have this set only thus
842 * allowing the remainder of the MP positions to be relative to
843 * zero.
844 * @return CTR_OKAY if trajectory point push ok. CTR_BufferFull if buffer is
845 * full due to kMotionProfileTopBufferCapacity.
846 */
847CTR_Code CanTalonSRX::PushMotionProfileTrajectory(int targPos, int targVel,
848 int profileSlotSelect,
849 int timeDurMs, int velOnly,
850 int isLastPoint,
851 int zeroPos) {
852 ReactToMotionProfileCall();
853 /* create our trajectory point */
854 TALON_Control_6_MotProfAddTrajPoint_huff0_t traj;
855 memset((void *)&traj, 0, sizeof(traj));
856 traj.NextPt_ZeroPosition = zeroPos ? 1 : 0;
857 traj.NextPt_VelOnly = velOnly ? 1 : 0;
858 traj.NextPt_IsLast = isLastPoint ? 1 : 0;
859 traj.NextPt_ProfileSlotSelect = (profileSlotSelect > 0) ? 1 : 0;
860 if (timeDurMs < 0)
861 timeDurMs = 0;
862 else if (timeDurMs > 255)
863 timeDurMs = 255;
864 traj.NextPt_DurationMs = timeDurMs;
865 traj.NextPt_VelocityH = targVel >> 0x08;
866 traj.NextPt_VelocityL = targVel & 0xFF;
867 traj.NextPt_PositionH = targPos >> 0x10;
868 traj.NextPt_PositionM = targPos >> 0x08;
869 traj.NextPt_PositionL = targPos & 0xFF;
870
871 std::unique_lock<std::mutex> lock(_mutMotProf);
872 if (_motProfTopBuffer.GetNumTrajectories() >= kMotionProfileTopBufferCapacity)
873 return CTR_BufferFull;
874 _motProfTopBuffer.Push(traj);
875 return CTR_OKAY;
876}
877/**
878 * Increment our flow control to manage streaming to the Talon.
879 * f(x) = { 1, x = 15,
880 * x+1, x < 15
881 * }
882 */
883#define MotionProf_IncrementSync(idx) ((idx >= 15) ? 1 : 0) + ((idx + 1) & 0xF)
884/**
885 * Update the NextPt signals inside the control frame given the next pt to send.
886 * @param control pointer to the CAN frame payload containing control6. Only
887 * the signals that serialize the next trajectory point are updated from the
888 * contents of newPt.
889 * @param newPt point to the next trajectory that needs to be inserted into
890 * Talon RAM.
891 */
892void CanTalonSRX::CopyTrajPtIntoControl(
893 TALON_Control_6_MotProfAddTrajPoint_t *control,
894 const TALON_Control_6_MotProfAddTrajPoint_t *newPt) {
895 /* Bring over the common signals in the first two bytes */
896 control->NextPt_ProfileSlotSelect = newPt->NextPt_ProfileSlotSelect;
897 control->NextPt_ZeroPosition = newPt->NextPt_ZeroPosition;
898 control->NextPt_VelOnly = newPt->NextPt_VelOnly;
899 control->NextPt_IsLast = newPt->NextPt_IsLast;
900 control->huffCode = newPt->huffCode;
901 /* the last six bytes are entirely for hold NextPt's values. */
902 uint8_t *dest = (uint8_t *)control;
903 const uint8_t *src = (const uint8_t *)newPt;
904 dest[2] = src[2];
905 dest[3] = src[3];
906 dest[4] = src[4];
907 dest[5] = src[5];
908 dest[6] = src[6];
909 dest[7] = src[7];
910}
911/**
912 * Caller is either pushing a new motion profile point, or is
913 * calling the Process buffer routine. In either case check our
914 * flow control to see if we need to start sending control6.
915 */
916void CanTalonSRX::ReactToMotionProfileCall() {
917 if (_motProfFlowControl < 0) {
918 /* we have not yet armed the periodic frame. We do this lazilly to
919 * save bus utilization since most Talons on the bus probably are not
920 * MP'ing.
921 */
922 ClearMotionProfileTrajectories(); /* this moves flow control so only fires
923 once if ever */
924 }
925}
926/**
927 * This must be called periodically to funnel the trajectory points from the
928 * API's top level buffer to the Talon's bottom level buffer. Recommendation
929 * is to call this twice as fast as the executation rate of the motion profile.
930 * So if MP is running with 20ms trajectory points, try calling this routine
931 * every 10ms. All motion profile functions are thread-safe through the use of
932 * a mutex, so there is no harm in having the caller utilize threading.
933 */
934void CanTalonSRX::ProcessMotionProfileBuffer() {
935 ReactToMotionProfileCall();
936 /* get the latest status frame */
937 GET_STATUS9();
938 /* lock */
939 std::unique_lock<std::mutex> lock(_mutMotProf);
940 /* calc what we expect to receive */
941 if (_motProfFlowControl == rx->NextID) {
942 /* Talon has completed the last req */
943 if (_motProfTopBuffer.IsEmpty()) {
944 /* nothing to do */
945 } else {
946 /* get the latest control frame */
947 auto toFill = GetControl6();
948 TALON_Control_6_MotProfAddTrajPoint_t *front = _motProfTopBuffer.Front();
949 CopyTrajPtIntoControl(toFill.toSend, front);
950 _motProfTopBuffer.Pop();
951 _motProfFlowControl = MotionProf_IncrementSync(_motProfFlowControl);
952 toFill->Idx = _motProfFlowControl;
953 FlushTx(toFill);
954 }
955 } else {
956 /* still waiting on Talon */
957 }
958}
959/**
960 * Retrieve all status information.
961 * Since this all comes from one CAN frame, its ideal to have one routine to
962 * retrieve the frame once and decode everything.
963 * @param [out] flags bitfield for status bools. Starting with least
964 * significant bit: IsValid, HasUnderrun, IsUnderrun, IsLast, VelOnly.
965 *
966 * IsValid set when MP executer is processing a trajectory point,
967 * and that point's status is instrumented with IsLast,
968 * VelOnly, targPos, targVel. However if MP executor is
969 * not processing a trajectory point, then this flag is
970 * false, and the instrumented signals will be zero.
971 * HasUnderrun is set anytime the MP executer is ready to pop
972 * another trajectory point from the Talon's RAM,
973 * but the buffer is empty. It can only be cleared
974 * by using SetParam(eMotionProfileHasUnderrunErr,0);
975 * IsUnderrun is set when the MP executer is ready for another
976 * point, but the buffer is empty, and cleared when
977 * the MP executer does not need another point.
978 * HasUnderrun shadows this registor when this
979 * register gets set, however HasUnderrun stays
980 * asserted until application has process it, and
981 * IsUnderrun auto-clears when the condition is
982 * resolved.
983 * IsLast is set/cleared based on the MP executer's current
984 * trajectory point's IsLast value. This assumes
985 * IsLast was set when PushMotionProfileTrajectory
986 * was used to insert the currently processed trajectory
987 * point.
988 * VelOnly is set/cleared based on the MP executer's current
989 * trajectory point's VelOnly value.
990 *
991 * @param [out] profileSlotSelect The currently processed trajectory point's
992 * selected slot. This can differ in the currently selected slot used
993 * for Position and Velocity servo modes.
994 * @param [out] targPos The currently processed trajectory point's position
995 * in native units. This param is zero if IsValid is zero.
996 * @param [out] targVel The currently processed trajectory point's velocity
997 * in native units. This param is zero if IsValid is zero.
998 * @param [out] topBufferRem The remaining number of points in the top level
999 * buffer.
1000 * @param [out] topBufferCnt The number of points in the top level buffer to
1001 * be sent to Talon.
1002 * @param [out] btmBufferCnt The number of points in the bottom level buffer
1003 * inside Talon.
1004 * @return CTR error code
1005 */
1006CTR_Code CanTalonSRX::GetMotionProfileStatus(
1007 uint32_t &flags, uint32_t &profileSlotSelect, int32_t &targPos,
1008 int32_t &targVel, uint32_t &topBufferRem, uint32_t &topBufferCnt,
1009 uint32_t &btmBufferCnt, uint32_t &outputEnable) {
1010 /* get the latest status frame */
1011 GET_STATUS9();
1012
1013 /* clear signals in case we never received an update, caller should check
1014 * return
1015 */
1016 flags = 0;
1017 profileSlotSelect = 0;
1018 targPos = 0;
1019 targVel = 0;
1020 btmBufferCnt = 0;
1021
1022 /* these signals are always available */
1023 topBufferCnt = _motProfTopBuffer.GetNumTrajectories();
1024 topBufferRem =
1025 kMotionProfileTopBufferCapacity - _motProfTopBuffer.GetNumTrajectories();
1026
1027 /* TODO: make enums or make a better method prototype */
1028 if (rx->ActTraj_IsValid) flags |= kMotionProfileFlag_ActTraj_IsValid;
1029 if (rx->HasUnderrun) flags |= kMotionProfileFlag_HasUnderrun;
1030 if (rx->IsUnderrun) flags |= kMotionProfileFlag_IsUnderrun;
1031 if (rx->ActTraj_IsLast) flags |= kMotionProfileFlag_ActTraj_IsLast;
1032 if (rx->ActTraj_VelOnly) flags |= kMotionProfileFlag_ActTraj_VelOnly;
1033
1034 btmBufferCnt = rx->Count;
1035
1036 targPos = rx->ActTraj_PositionH;
1037 targPos <<= 8;
1038 targPos |= rx->ActTraj_PositionM;
1039 targPos <<= 8;
1040 targPos |= rx->ActTraj_PositionL;
1041
1042 targVel = rx->ActTraj_VelocityH;
1043 targVel <<= 8;
1044 targVel |= rx->ActTraj_VelocityL;
1045
1046 profileSlotSelect = rx->ActTraj_ProfileSlotSelect;
1047
1048 switch (rx->OutputType) {
1049 case kMotionProf_Disabled:
1050 case kMotionProf_Enable:
1051 case kMotionProf_Hold:
1052 outputEnable = rx->OutputType;
1053 break;
1054 default:
1055 /* do now allow invalid values for sake of user-facing enum types */
1056 outputEnable = kMotionProf_Disabled;
1057 break;
1058 }
1059 return rx.err;
1060}
1061//------------------------ auto generated ------------------------------------//
1062/* This API is optimal since it uses the fire-and-forget CAN interface.
1063 * These signals should cover the majority of all use cases.
1064 */
1065CTR_Code CanTalonSRX::GetFault_OverTemp(int &param)
1066{
1067 GET_STATUS1();
1068 param = rx->Fault_OverTemp;
1069 return rx.err;
1070}
1071CTR_Code CanTalonSRX::GetFault_UnderVoltage(int &param)
1072{
1073 GET_STATUS1();
1074 param = rx->Fault_UnderVoltage;
1075 return rx.err;
1076}
1077CTR_Code CanTalonSRX::GetFault_ForLim(int &param)
1078{
1079 GET_STATUS1();
1080 param = rx->Fault_ForLim;
1081 return rx.err;
1082}
1083CTR_Code CanTalonSRX::GetFault_RevLim(int &param)
1084{
1085 GET_STATUS1();
1086 param = rx->Fault_RevLim;
1087 return rx.err;
1088}
1089CTR_Code CanTalonSRX::GetFault_HardwareFailure(int &param)
1090{
1091 GET_STATUS1();
1092 param = rx->Fault_HardwareFailure;
1093 return rx.err;
1094}
1095CTR_Code CanTalonSRX::GetFault_ForSoftLim(int &param)
1096{
1097 GET_STATUS1();
1098 param = rx->Fault_ForSoftLim;
1099 return rx.err;
1100}
1101CTR_Code CanTalonSRX::GetFault_RevSoftLim(int &param)
1102{
1103 GET_STATUS1();
1104 param = rx->Fault_RevSoftLim;
1105 return rx.err;
1106}
1107CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int &param)
1108{
1109 GET_STATUS2();
1110 param = rx->StckyFault_OverTemp;
1111 return rx.err;
1112}
1113CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int &param)
1114{
1115 GET_STATUS2();
1116 param = rx->StckyFault_UnderVoltage;
1117 return rx.err;
1118}
1119CTR_Code CanTalonSRX::GetStckyFault_ForLim(int &param)
1120{
1121 GET_STATUS2();
1122 param = rx->StckyFault_ForLim;
1123 return rx.err;
1124}
1125CTR_Code CanTalonSRX::GetStckyFault_RevLim(int &param)
1126{
1127 GET_STATUS2();
1128 param = rx->StckyFault_RevLim;
1129 return rx.err;
1130}
1131CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int &param)
1132{
1133 GET_STATUS2();
1134 param = rx->StckyFault_ForSoftLim;
1135 return rx.err;
1136}
1137CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int &param)
1138{
1139 GET_STATUS2();
1140 param = rx->StckyFault_RevSoftLim;
1141 return rx.err;
1142}
1143CTR_Code CanTalonSRX::GetAppliedThrottle(int &param)
1144{
1145 GET_STATUS1();
1146 int32_t raw = 0;
1147 raw |= rx->AppliedThrottle_h3;
1148 raw <<= 8;
1149 raw |= rx->AppliedThrottle_l8;
1150 raw <<= (32-11); /* sign extend */
1151 raw >>= (32-11); /* sign extend */
1152 param = (int)raw;
1153 return rx.err;
1154}
1155CTR_Code CanTalonSRX::GetCloseLoopErr(int &param)
1156{
1157 GET_STATUS1();
1158 int32_t raw = 0;
1159 raw |= rx->CloseLoopErrH;
1160 raw <<= 16 - 8;
1161 raw |= rx->CloseLoopErrM;
1162 raw <<= 8;
1163 raw |= rx->CloseLoopErrL;
1164 raw <<= (32-24); /* sign extend */
1165 raw >>= (32-24); /* sign extend */
1166 param = (int)raw;
1167 return rx.err;
1168}
1169CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int &param)
1170{
1171 GET_STATUS1();
1172 param = rx->FeedbackDeviceSelect;
1173 return rx.err;
1174}
1175CTR_Code CanTalonSRX::GetModeSelect(int &param)
1176{
1177 GET_STATUS1();
1178 uint32_t raw = 0;
1179 raw |= rx->ModeSelect_h1;
1180 raw <<= 3;
1181 raw |= rx->ModeSelect_b3;
1182 param = (int)raw;
1183 return rx.err;
1184}
1185CTR_Code CanTalonSRX::GetLimitSwitchEn(int &param)
1186{
1187 GET_STATUS1();
1188 param = rx->LimitSwitchEn;
1189 return rx.err;
1190}
1191CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int &param)
1192{
1193 GET_STATUS1();
1194 param = rx->LimitSwitchClosedFor;
1195 return rx.err;
1196}
1197CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int &param)
1198{
1199 GET_STATUS1();
1200 param = rx->LimitSwitchClosedRev;
1201 return rx.err;
1202}
1203CTR_Code CanTalonSRX::GetSensorPosition(int &param)
1204{
1205 GET_STATUS2();
1206 int32_t raw = 0;
1207 raw |= rx->SensorPositionH;
1208 raw <<= 16 - 8;
1209 raw |= rx->SensorPositionM;
1210 raw <<= 8;
1211 raw |= rx->SensorPositionL;
1212 raw <<= (32-24); /* sign extend */
1213 raw >>= (32-24); /* sign extend */
1214 if(rx->PosDiv8)
1215 raw *= 8;
1216 param = (int)raw;
1217 return rx.err;
1218}
1219CTR_Code CanTalonSRX::GetSensorVelocity(int &param)
1220{
1221 GET_STATUS2();
1222 int32_t raw = 0;
1223 raw |= rx->SensorVelocityH;
1224 raw <<= 8;
1225 raw |= rx->SensorVelocityL;
1226 raw <<= (32-16); /* sign extend */
1227 raw >>= (32-16); /* sign extend */
1228 if(rx->VelDiv4)
1229 raw *= 4;
1230 param = (int)raw;
1231 return rx.err;
1232}
1233CTR_Code CanTalonSRX::GetCurrent(double &param)
1234{
1235 GET_STATUS2();
1236 uint32_t raw = 0;
1237 raw |= rx->Current_h8;
1238 raw <<= 2;
1239 raw |= rx->Current_l2;
1240 param = (double)raw * 0.125 + 0;
1241 return rx.err;
1242}
1243CTR_Code CanTalonSRX::GetBrakeIsEnabled(int &param)
1244{
1245 GET_STATUS2();
1246 param = rx->BrakeIsEnabled;
1247 return rx.err;
1248}
1249CTR_Code CanTalonSRX::GetEncPosition(int &param)
1250{
1251 GET_STATUS3();
1252 int32_t raw = 0;
1253 raw |= rx->EncPositionH;
1254 raw <<= 16 - 8;
1255 raw |= rx->EncPositionM;
1256 raw <<= 8;
1257 raw |= rx->EncPositionL;
1258 raw <<= (32-24); /* sign extend */
1259 raw >>= (32-24); /* sign extend */
1260 if(rx->PosDiv8)
1261 raw *= 8;
1262 param = (int)raw;
1263 return rx.err;
1264}
1265CTR_Code CanTalonSRX::GetEncVel(int &param)
1266{
1267 GET_STATUS3();
1268 int32_t raw = 0;
1269 raw |= rx->EncVelH;
1270 raw <<= 8;
1271 raw |= rx->EncVelL;
1272 raw <<= (32-16); /* sign extend */
1273 raw >>= (32-16); /* sign extend */
1274 if(rx->VelDiv4)
1275 raw *= 4;
1276 param = (int)raw;
1277 return rx.err;
1278}
1279CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int &param)
1280{
1281 GET_STATUS3();
1282 uint32_t raw = 0;
1283 raw |= rx->EncIndexRiseEventsH;
1284 raw <<= 8;
1285 raw |= rx->EncIndexRiseEventsL;
1286 param = (int)raw;
1287 return rx.err;
1288}
1289CTR_Code CanTalonSRX::GetQuadApin(int &param)
1290{
1291 GET_STATUS3();
1292 param = rx->QuadApin;
1293 return rx.err;
1294}
1295CTR_Code CanTalonSRX::GetQuadBpin(int &param)
1296{
1297 GET_STATUS3();
1298 param = rx->QuadBpin;
1299 return rx.err;
1300}
1301CTR_Code CanTalonSRX::GetQuadIdxpin(int &param)
1302{
1303 GET_STATUS3();
1304 param = rx->QuadIdxpin;
1305 return rx.err;
1306}
1307CTR_Code CanTalonSRX::GetAnalogInWithOv(int &param)
1308{
1309 GET_STATUS4();
1310 int32_t raw = 0;
1311 raw |= rx->AnalogInWithOvH;
1312 raw <<= 16 - 8;
1313 raw |= rx->AnalogInWithOvM;
1314 raw <<= 8;
1315 raw |= rx->AnalogInWithOvL;
1316 raw <<= (32-24); /* sign extend */
1317 raw >>= (32-24); /* sign extend */
1318 if(rx->PosDiv8)
1319 raw *= 8;
1320 param = (int)raw;
1321 return rx.err;
1322}
1323CTR_Code CanTalonSRX::GetAnalogInVel(int &param)
1324{
1325 GET_STATUS4();
1326 int32_t raw = 0;
1327 raw |= rx->AnalogInVelH;
1328 raw <<= 8;
1329 raw |= rx->AnalogInVelL;
1330 raw <<= (32-16); /* sign extend */
1331 raw >>= (32-16); /* sign extend */
1332 if(rx->VelDiv4)
1333 raw *= 4;
1334 param = (int)raw;
1335 return rx.err;
1336}
1337CTR_Code CanTalonSRX::GetTemp(double &param)
1338{
1339 GET_STATUS4();
1340 uint32_t raw = rx->Temp;
1341 param = (double)raw * 0.6451612903 + -50;
1342 return rx.err;
1343}
1344CTR_Code CanTalonSRX::GetBatteryV(double &param)
1345{
1346 GET_STATUS4();
1347 uint32_t raw = rx->BatteryV;
1348 param = (double)raw * 0.05 + 4;
1349 return rx.err;
1350}
1351CTR_Code CanTalonSRX::GetResetCount(int &param)
1352{
1353 GET_STATUS5();
1354 uint32_t raw = 0;
1355 raw |= rx->ResetCountH;
1356 raw <<= 8;
1357 raw |= rx->ResetCountL;
1358 param = (int)raw;
1359 return rx.err;
1360}
1361CTR_Code CanTalonSRX::GetResetFlags(int &param)
1362{
1363 GET_STATUS5();
1364 uint32_t raw = 0;
1365 raw |= rx->ResetFlagsH;
1366 raw <<= 8;
1367 raw |= rx->ResetFlagsL;
1368 param = (int)raw;
1369 return rx.err;
1370}
1371CTR_Code CanTalonSRX::GetFirmVers(int &param)
1372{
1373 GET_STATUS5();
1374 uint32_t raw = 0;
1375 raw |= rx->FirmVersH;
1376 raw <<= 8;
1377 raw |= rx->FirmVersL;
1378 param = (int)raw;
1379 return rx.err;
1380}
1381CTR_Code CanTalonSRX::GetPulseWidthPosition(int &param)
1382{
1383 GET_STATUS8();
1384 int32_t raw = 0;
1385 raw |= rx->PulseWidPositionH;
1386 raw <<= 16 - 8;
1387 raw |= rx->PulseWidPositionM;
1388 raw <<= 8;
1389 raw |= rx->PulseWidPositionL;
1390 raw <<= (32-24); /* sign extend */
1391 raw >>= (32-24); /* sign extend */
1392 if(rx->PosDiv8)
1393 raw *= 8;
1394 param = (int)raw;
1395 return rx.err;
1396}
1397CTR_Code CanTalonSRX::GetPulseWidthVelocity(int &param)
1398{
1399 GET_STATUS8();
1400 int32_t raw = 0;
1401 raw |= rx->PulseWidVelH;
1402 raw <<= 8;
1403 raw |= rx->PulseWidVelL;
1404 raw <<= (32-16); /* sign extend */
1405 raw >>= (32-16); /* sign extend */
1406 if(rx->VelDiv4)
1407 raw *= 4;
1408 param = (int)raw;
1409 return rx.err;
1410}
1411CTR_Code CanTalonSRX::GetPulseWidthRiseToRiseUs(int &param)
1412{
1413 GET_STATUS8();
1414 uint32_t raw = 0;
1415 raw |= rx->PeriodUsM8;
1416 raw <<= 8;
1417 raw |= rx->PeriodUsL8;
1418 param = (int)raw;
1419 return rx.err;
1420}
1421CTR_Code CanTalonSRX::GetActTraj_IsValid(int &param)
1422{
1423 GET_STATUS9();
1424 param = rx->ActTraj_IsValid;
1425 return rx.err;
1426}
1427CTR_Code CanTalonSRX::GetActTraj_ProfileSlotSelect(int &param)
1428{
1429 GET_STATUS9();
1430 param = rx->ActTraj_ProfileSlotSelect;
1431 return rx.err;
1432}
1433CTR_Code CanTalonSRX::GetActTraj_VelOnly(int &param)
1434{
1435 GET_STATUS9();
1436 param = rx->ActTraj_VelOnly;
1437 return rx.err;
1438}
1439CTR_Code CanTalonSRX::GetActTraj_IsLast(int &param)
1440{
1441 GET_STATUS9();
1442 param = rx->ActTraj_IsLast;
1443 return rx.err;
1444}
1445CTR_Code CanTalonSRX::GetOutputType(int &param)
1446{
1447 GET_STATUS9();
1448 param = rx->OutputType;
1449 return rx.err;
1450}
1451CTR_Code CanTalonSRX::GetHasUnderrun(int &param)
1452{
1453 GET_STATUS9();
1454 param = rx->HasUnderrun;
1455 return rx.err;
1456}
1457CTR_Code CanTalonSRX::GetIsUnderrun(int &param)
1458{
1459 GET_STATUS9();
1460 param = rx->IsUnderrun;
1461 return rx.err;
1462}
1463CTR_Code CanTalonSRX::GetNextID(int &param)
1464{
1465 GET_STATUS9();
1466 param = rx->NextID;
1467 return rx.err;
1468}
1469CTR_Code CanTalonSRX::GetBufferIsFull(int &param)
1470{
1471 GET_STATUS9();
1472 param = rx->BufferIsFull;
1473 return rx.err;
1474}
1475CTR_Code CanTalonSRX::GetCount(int &param)
1476{
1477 GET_STATUS9();
1478 param = rx->Count;
1479 return rx.err;
1480}
1481CTR_Code CanTalonSRX::GetActTraj_Velocity(int &param)
1482{
1483 GET_STATUS9();
1484 int32_t raw = 0;
1485 raw |= rx->ActTraj_VelocityH;
1486 raw <<= 8;
1487 raw |= rx->ActTraj_VelocityL;
1488 raw <<= (32-16); /* sign extend */
1489 raw >>= (32-16); /* sign extend */
1490 param = (int)raw;
1491 return rx.err;
1492}
1493CTR_Code CanTalonSRX::GetActTraj_Position(int &param)
1494{
1495 GET_STATUS9();
1496 int32_t raw = 0;
1497 raw |= rx->ActTraj_PositionH;
1498 raw <<= 16 - 8;
1499 raw |= rx->ActTraj_PositionM;
1500 raw <<= 8;
1501 raw |= rx->ActTraj_PositionL;
1502 raw <<= (32-24); /* sign extend */
1503 raw >>= (32-24); /* sign extend */
1504 param = (int)raw;
1505 return rx.err;
1506}
1507CTR_Code CanTalonSRX::SetDemand(int param)
1508{
1509 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1510 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1511 toFill->DemandH = param>>16;
1512 toFill->DemandM = param>>8;
1513 toFill->DemandL = param>>0;
1514 FlushTx(toFill);
1515 return CTR_OKAY;
1516}
1517CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)
1518{
1519 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1520 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1521 toFill->OverrideLimitSwitchEn = param;
1522 FlushTx(toFill);
1523 return CTR_OKAY;
1524}
1525CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)
1526{
1527 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1528 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1529 toFill->FeedbackDeviceSelect = param;
1530 FlushTx(toFill);
1531 return CTR_OKAY;
1532}
1533CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)
1534{
1535 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1536 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1537 toFill->RevMotDuringCloseLoopEn = param;
1538 FlushTx(toFill);
1539 return CTR_OKAY;
1540}
1541CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)
1542{
1543 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1544 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1545 toFill->OverrideBrakeType = param;
1546 FlushTx(toFill);
1547 return CTR_OKAY;
1548}
1549CTR_Code CanTalonSRX::SetModeSelect(int param)
1550{
1551 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1552 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1553 toFill->ModeSelect = param;
1554 FlushTx(toFill);
1555 return CTR_OKAY;
1556}
1557CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)
1558{
1559 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1560 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1561 toFill->ProfileSlotSelect = param;
1562 FlushTx(toFill);
1563 return CTR_OKAY;
1564}
1565CTR_Code CanTalonSRX::SetRampThrottle(int param)
1566{
1567 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1568 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1569 toFill->RampThrottle = param;
1570 FlushTx(toFill);
1571 return CTR_OKAY;
1572}
1573CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)
1574{
1575 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(_controlFrameArbId | GetDeviceNumber());
1576 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1577 toFill->RevFeedbackSensor = param ? 1 : 0;
1578 FlushTx(toFill);
1579 return CTR_OKAY;
1580}
1581//------------------ C interface --------------------------------------------//
1582extern "C" {
1583void *c_TalonSRX_Create3(int deviceNumber, int controlPeriodMs, int enablePeriodMs)
1584{
1585 return new CanTalonSRX(deviceNumber, controlPeriodMs, enablePeriodMs);
1586}
1587void *c_TalonSRX_Create2(int deviceNumber, int controlPeriodMs)
1588{
1589 return new CanTalonSRX(deviceNumber, controlPeriodMs);
1590}
1591void *c_TalonSRX_Create1(int deviceNumber)
1592{
1593 return new CanTalonSRX(deviceNumber);
1594}
1595void c_TalonSRX_Destroy(void *handle)
1596{
1597 delete (CanTalonSRX*)handle;
1598}
1599void c_TalonSRX_Set(void *handle, double value)
1600{
1601 return ((CanTalonSRX*)handle)->Set(value);
1602}
1603CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)
1604{
1605 return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);
1606}
1607CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)
1608{
1609 return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);
1610}
1611CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)
1612{
1613 return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);
1614}
1615CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)
1616{
1617 return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);
1618}
1619CTR_Code c_TalonSRX_SetPgain(void *handle, int slotIdx, double gain)
1620{
1621 return ((CanTalonSRX*)handle)->SetPgain((unsigned)slotIdx, gain);
1622}
1623CTR_Code c_TalonSRX_SetIgain(void *handle, int slotIdx, double gain)
1624{
1625 return ((CanTalonSRX*)handle)->SetIgain((unsigned)slotIdx, gain);
1626}
1627CTR_Code c_TalonSRX_SetDgain(void *handle, int slotIdx, double gain)
1628{
1629 return ((CanTalonSRX*)handle)->SetDgain((unsigned)slotIdx, gain);
1630}
1631CTR_Code c_TalonSRX_SetFgain(void *handle, int slotIdx, double gain)
1632{
1633 return ((CanTalonSRX*)handle)->SetFgain((unsigned)slotIdx, gain);
1634}
1635CTR_Code c_TalonSRX_SetIzone(void *handle, int slotIdx, int zone)
1636{
1637 return ((CanTalonSRX*)handle)->SetIzone((unsigned)slotIdx, zone);
1638}
1639CTR_Code c_TalonSRX_SetCloseLoopRampRate(void *handle, int slotIdx, int closeLoopRampRate)
1640{
1641 return ((CanTalonSRX*)handle)->SetCloseLoopRampRate((unsigned)slotIdx, closeLoopRampRate);
1642}
1643CTR_Code c_TalonSRX_SetVoltageCompensationRate(void *handle, double voltagePerMs)
1644{
1645 return ((CanTalonSRX*)handle)->SetVoltageCompensationRate(voltagePerMs);
1646}
1647CTR_Code c_TalonSRX_SetSensorPosition(void *handle, int pos)
1648{
1649 return ((CanTalonSRX*)handle)->SetSensorPosition(pos);
1650}
1651CTR_Code c_TalonSRX_SetForwardSoftLimit(void *handle, int forwardLimit)
1652{
1653 return ((CanTalonSRX*)handle)->SetForwardSoftLimit(forwardLimit);
1654}
1655CTR_Code c_TalonSRX_SetReverseSoftLimit(void *handle, int reverseLimit)
1656{
1657 return ((CanTalonSRX*)handle)->SetReverseSoftLimit(reverseLimit);
1658}
1659CTR_Code c_TalonSRX_SetForwardSoftEnable(void *handle, int enable)
1660{
1661 return ((CanTalonSRX*)handle)->SetForwardSoftEnable(enable);
1662}
1663CTR_Code c_TalonSRX_SetReverseSoftEnable(void *handle, int enable)
1664{
1665 return ((CanTalonSRX*)handle)->SetReverseSoftEnable(enable);
1666}
1667CTR_Code c_TalonSRX_GetPgain(void *handle, int slotIdx, double *gain)
1668{
1669 return ((CanTalonSRX*)handle)->GetPgain((unsigned)slotIdx, *gain);
1670}
1671CTR_Code c_TalonSRX_GetIgain(void *handle, int slotIdx, double *gain)
1672{
1673 return ((CanTalonSRX*)handle)->GetIgain((unsigned)slotIdx, *gain);
1674}
1675CTR_Code c_TalonSRX_GetDgain(void *handle, int slotIdx, double *gain)
1676{
1677 return ((CanTalonSRX*)handle)->GetDgain((unsigned)slotIdx, *gain);
1678}
1679CTR_Code c_TalonSRX_GetFgain(void *handle, int slotIdx, double *gain)
1680{
1681 return ((CanTalonSRX*)handle)->GetFgain((unsigned)slotIdx, *gain);
1682}
1683CTR_Code c_TalonSRX_GetIzone(void *handle, int slotIdx, int *zone)
1684{
1685 return ((CanTalonSRX*)handle)->GetIzone((unsigned)slotIdx, *zone);
1686}
1687CTR_Code c_TalonSRX_GetCloseLoopRampRate(void *handle, int slotIdx, int *closeLoopRampRate)
1688{
1689 return ((CanTalonSRX*)handle)->GetCloseLoopRampRate((unsigned)slotIdx, *closeLoopRampRate);
1690}
1691CTR_Code c_TalonSRX_GetVoltageCompensationRate(void *handle, double *voltagePerMs)
1692{
1693 return ((CanTalonSRX*)handle)->GetVoltageCompensationRate(*voltagePerMs);
1694}
1695CTR_Code c_TalonSRX_GetForwardSoftLimit(void *handle, int *forwardLimit)
1696{
1697 return ((CanTalonSRX*)handle)->GetForwardSoftLimit(*forwardLimit);
1698}
1699CTR_Code c_TalonSRX_GetReverseSoftLimit(void *handle, int *reverseLimit)
1700{
1701 return ((CanTalonSRX*)handle)->GetReverseSoftLimit(*reverseLimit);
1702}
1703CTR_Code c_TalonSRX_GetForwardSoftEnable(void *handle, int *enable)
1704{
1705 return ((CanTalonSRX*)handle)->GetForwardSoftEnable(*enable);
1706}
1707CTR_Code c_TalonSRX_GetReverseSoftEnable(void *handle, int *enable)
1708{
1709 return ((CanTalonSRX*)handle)->GetReverseSoftEnable(*enable);
1710}
1711CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param)
1712{
1713 return ((CanTalonSRX*)handle)->GetPulseWidthRiseToFallUs(*param);
1714}
1715CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param)
1716{
1717 return ((CanTalonSRX*)handle)->IsPulseWidthSensorPresent(*param);
1718}
1719CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)
1720{
1721 return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);
1722}
1723CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, int frameEnum, int periodMs)
1724{
1725 return ((CanTalonSRX*)handle)->SetStatusFrameRate((unsigned)frameEnum, (unsigned)periodMs);
1726}
1727CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)
1728{
1729 return ((CanTalonSRX*)handle)->ClearStickyFaults();
1730}
1731void c_TalonSRX_ChangeMotionControlFramePeriod(void *handle, int periodMs)
1732{
1733 return ((CanTalonSRX*)handle)->ChangeMotionControlFramePeriod((uint32_t)periodMs);
1734}
1735void c_TalonSRX_ClearMotionProfileTrajectories(void *handle)
1736{
1737 return ((CanTalonSRX*)handle)->ClearMotionProfileTrajectories();
1738}
1739int c_TalonSRX_GetMotionProfileTopLevelBufferCount(void *handle)
1740{
1741 return ((CanTalonSRX*)handle)->GetMotionProfileTopLevelBufferCount();
1742}
1743int c_TalonSRX_IsMotionProfileTopLevelBufferFull(void *handle)
1744{
1745 return ((CanTalonSRX*)handle)->IsMotionProfileTopLevelBufferFull();
1746}
1747CTR_Code c_TalonSRX_PushMotionProfileTrajectory(void *handle, int targPos, int targVel, int profileSlotSelect, int timeDurMs, int velOnly, int isLastPoint, int zeroPos)
1748{
1749 return ((CanTalonSRX*)handle)->PushMotionProfileTrajectory(targPos, targVel, profileSlotSelect, timeDurMs, velOnly, isLastPoint, zeroPos);
1750}
1751void c_TalonSRX_ProcessMotionProfileBuffer(void *handle)
1752{
1753 return ((CanTalonSRX*)handle)->ProcessMotionProfileBuffer();
1754}
1755CTR_Code c_TalonSRX_GetMotionProfileStatus(void *handle, int *flags, int *profileSlotSelect, int *targPos, int *targVel, int *topBufferRemaining, int *topBufferCnt, int *btmBufferCnt, int *outputEnable)
1756{
1757 uint32_t flags_val;
1758 uint32_t profileSlotSelect_val;
1759 int32_t targPos_val;
1760 int32_t targVel_val;
1761 uint32_t topBufferRemaining_val;
1762 uint32_t topBufferCnt_val;
1763 uint32_t btmBufferCnt_val;
1764 uint32_t outputEnable_val;
1765 CTR_Code retval = ((CanTalonSRX*)handle)->GetMotionProfileStatus(flags_val, profileSlotSelect_val, targPos_val, targVel_val, topBufferRemaining_val, topBufferCnt_val, btmBufferCnt_val, outputEnable_val);
1766 *flags = (int)flags_val;
1767 *profileSlotSelect = (int)profileSlotSelect_val;
1768 *targPos = (int)targPos_val;
1769 *targVel = (int)targVel_val;
1770 *topBufferRemaining = (int)topBufferRemaining_val;
1771 *topBufferCnt = (int)topBufferCnt_val;
1772 *btmBufferCnt = (int)btmBufferCnt_val;
1773 *outputEnable = (int)outputEnable_val;
1774 return retval;
1775}
1776CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)
1777{
1778 return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);
1779}
1780CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)
1781{
1782 return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);
1783}
1784CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)
1785{
1786 return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);
1787}
1788CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)
1789{
1790 return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);
1791}
1792CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)
1793{
1794 return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);
1795}
1796CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)
1797{
1798 return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);
1799}
1800CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)
1801{
1802 return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);
1803}
1804CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)
1805{
1806 return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);
1807}
1808CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)
1809{
1810 return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);
1811}
1812CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)
1813{
1814 return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);
1815}
1816CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)
1817{
1818 return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);
1819}
1820CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)
1821{
1822 return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);
1823}
1824CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)
1825{
1826 return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);
1827}
1828CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)
1829{
1830 return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);
1831}
1832CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)
1833{
1834 return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);
1835}
1836CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)
1837{
1838 return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);
1839}
1840CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)
1841{
1842 return ((CanTalonSRX*)handle)->GetModeSelect(*param);
1843}
1844CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)
1845{
1846 return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);
1847}
1848CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)
1849{
1850 return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);
1851}
1852CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)
1853{
1854 return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);
1855}
1856CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)
1857{
1858 return ((CanTalonSRX*)handle)->GetSensorPosition(*param);
1859}
1860CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)
1861{
1862 return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);
1863}
1864CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)
1865{
1866 return ((CanTalonSRX*)handle)->GetCurrent(*param);
1867}
1868CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)
1869{
1870 return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);
1871}
1872CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)
1873{
1874 return ((CanTalonSRX*)handle)->GetEncPosition(*param);
1875}
1876CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)
1877{
1878 return ((CanTalonSRX*)handle)->GetEncVel(*param);
1879}
1880CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)
1881{
1882 return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);
1883}
1884CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)
1885{
1886 return ((CanTalonSRX*)handle)->GetQuadApin(*param);
1887}
1888CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)
1889{
1890 return ((CanTalonSRX*)handle)->GetQuadBpin(*param);
1891}
1892CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)
1893{
1894 return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);
1895}
1896CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)
1897{
1898 return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);
1899}
1900CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)
1901{
1902 return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);
1903}
1904CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)
1905{
1906 return ((CanTalonSRX*)handle)->GetTemp(*param);
1907}
1908CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)
1909{
1910 return ((CanTalonSRX*)handle)->GetBatteryV(*param);
1911}
1912CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)
1913{
1914 return ((CanTalonSRX*)handle)->GetResetCount(*param);
1915}
1916CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)
1917{
1918 return ((CanTalonSRX*)handle)->GetResetFlags(*param);
1919}
1920CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)
1921{
1922 return ((CanTalonSRX*)handle)->GetFirmVers(*param);
1923}
1924CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param)
1925{
1926 return ((CanTalonSRX*)handle)->GetPulseWidthPosition(*param);
1927}
1928CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param)
1929{
1930 return ((CanTalonSRX*)handle)->GetPulseWidthVelocity(*param);
1931}
1932CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param)
1933{
1934 return ((CanTalonSRX*)handle)->GetPulseWidthRiseToRiseUs(*param);
1935}
1936CTR_Code c_TalonSRX_GetActTraj_IsValid(void *handle, int *param)
1937{
1938 return ((CanTalonSRX*)handle)->GetActTraj_IsValid(*param);
1939}
1940CTR_Code c_TalonSRX_GetActTraj_ProfileSlotSelect(void *handle, int *param)
1941{
1942 return ((CanTalonSRX*)handle)->GetActTraj_ProfileSlotSelect(*param);
1943}
1944CTR_Code c_TalonSRX_GetActTraj_VelOnly(void *handle, int *param)
1945{
1946 return ((CanTalonSRX*)handle)->GetActTraj_VelOnly(*param);
1947}
1948CTR_Code c_TalonSRX_GetActTraj_IsLast(void *handle, int *param)
1949{
1950 return ((CanTalonSRX*)handle)->GetActTraj_IsLast(*param);
1951}
1952CTR_Code c_TalonSRX_GetOutputType(void *handle, int *param)
1953{
1954 return ((CanTalonSRX*)handle)->GetOutputType(*param);
1955}
1956CTR_Code c_TalonSRX_GetHasUnderrun(void *handle, int *param)
1957{
1958 return ((CanTalonSRX*)handle)->GetHasUnderrun(*param);
1959}
1960CTR_Code c_TalonSRX_GetIsUnderrun(void *handle, int *param)
1961{
1962 return ((CanTalonSRX*)handle)->GetIsUnderrun(*param);
1963}
1964CTR_Code c_TalonSRX_GetNextID(void *handle, int *param)
1965{
1966 return ((CanTalonSRX*)handle)->GetNextID(*param);
1967}
1968CTR_Code c_TalonSRX_GetBufferIsFull(void *handle, int *param)
1969{
1970 return ((CanTalonSRX*)handle)->GetBufferIsFull(*param);
1971}
1972CTR_Code c_TalonSRX_GetCount(void *handle, int *param)
1973{
1974 return ((CanTalonSRX*)handle)->GetCount(*param);
1975}
1976CTR_Code c_TalonSRX_GetActTraj_Velocity(void *handle, int *param)
1977{
1978 return ((CanTalonSRX*)handle)->GetActTraj_Velocity(*param);
1979}
1980CTR_Code c_TalonSRX_GetActTraj_Position(void *handle, int *param)
1981{
1982 return ((CanTalonSRX*)handle)->GetActTraj_Position(*param);
1983}
1984CTR_Code c_TalonSRX_SetDemand(void *handle, int param)
1985{
1986 return ((CanTalonSRX*)handle)->SetDemand(param);
1987}
1988CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)
1989{
1990 return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);
1991}
1992CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)
1993{
1994 return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);
1995}
1996CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)
1997{
1998 return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);
1999}
2000CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)
2001{
2002 return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);
2003}
2004CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)
2005{
2006 return ((CanTalonSRX*)handle)->SetModeSelect(param);
2007}
2008CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)
2009{
2010 return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);
2011}
2012CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)
2013{
2014 return ((CanTalonSRX*)handle)->SetRampThrottle(param);
2015}
2016CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)
2017{
2018 return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);
2019}
2020}