blob: 56e68e1ec1466e00d3512d13effc8e1260888966 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/**
2 * @brief CAN TALON SRX driver.
3 *
4 * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs
5 * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate
6 * The getters for these unsolicited signals are auto generated at the bottom of this module.
7 *
8 * Likewise most control signals are sent periodically using the fire-and-forget CAN API.
9 * The setters for these unsolicited signals are auto generated at the bottom of this module.
10 *
11 * Signals that are not available in an unsolicited fashion are the Close Loop gains.
12 * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once
13 * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are
14 * loaded in the TALON, they will persist through power cycles and mode changes.
15 *
16 * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from
17 * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.
18 *
19 * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely
20 * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.
21 * If this API is used, be mindful of the CAN utilization reported in the driver station.
22 *
23 * If calling application has used the config routines to configure the selected feedback sensor, then all positions are measured in
24 * floating point precision rotations. All sensor velocities are specified in floating point precision RPM.
25 * @see ConfigPotentiometerTurns
26 * @see ConfigEncoderCodesPerRev
27 * HOWEVER, if calling application has not called the config routine for selected feedback sensor, then all getters/setters for
28 * position/velocity use the native engineering units of the Talon SRX firm (just like in 2015). Signals explained below.
29 *
30 * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode).
31 * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).
32 * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition()
33 * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default).
34 * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.
35 *
36 * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
37 * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation
38 * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor
39 * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.
40 *
41 * Velocity is in position ticks / 100ms.
42 *
43 * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).
44 * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).
45 *
46 * Pos and velocity close loops are calc'd as
47 * err = target - posOrVel.
48 * iErr += err;
49 * if( (IZone!=0) and abs(err) > IZone)
50 * ClearIaccum()
51 * output = P X err + I X iErr + D X dErr + F X target
52 * dErr = err - lastErr
53 * P, I,and D gains are always positive. F can be negative.
54 * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.
55 * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.
56 *
57 * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1
58 * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
59 *
60 * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)
61 * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
62 * Close loop and integral accumulator runs every 1ms.
63 *
64 * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)
65 * per change of 1 unit (ADC or encoder) per ms.
66 *
67 * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of
68 * this value, the integrated error will auto-clear...
69 * if( (IZone!=0) and abs(err) > IZone)
70 * ClearIaccum()
71 * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.
72 *
73 * CloseLoopRampRate is in throttle units per 1ms. Set to zero to disable ramping.
74 * Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.
75 *
76 * auto generated using spreadsheet and WpiClassGen.csproj
77 * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
78 */
79#include "HAL/CanTalonSRX.h"
80#include "FRC_NetworkCommunication/CANSessionMux.h" //CAN Comm
81#include <string.h> // memset
82#include <unistd.h> // usleep
83
84#define STATUS_1 0x02041400
85#define STATUS_2 0x02041440
86#define STATUS_3 0x02041480
87#define STATUS_4 0x020414C0
88#define STATUS_5 0x02041500
89#define STATUS_6 0x02041540
90#define STATUS_7 0x02041580
91#define STATUS_8 0x020415C0
92
93#define CONTROL_1 0x02040000
94#define CONTROL_2 0x02040040
95#define CONTROL_3 0x02040080
96
97#define EXPECTED_RESPONSE_TIMEOUT_MS (200)
98#define GET_STATUS1() CtreCanNode::recMsg<TALON_Status_1_General_10ms_t > rx = GetRx<TALON_Status_1_General_10ms_t>(STATUS_1 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
99#define GET_STATUS2() CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t > rx = GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
100#define GET_STATUS3() CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t > rx = GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
101#define GET_STATUS4() CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx = GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
102#define GET_STATUS5() CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t > rx = GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
103#define GET_STATUS6() CtreCanNode::recMsg<TALON_Status_6_Eol_t > rx = GetRx<TALON_Status_6_Eol_t>(STATUS_6 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
104#define GET_STATUS7() CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t > rx = GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
105#define GET_STATUS8() CtreCanNode::recMsg<TALON_Status_8_PulseWid_100ms_t > rx = GetRx<TALON_Status_8_PulseWid_100ms_t>(STATUS_8 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
106
107#define PARAM_REQUEST 0x02041800
108#define PARAM_RESPONSE 0x02041840
109#define PARAM_SET 0x02041880
110
111const int kParamArbIdValue = PARAM_RESPONSE;
112const int kParamArbIdMask = 0xFFFFFFFF;
113
114const double FLOAT_TO_FXP_10_22 = (double)0x400000;
115const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625;
116
117const double FLOAT_TO_FXP_0_8 = (double)0x100;
118const double FXP_TO_FLOAT_0_8 = 0.00390625;
119
120/* encoder/decoders */
121/** control */
122typedef struct _TALON_Control_1_General_10ms_t {
123 unsigned TokenH:8;
124 unsigned TokenL:8;
125 unsigned DemandH:8;
126 unsigned DemandM:8;
127 unsigned DemandL:8;
128 unsigned ProfileSlotSelect:1;
129 unsigned FeedbackDeviceSelect:4;
130 unsigned OverrideLimitSwitchEn:3;
131 unsigned RevFeedbackSensor:1;
132 unsigned RevMotDuringCloseLoopEn:1;
133 unsigned OverrideBrakeType:2;
134 unsigned ModeSelect:4;
135 unsigned RampThrottle:8;
136} TALON_Control_1_General_10ms_t ;
137typedef struct _TALON_Control_2_Rates_OneShot_t {
138 unsigned Status1Ms:8;
139 unsigned Status2Ms:8;
140 unsigned Status3Ms:8;
141 unsigned Status4Ms:8;
142 unsigned StatusPulWidMs:8; // TALON_Status_8_PulseWid_100ms_t
143} TALON_Control_2_Rates_OneShot_t ;
144typedef struct _TALON_Control_3_ClearFlags_OneShot_t {
145 unsigned ZeroFeedbackSensor:1;
146 unsigned ClearStickyFaults:1;
147} TALON_Control_3_ClearFlags_OneShot_t ;
148
149/** status */
150typedef struct _TALON_Status_1_General_10ms_t {
151 unsigned CloseLoopErrH:8;
152 unsigned CloseLoopErrM:8;
153 unsigned CloseLoopErrL:8;
154 unsigned AppliedThrottle_h3:3;
155 unsigned Fault_RevSoftLim:1;
156 unsigned Fault_ForSoftLim:1;
157 unsigned TokLocked:1;
158 unsigned LimitSwitchClosedRev:1;
159 unsigned LimitSwitchClosedFor:1;
160 unsigned AppliedThrottle_l8:8;
161 unsigned ModeSelect_h1:1;
162 unsigned FeedbackDeviceSelect:4;
163 unsigned LimitSwitchEn:3;
164 unsigned Fault_HardwareFailure:1;
165 unsigned Fault_RevLim:1;
166 unsigned Fault_ForLim:1;
167 unsigned Fault_UnderVoltage:1;
168 unsigned Fault_OverTemp:1;
169 unsigned ModeSelect_b3:3;
170 unsigned TokenSeed:8;
171} TALON_Status_1_General_10ms_t ;
172typedef struct _TALON_Status_2_Feedback_20ms_t {
173 unsigned SensorPositionH:8;
174 unsigned SensorPositionM:8;
175 unsigned SensorPositionL:8;
176 unsigned SensorVelocityH:8;
177 unsigned SensorVelocityL:8;
178 unsigned Current_h8:8;
179 unsigned StckyFault_RevSoftLim:1;
180 unsigned StckyFault_ForSoftLim:1;
181 unsigned StckyFault_RevLim:1;
182 unsigned StckyFault_ForLim:1;
183 unsigned StckyFault_UnderVoltage:1;
184 unsigned StckyFault_OverTemp:1;
185 unsigned Current_l2:2;
186 unsigned reserved2:4;
187 unsigned VelDiv4:1;
188 unsigned PosDiv8:1;
189 unsigned ProfileSlotSelect:1;
190 unsigned BrakeIsEnabled:1;
191} TALON_Status_2_Feedback_20ms_t ;
192typedef struct _TALON_Status_3_Enc_100ms_t {
193 unsigned EncPositionH:8;
194 unsigned EncPositionM:8;
195 unsigned EncPositionL:8;
196 unsigned EncVelH:8;
197 unsigned EncVelL:8;
198 unsigned EncIndexRiseEventsH:8;
199 unsigned EncIndexRiseEventsL:8;
200 unsigned reserved:3;
201 unsigned VelDiv4:1;
202 unsigned PosDiv8:1;
203 unsigned QuadIdxpin:1;
204 unsigned QuadBpin:1;
205 unsigned QuadApin:1;
206} TALON_Status_3_Enc_100ms_t ;
207typedef struct _TALON_Status_4_AinTempVbat_100ms_t {
208 unsigned AnalogInWithOvH:8;
209 unsigned AnalogInWithOvM:8;
210 unsigned AnalogInWithOvL:8;
211 unsigned AnalogInVelH:8;
212 unsigned AnalogInVelL:8;
213 unsigned Temp:8;
214 unsigned BatteryV:8;
215 unsigned reserved:6;
216 unsigned VelDiv4:1;
217 unsigned PosDiv8:1;
218} TALON_Status_4_AinTempVbat_100ms_t ;
219typedef struct _TALON_Status_5_Startup_OneShot_t {
220 unsigned ResetCountH:8;
221 unsigned ResetCountL:8;
222 unsigned ResetFlagsH:8;
223 unsigned ResetFlagsL:8;
224 unsigned FirmVersH:8;
225 unsigned FirmVersL:8;
226} TALON_Status_5_Startup_OneShot_t ;
227typedef struct _TALON_Status_6_Eol_t {
228 unsigned currentAdcUncal_h2:2;
229 unsigned reserved1:5;
230 unsigned SpiCsPin_GadgeteerPin6:1;
231 unsigned currentAdcUncal_l8:8;
232 unsigned tempAdcUncal_h2:2;
233 unsigned reserved2:6;
234 unsigned tempAdcUncal_l8:8;
235 unsigned vbatAdcUncal_h2:2;
236 unsigned reserved3:6;
237 unsigned vbatAdcUncal_l8:8;
238 unsigned analogAdcUncal_h2:2;
239 unsigned reserved4:6;
240 unsigned analogAdcUncal_l8:8;
241} TALON_Status_6_Eol_t ;
242typedef struct _TALON_Status_7_Debug_200ms_t {
243 unsigned TokenizationFails_h8:8;
244 unsigned TokenizationFails_l8:8;
245 unsigned LastFailedToken_h8:8;
246 unsigned LastFailedToken_l8:8;
247 unsigned TokenizationSucceses_h8:8;
248 unsigned TokenizationSucceses_l8:8;
249} TALON_Status_7_Debug_200ms_t ;
250typedef struct _TALON_Status_8_PulseWid_100ms_t {
251 unsigned PulseWidPositionH:8;
252 unsigned PulseWidPositionM:8;
253 unsigned PulseWidPositionL:8;
254 unsigned reserved:6;
255 unsigned VelDiv4:1;
256 unsigned PosDiv8:1;
257 unsigned PeriodUsM8:8;
258 unsigned PeriodUsL8:8;
259 unsigned PulseWidVelH:8;
260 unsigned PulseWidVelL:8;
261} TALON_Status_8_PulseWid_100ms_t ;
262typedef struct _TALON_Param_Request_t {
263 unsigned ParamEnum:8;
264} TALON_Param_Request_t ;
265typedef struct _TALON_Param_Response_t {
266 unsigned ParamEnum:8;
267 unsigned ParamValueL:8;
268 unsigned ParamValueML:8;
269 unsigned ParamValueMH:8;
270 unsigned ParamValueH:8;
271} TALON_Param_Response_t ;
272
273CanTalonSRX::CanTalonSRX(int deviceNumber,int controlPeriodMs): CtreCanNode(deviceNumber), _can_h(0), _can_stat(0)
274{
275 /* bound period to be within [1 ms,95 ms] */
276 if(controlPeriodMs < 1)
277 controlPeriodMs = 1;
278 else if(controlPeriodMs > 95)
279 controlPeriodMs = 95;
280 RegisterRx(STATUS_1 | (UINT8)deviceNumber );
281 RegisterRx(STATUS_2 | (UINT8)deviceNumber );
282 RegisterRx(STATUS_3 | (UINT8)deviceNumber );
283 RegisterRx(STATUS_4 | (UINT8)deviceNumber );
284 RegisterRx(STATUS_5 | (UINT8)deviceNumber );
285 RegisterRx(STATUS_6 | (UINT8)deviceNumber );
286 RegisterRx(STATUS_7 | (UINT8)deviceNumber );
287 RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)controlPeriodMs);
288 /* the only default param that is nonzero is limit switch.
289 * Default to using the flash settings. */
290 SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);
291}
292/* CanTalonSRX D'tor
293 */
294CanTalonSRX::~CanTalonSRX()
295{
296 if (m_hasBeenMoved){
297 /* Another CANTalonSRX still exists, so
298 don't un-register the periodic control frame */
299 }else{
300 /* un-register the control frame so Talon is disabled */
301 RegisterTx(CONTROL_1 | (UINT8)GetDeviceNumber(), 0);
302 }
303 /* free the stream we used for SetParam/GetParamResponse */
304 if(_can_h){
305 FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);
306 _can_h = 0;
307 }
308}
309void CanTalonSRX::OpenSessionIfNeedBe()
310{
311 _can_stat = 0;
312 if (_can_h == 0) {
313 /* bit30 - bit8 must match $000002XX. Top bit is not masked to get remote frames */
314 FRC_NetworkCommunication_CANSessionMux_openStreamSession(&_can_h,kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask, kMsgCapacity, &_can_stat);
315 if (_can_stat == 0) {
316 /* success */
317 } else {
318 /* something went wrong, try again later */
319 _can_h = 0;
320 }
321 }
322}
323void CanTalonSRX::ProcessStreamMessages()
324{
325 if(0 == _can_h)
326 OpenSessionIfNeedBe();
327 /* process receive messages */
328 uint32_t i;
329 uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);
330 uint32_t messagesRead = 0;
331 /* read out latest bunch of messages */
332 _can_stat = 0;
333 if (_can_h){
334 FRC_NetworkCommunication_CANSessionMux_readStreamSession(_can_h,_msgBuff, messagesToRead, &messagesRead, &_can_stat);
335 }
336 /* loop thru each message of interest */
337 for (i = 0; i < messagesRead; ++i) {
338 tCANStreamMessage * msg = _msgBuff + i;
339 if(msg->messageID == (PARAM_RESPONSE | GetDeviceNumber()) ){
340 TALON_Param_Response_t * paramResp = (TALON_Param_Response_t*)msg->data;
341 /* decode value */
342 int32_t val = paramResp->ParamValueH;
343 val <<= 8;
344 val |= paramResp->ParamValueMH;
345 val <<= 8;
346 val |= paramResp->ParamValueML;
347 val <<= 8;
348 val |= paramResp->ParamValueL;
349 /* save latest signal */
350 _sigs[paramResp->ParamEnum] = val;
351 }else{
352 int brkpthere = 42;
353 ++brkpthere;
354 }
355 }
356}
357void CanTalonSRX::Set(double value)
358{
359 if(value > 1)
360 value = 1;
361 else if(value < -1)
362 value = -1;
363 SetDemand(1023*value); /* must be within [-1023,1023] */
364}
365/*---------------------setters and getters that use the param request/response-------------*/
366/**
367 * Send a one shot frame to set an arbitrary signal.
368 * Most signals are in the control frame so avoid using this API unless you have to.
369 * Use this api for...
370 * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically.
371 * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame.
372 * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.
373 */
374CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits)
375{
376 /* caller is using param API. Open session if it hasn'T been done. */
377 if(0 == _can_h)
378 OpenSessionIfNeedBe();
379 TALON_Param_Response_t frame;
380 memset(&frame,0,sizeof(frame));
381 frame.ParamEnum = paramEnum;
382 frame.ParamValueH = rawBits >> 0x18;
383 frame.ParamValueMH = rawBits >> 0x10;
384 frame.ParamValueML = rawBits >> 0x08;
385 frame.ParamValueL = rawBits;
386 int32_t status = 0;
387 FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_SET | GetDeviceNumber(), (const uint8_t*)&frame, 5, 0, &status);
388 if(status)
389 return CTR_TxFailed;
390 return CTR_OKAY;
391}
392/**
393 * Checks cached CAN frames and updating solicited signals.
394 */
395CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int & rawBits)
396{
397 CTR_Code retval = CTR_OKAY;
398 /* process received param events. We don't expect many since this API is not used often. */
399 ProcessStreamMessages();
400 /* grab the solicited signal value */
401 sigs_t::iterator i = _sigs.find(paramEnum);
402 if(i == _sigs.end()){
403 retval = CTR_SigNotUpdated;
404 }else{
405 rawBits = i->second;
406 }
407 return retval;
408}
409/**
410 * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically.
411 * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.
412 * @param param to request.
413 */
414CTR_Code CanTalonSRX::RequestParam(param_t paramEnum)
415{
416 /* process received param events. We don't expect many since this API is not used often. */
417 ProcessStreamMessages();
418 TALON_Param_Request_t frame;
419 memset(&frame,0,sizeof(frame));
420 frame.ParamEnum = paramEnum;
421 int32_t status = 0;
422 FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_REQUEST | GetDeviceNumber(), (const uint8_t*)&frame, 1, 0, &status);
423 if(status)
424 return CTR_TxFailed;
425 return CTR_OKAY;
426}
427
428CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value)
429{
430 int32_t rawbits = 0;
431 switch(paramEnum){
432 case eProfileParamSlot0_P:/* unsigned 10.22 fixed pt value */
433 case eProfileParamSlot0_I:
434 case eProfileParamSlot0_D:
435 case eProfileParamSlot1_P:
436 case eProfileParamSlot1_I:
437 case eProfileParamSlot1_D:
438 {
439 uint32_t urawbits;
440 value = std::min(value,1023.0); /* bounds check doubles that are outside u10.22 */
441 value = std::max(value,0.0);
442 urawbits = value * FLOAT_TO_FXP_10_22; /* perform unsign arithmetic */
443 rawbits = urawbits; /* copy bits over. SetParamRaw just stuffs into CAN frame with no sense of signedness */
444 } break;
445 case eProfileParamSlot1_F: /* signed 10.22 fixed pt value */
446 case eProfileParamSlot0_F:
447 value = std::min(value, 512.0); /* bounds check doubles that are outside s10.22 */
448 value = std::max(value,-512.0);
449 rawbits = value * FLOAT_TO_FXP_10_22;
450 break;
451 case eProfileParamVcompRate: /* unsigned 0.8 fixed pt value volts per ms */
452 /* within [0,1) volts per ms.
453 Slowest ramp is 1/256 VperMilliSec or 3.072 seconds from 0-to-12V.
454 Fastest ramp is 255/256 VperMilliSec or 12.1ms from 0-to-12V.
455 */
456 if(value <= 0){
457 /* negative or zero (disable), send raw value of zero */
458 rawbits = 0;
459 }else{
460 /* nonzero ramping */
461 rawbits = value * FLOAT_TO_FXP_0_8;
462 /* since whole part is cleared, cap to just under whole unit */
463 if(rawbits > (FLOAT_TO_FXP_0_8-1) )
464 rawbits = (FLOAT_TO_FXP_0_8-1);
465 /* since ramping is nonzero, cap to smallest ramp rate possible */
466 if(rawbits == 0){
467 /* caller is providing a nonzero ramp rate that's too small
468 to serialize, so cap to smallest possible */
469 rawbits = 1;
470 }
471 }
472 break;
473 default: /* everything else is integral */
474 rawbits = (int32_t)value;
475 break;
476 }
477 return SetParamRaw(paramEnum,rawbits);
478}
479CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double & value)
480{
481 int32_t rawbits = 0;
482 CTR_Code retval = GetParamResponseRaw(paramEnum,rawbits);
483 switch(paramEnum){
484 case eProfileParamSlot0_P:/* 10.22 fixed pt value */
485 case eProfileParamSlot0_I:
486 case eProfileParamSlot0_D:
487 case eProfileParamSlot0_F:
488 case eProfileParamSlot1_P:
489 case eProfileParamSlot1_I:
490 case eProfileParamSlot1_D:
491 case eProfileParamSlot1_F:
492 case eCurrent:
493 case eTemp:
494 case eBatteryV:
495 value = ((double)rawbits) * FXP_TO_FLOAT_10_22;
496 break;
497 case eProfileParamVcompRate:
498 value = ((double)rawbits) * FXP_TO_FLOAT_0_8;
499 break;
500 default: /* everything else is integral */
501 value = (double)rawbits;
502 break;
503 }
504 return retval;
505}
506CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int & value)
507{
508 double dvalue = 0;
509 CTR_Code retval = GetParamResponse(paramEnum, dvalue);
510 value = (int32_t)dvalue;
511 return retval;
512}
513/*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/
514/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/
515/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/
516/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/
517CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx,double gain)
518{
519 if(slotIdx == 0)
520 return SetParam(eProfileParamSlot0_P, gain);
521 return SetParam(eProfileParamSlot1_P, gain);
522}
523CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx,double gain)
524{
525 if(slotIdx == 0)
526 return SetParam(eProfileParamSlot0_I, gain);
527 return SetParam(eProfileParamSlot1_I, gain);
528}
529CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx,double gain)
530{
531 if(slotIdx == 0)
532 return SetParam(eProfileParamSlot0_D, gain);
533 return SetParam(eProfileParamSlot1_D, gain);
534}
535CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx,double gain)
536{
537 if(slotIdx == 0)
538 return SetParam(eProfileParamSlot0_F, gain);
539 return SetParam(eProfileParamSlot1_F, gain);
540}
541CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx,int zone)
542{
543 if(slotIdx == 0)
544 return SetParam(eProfileParamSlot0_IZone, zone);
545 return SetParam(eProfileParamSlot1_IZone, zone);
546}
547CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate)
548{
549 if(slotIdx == 0)
550 return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
551 return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
552}
553CTR_Code CanTalonSRX::SetVoltageCompensationRate(double voltagePerMs)
554{
555 return SetParam(eProfileParamVcompRate, voltagePerMs);
556}
557CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx,double & gain)
558{
559 if(slotIdx == 0)
560 return GetParamResponse(eProfileParamSlot0_P, gain);
561 return GetParamResponse(eProfileParamSlot1_P, gain);
562}
563CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx,double & gain)
564{
565 if(slotIdx == 0)
566 return GetParamResponse(eProfileParamSlot0_I, gain);
567 return GetParamResponse(eProfileParamSlot1_I, gain);
568}
569CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx,double & gain)
570{
571 if(slotIdx == 0)
572 return GetParamResponse(eProfileParamSlot0_D, gain);
573 return GetParamResponse(eProfileParamSlot1_D, gain);
574}
575CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx,double & gain)
576{
577 if(slotIdx == 0)
578 return GetParamResponse(eProfileParamSlot0_F, gain);
579 return GetParamResponse(eProfileParamSlot1_F, gain);
580}
581CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx,int & zone)
582{
583 if(slotIdx == 0)
584 return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);
585 return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);
586}
587CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate)
588{
589 if(slotIdx == 0)
590 return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
591 return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
592}
593CTR_Code CanTalonSRX::GetVoltageCompensationRate(double & voltagePerMs)
594{
595 return GetParamResponse(eProfileParamVcompRate, voltagePerMs);
596}
597CTR_Code CanTalonSRX::SetSensorPosition(int pos)
598{
599 return SetParam(eSensorPosition, pos);
600}
601CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit)
602{
603 return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);
604}
605CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit)
606{
607 return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);
608}
609CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable)
610{
611 return SetParam(eProfileParamSoftLimitForEnable, enable);
612}
613CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable)
614{
615 return SetParam(eProfileParamSoftLimitRevEnable, enable);
616}
617CTR_Code CanTalonSRX::GetForwardSoftLimit(int & forwardLimit)
618{
619 return GetParamResponseInt32(eProfileParamSoftLimitForThreshold, forwardLimit);
620}
621CTR_Code CanTalonSRX::GetReverseSoftLimit(int & reverseLimit)
622{
623 return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold, reverseLimit);
624}
625CTR_Code CanTalonSRX::GetForwardSoftEnable(int & enable)
626{
627 return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);
628}
629CTR_Code CanTalonSRX::GetReverseSoftEnable(int & enable)
630{
631 return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);
632}
633/**
634 * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available.
635 */
636CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum, unsigned periodMs)
637{
638 CTR_Code retval = CTR_OKAY;
639 int32_t paramEnum = 0;
640 /* bounds check the period */
641 if(periodMs < 1)
642 periodMs = 1;
643 else if (periodMs > 255)
644 periodMs = 255;
645 uint8_t period = (uint8_t)periodMs;
646 /* lookup the correct param enum based on what frame to rate-change */
647 switch(frameEnum){
648 case kStatusFrame_General:
649 paramEnum = eStatus1FrameRate;
650 break;
651 case kStatusFrame_Feedback:
652 paramEnum = eStatus2FrameRate;
653 break;
654 case kStatusFrame_Encoder:
655 paramEnum = eStatus3FrameRate;
656 break;
657 case kStatusFrame_AnalogTempVbat:
658 paramEnum = eStatus4FrameRate;
659 break;
660 case kStatusFrame_PulseWidthMeas:
661 paramEnum = eStatus8FrameRate;
662 break;
663 default:
664 /* caller's request is not support, return an error code */
665 retval = CTR_InvalidParamValue;
666 break;
667 }
668 /* if lookup was succesful, send set-request out */
669 if(retval == CTR_OKAY){
670 /* paramEnum is updated, sent it out */
671 retval = SetParamRaw(paramEnum, period);
672 }
673 return retval;
674}
675/**
676 * Clear all sticky faults in TALON.
677 */
678CTR_Code CanTalonSRX::ClearStickyFaults()
679{
680 int32_t status = 0;
681 /* build request frame */
682 TALON_Control_3_ClearFlags_OneShot_t frame;
683 memset(&frame,0,sizeof(frame));
684 frame.ClearStickyFaults = 1;
685 FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_3 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status);
686 if(status)
687 return CTR_TxFailed;
688 return CTR_OKAY;
689}
690/*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/
691/*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/
692CTR_Code CanTalonSRX::GetFault_OverTemp(int &param)
693{
694 GET_STATUS1();
695 param = rx->Fault_OverTemp;
696 return rx.err;
697}
698CTR_Code CanTalonSRX::GetFault_UnderVoltage(int &param)
699{
700 GET_STATUS1();
701 param = rx->Fault_UnderVoltage;
702 return rx.err;
703}
704CTR_Code CanTalonSRX::GetFault_ForLim(int &param)
705{
706 GET_STATUS1();
707 param = rx->Fault_ForLim;
708 return rx.err;
709}
710CTR_Code CanTalonSRX::GetFault_RevLim(int &param)
711{
712 GET_STATUS1();
713 param = rx->Fault_RevLim;
714 return rx.err;
715}
716CTR_Code CanTalonSRX::GetFault_HardwareFailure(int &param)
717{
718 GET_STATUS1();
719 param = rx->Fault_HardwareFailure;
720 return rx.err;
721}
722CTR_Code CanTalonSRX::GetFault_ForSoftLim(int &param)
723{
724 GET_STATUS1();
725 param = rx->Fault_ForSoftLim;
726 return rx.err;
727}
728CTR_Code CanTalonSRX::GetFault_RevSoftLim(int &param)
729{
730 GET_STATUS1();
731 param = rx->Fault_RevSoftLim;
732 return rx.err;
733}
734CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int &param)
735{
736 GET_STATUS2();
737 param = rx->StckyFault_OverTemp;
738 return rx.err;
739}
740CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int &param)
741{
742 GET_STATUS2();
743 param = rx->StckyFault_UnderVoltage;
744 return rx.err;
745}
746CTR_Code CanTalonSRX::GetStckyFault_ForLim(int &param)
747{
748 GET_STATUS2();
749 param = rx->StckyFault_ForLim;
750 return rx.err;
751}
752CTR_Code CanTalonSRX::GetStckyFault_RevLim(int &param)
753{
754 GET_STATUS2();
755 param = rx->StckyFault_RevLim;
756 return rx.err;
757}
758CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int &param)
759{
760 GET_STATUS2();
761 param = rx->StckyFault_ForSoftLim;
762 return rx.err;
763}
764CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int &param)
765{
766 GET_STATUS2();
767 param = rx->StckyFault_RevSoftLim;
768 return rx.err;
769}
770CTR_Code CanTalonSRX::GetAppliedThrottle(int &param)
771{
772 GET_STATUS1();
773 int32_t raw = 0;
774 raw |= rx->AppliedThrottle_h3;
775 raw <<= 8;
776 raw |= rx->AppliedThrottle_l8;
777 raw <<= (32-11); /* sign extend */
778 raw >>= (32-11); /* sign extend */
779 param = (int)raw;
780 return rx.err;
781}
782CTR_Code CanTalonSRX::GetCloseLoopErr(int &param)
783{
784 GET_STATUS1();
785 int32_t raw = 0;
786 raw |= rx->CloseLoopErrH;
787 raw <<= 8;
788 raw |= rx->CloseLoopErrM;
789 raw <<= 8;
790 raw |= rx->CloseLoopErrL;
791 raw <<= (32-24); /* sign extend */
792 raw >>= (32-24); /* sign extend */
793 param = (int)raw;
794 return rx.err;
795}
796CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int &param)
797{
798 GET_STATUS1();
799 param = rx->FeedbackDeviceSelect;
800 return rx.err;
801}
802CTR_Code CanTalonSRX::GetModeSelect(int &param)
803{
804 GET_STATUS1();
805 uint32_t raw = 0;
806 raw |= rx->ModeSelect_h1;
807 raw <<= 3;
808 raw |= rx->ModeSelect_b3;
809 param = (int)raw;
810 return rx.err;
811}
812CTR_Code CanTalonSRX::GetLimitSwitchEn(int &param)
813{
814 GET_STATUS1();
815 param = rx->LimitSwitchEn;
816 return rx.err;
817}
818CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int &param)
819{
820 GET_STATUS1();
821 param = rx->LimitSwitchClosedFor;
822 return rx.err;
823}
824CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int &param)
825{
826 GET_STATUS1();
827 param = rx->LimitSwitchClosedRev;
828 return rx.err;
829}
830CTR_Code CanTalonSRX::GetSensorPosition(int &param)
831{
832 GET_STATUS2();
833 int32_t raw = 0;
834 raw |= rx->SensorPositionH;
835 raw <<= 8;
836 raw |= rx->SensorPositionM;
837 raw <<= 8;
838 raw |= rx->SensorPositionL;
839 raw <<= (32-24); /* sign extend */
840 raw >>= (32-24); /* sign extend */
841 if(rx->PosDiv8)
842 raw *= 8;
843 param = (int)raw;
844 return rx.err;
845}
846CTR_Code CanTalonSRX::GetSensorVelocity(int &param)
847{
848 GET_STATUS2();
849 int32_t raw = 0;
850 raw |= rx->SensorVelocityH;
851 raw <<= 8;
852 raw |= rx->SensorVelocityL;
853 raw <<= (32-16); /* sign extend */
854 raw >>= (32-16); /* sign extend */
855 if(rx->VelDiv4)
856 raw *= 4;
857 param = (int)raw;
858 return rx.err;
859}
860CTR_Code CanTalonSRX::GetCurrent(double &param)
861{
862 GET_STATUS2();
863 uint32_t raw = 0;
864 raw |= rx->Current_h8;
865 raw <<= 2;
866 raw |= rx->Current_l2;
867 param = (double)raw * 0.125 + 0;
868 return rx.err;
869}
870CTR_Code CanTalonSRX::GetBrakeIsEnabled(int &param)
871{
872 GET_STATUS2();
873 param = rx->BrakeIsEnabled;
874 return rx.err;
875}
876CTR_Code CanTalonSRX::GetEncPosition(int &param)
877{
878 GET_STATUS3();
879 int32_t raw = 0;
880 raw |= rx->EncPositionH;
881 raw <<= 8;
882 raw |= rx->EncPositionM;
883 raw <<= 8;
884 raw |= rx->EncPositionL;
885 raw <<= (32-24); /* sign extend */
886 raw >>= (32-24); /* sign extend */
887 if(rx->PosDiv8)
888 raw *= 8;
889 param = (int)raw;
890 return rx.err;
891}
892CTR_Code CanTalonSRX::GetEncVel(int &param)
893{
894 GET_STATUS3();
895 int32_t raw = 0;
896 raw |= rx->EncVelH;
897 raw <<= 8;
898 raw |= rx->EncVelL;
899 raw <<= (32-16); /* sign extend */
900 raw >>= (32-16); /* sign extend */
901 if(rx->VelDiv4)
902 raw *= 4;
903 param = (int)raw;
904 return rx.err;
905}
906CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int &param)
907{
908 GET_STATUS3();
909 uint32_t raw = 0;
910 raw |= rx->EncIndexRiseEventsH;
911 raw <<= 8;
912 raw |= rx->EncIndexRiseEventsL;
913 param = (int)raw;
914 return rx.err;
915}
916CTR_Code CanTalonSRX::GetQuadApin(int &param)
917{
918 GET_STATUS3();
919 param = rx->QuadApin;
920 return rx.err;
921}
922CTR_Code CanTalonSRX::GetQuadBpin(int &param)
923{
924 GET_STATUS3();
925 param = rx->QuadBpin;
926 return rx.err;
927}
928CTR_Code CanTalonSRX::GetQuadIdxpin(int &param)
929{
930 GET_STATUS3();
931 param = rx->QuadIdxpin;
932 return rx.err;
933}
934CTR_Code CanTalonSRX::GetAnalogInWithOv(int &param)
935{
936 GET_STATUS4();
937 int32_t raw = 0;
938 raw |= rx->AnalogInWithOvH;
939 raw <<= 8;
940 raw |= rx->AnalogInWithOvM;
941 raw <<= 8;
942 raw |= rx->AnalogInWithOvL;
943 raw <<= (32-24); /* sign extend */
944 raw >>= (32-24); /* sign extend */
945 if(rx->PosDiv8)
946 raw *= 8;
947 param = (int)raw;
948 return rx.err;
949}
950CTR_Code CanTalonSRX::GetAnalogInVel(int &param)
951{
952 GET_STATUS4();
953 int32_t raw = 0;
954 raw |= rx->AnalogInVelH;
955 raw <<= 8;
956 raw |= rx->AnalogInVelL;
957 raw <<= (32-16); /* sign extend */
958 raw >>= (32-16); /* sign extend */
959 if(rx->VelDiv4)
960 raw *= 4;
961 param = (int)raw;
962 return rx.err;
963}
964CTR_Code CanTalonSRX::GetTemp(double &param)
965{
966 GET_STATUS4();
967 uint32_t raw = rx->Temp;
968 param = (double)raw * 0.6451612903 + -50;
969 return rx.err;
970}
971CTR_Code CanTalonSRX::GetBatteryV(double &param)
972{
973 GET_STATUS4();
974 uint32_t raw = rx->BatteryV;
975 param = (double)raw * 0.05 + 4;
976 return rx.err;
977}
978CTR_Code CanTalonSRX::GetResetCount(int &param)
979{
980 GET_STATUS5();
981 uint32_t raw = 0;
982 raw |= rx->ResetCountH;
983 raw <<= 8;
984 raw |= rx->ResetCountL;
985 param = (int)raw;
986 return rx.err;
987}
988CTR_Code CanTalonSRX::GetResetFlags(int &param)
989{
990 GET_STATUS5();
991 uint32_t raw = 0;
992 raw |= rx->ResetFlagsH;
993 raw <<= 8;
994 raw |= rx->ResetFlagsL;
995 param = (int)raw;
996 return rx.err;
997}
998CTR_Code CanTalonSRX::GetFirmVers(int &param)
999{
1000 GET_STATUS5();
1001 uint32_t raw = 0;
1002 raw |= rx->FirmVersH;
1003 raw <<= 8;
1004 raw |= rx->FirmVersL;
1005 param = (int)raw;
1006 return rx.err;
1007}
1008CTR_Code CanTalonSRX::SetDemand(int param)
1009{
1010 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1011 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1012 toFill->DemandH = param>>16;
1013 toFill->DemandM = param>>8;
1014 toFill->DemandL = param>>0;
1015 FlushTx(toFill);
1016 return CTR_OKAY;
1017}
1018CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)
1019{
1020 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1021 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1022 toFill->OverrideLimitSwitchEn = param;
1023 FlushTx(toFill);
1024 return CTR_OKAY;
1025}
1026CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)
1027{
1028 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1029 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1030 toFill->FeedbackDeviceSelect = param;
1031 FlushTx(toFill);
1032 return CTR_OKAY;
1033}
1034CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)
1035{
1036 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1037 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1038 toFill->RevMotDuringCloseLoopEn = param;
1039 FlushTx(toFill);
1040 return CTR_OKAY;
1041}
1042CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)
1043{
1044 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1045 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1046 toFill->OverrideBrakeType = param;
1047 FlushTx(toFill);
1048 return CTR_OKAY;
1049}
1050CTR_Code CanTalonSRX::SetModeSelect(int param)
1051{
1052 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1053 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1054 toFill->ModeSelect = param;
1055 FlushTx(toFill);
1056 return CTR_OKAY;
1057}
1058/**
1059 * @param modeSelect selects which mode.
1060 * @param demand setpt or throttle or masterId to follow.
1061 * @return error code, 0 iff successful.
1062 * This function has the advantage of atomically setting mode and demand.
1063 */
1064CTR_Code CanTalonSRX::SetModeSelect(int modeSelect,int demand)
1065{
1066 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1067 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1068 toFill->ModeSelect = modeSelect;
1069 toFill->DemandH = demand>>16;
1070 toFill->DemandM = demand>>8;
1071 toFill->DemandL = demand>>0;
1072 FlushTx(toFill);
1073 return CTR_OKAY;
1074}
1075CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)
1076{
1077 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1078 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1079 toFill->ProfileSlotSelect = param;
1080 FlushTx(toFill);
1081 return CTR_OKAY;
1082}
1083CTR_Code CanTalonSRX::SetRampThrottle(int param)
1084{
1085 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1086 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1087 toFill->RampThrottle = param;
1088 FlushTx(toFill);
1089 return CTR_OKAY;
1090}
1091CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)
1092{
1093 CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
1094 if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
1095 toFill->RevFeedbackSensor = param ? 1 : 0;
1096 FlushTx(toFill);
1097 return CTR_OKAY;
1098}
1099CTR_Code CanTalonSRX::GetPulseWidthPosition(int &param)
1100{
1101 GET_STATUS8();
1102 int32_t raw = 0;
1103 raw |= rx->PulseWidPositionH;
1104 raw <<= 8;
1105 raw |= rx->PulseWidPositionM;
1106 raw <<= 8;
1107 raw |= rx->PulseWidPositionL;
1108 raw <<= (32-24); /* sign extend */
1109 raw >>= (32-24); /* sign extend */
1110 if(rx->PosDiv8)
1111 raw *= 8;
1112 param = (int)raw;
1113 return rx.err;
1114}
1115CTR_Code CanTalonSRX::GetPulseWidthVelocity(int &param)
1116{
1117 GET_STATUS8();
1118 int32_t raw = 0;
1119 raw |= rx->PulseWidVelH;
1120 raw <<= 8;
1121 raw |= rx->PulseWidVelL;
1122 raw <<= (32-16); /* sign extend */
1123 raw >>= (32-16); /* sign extend */
1124 if(rx->VelDiv4)
1125 raw *= 4;
1126 param = (int)raw;
1127 return rx.err;
1128}
1129/**
1130 * @param param [out] Rise to rise timeperiod in microseconds.
1131 */
1132CTR_Code CanTalonSRX::GetPulseWidthRiseToRiseUs(int &param)
1133{
1134 GET_STATUS8();
1135 uint32_t raw = 0;
1136 raw |= rx->PeriodUsM8;
1137 raw <<= 8;
1138 raw |= rx->PeriodUsL8;
1139 param = (int)raw;
1140 return rx.err;
1141}
1142/**
1143 * @param param [out] Rise to fall time period in microseconds.
1144 */
1145CTR_Code CanTalonSRX::GetPulseWidthRiseToFallUs(int &param)
1146{
1147 int temp = 0;
1148 int periodUs = 0;
1149 /* first grab our 12.12 position */
1150 CTR_Code retval1 = GetPulseWidthPosition(temp);
1151 /* mask off number of turns */
1152 temp &= 0xFFF;
1153 /* next grab the waveform period. This value
1154 * will be zero if we stop getting pulses **/
1155 CTR_Code retval2 = GetPulseWidthRiseToRiseUs(periodUs);
1156 /* now we have 0.12 position that is scaled to the waveform period.
1157 Use fixed pt multiply to scale our 0.16 period into us.*/
1158 param = (temp * periodUs) / BIT12;
1159 /* pass the worst error code to caller.
1160 Assume largest value is the most pressing error code.*/
1161 return (CTR_Code)std::max((int)retval1, (int)retval2);
1162}
1163CTR_Code CanTalonSRX::IsPulseWidthSensorPresent(int &param)
1164{
1165 int periodUs = 0;
1166 CTR_Code retval = GetPulseWidthRiseToRiseUs(periodUs);
1167 /* if a nonzero period is present, we are getting good pules.
1168 Otherwise the sensor is not present. */
1169 if(periodUs != 0)
1170 param = 1;
1171 else
1172 param = 0;
1173 return retval;
1174}
1175//------------------ C interface --------------------------------------------//
1176extern "C" {
1177void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs)
1178{
1179 return new CanTalonSRX(deviceNumber, controlPeriodMs);
1180}
1181void c_TalonSRX_Destroy(void *handle)
1182{
1183 delete (CanTalonSRX*)handle;
1184}
1185CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)
1186{
1187 return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);
1188}
1189CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)
1190{
1191 return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);
1192}
1193CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)
1194{
1195 return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);
1196}
1197CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)
1198{
1199 return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);
1200}
1201CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs)
1202{
1203 return ((CanTalonSRX*)handle)->SetStatusFrameRate(frameEnum, periodMs);
1204}
1205CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)
1206{
1207 return ((CanTalonSRX*)handle)->ClearStickyFaults();
1208}
1209CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)
1210{
1211 return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);
1212}
1213CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)
1214{
1215 return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);
1216}
1217CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)
1218{
1219 return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);
1220}
1221CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)
1222{
1223 return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);
1224}
1225CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)
1226{
1227 return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);
1228}
1229CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)
1230{
1231 return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);
1232}
1233CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)
1234{
1235 return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);
1236}
1237CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)
1238{
1239 return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);
1240}
1241CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)
1242{
1243 return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);
1244}
1245CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)
1246{
1247 return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);
1248}
1249CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)
1250{
1251 return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);
1252}
1253CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)
1254{
1255 return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);
1256}
1257CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)
1258{
1259 return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);
1260}
1261CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)
1262{
1263 return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);
1264}
1265CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)
1266{
1267 return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);
1268}
1269CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)
1270{
1271 return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);
1272}
1273CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)
1274{
1275 return ((CanTalonSRX*)handle)->GetModeSelect(*param);
1276}
1277CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)
1278{
1279 return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);
1280}
1281CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)
1282{
1283 return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);
1284}
1285CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)
1286{
1287 return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);
1288}
1289CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)
1290{
1291 return ((CanTalonSRX*)handle)->GetSensorPosition(*param);
1292}
1293CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)
1294{
1295 return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);
1296}
1297CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)
1298{
1299 return ((CanTalonSRX*)handle)->GetCurrent(*param);
1300}
1301CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)
1302{
1303 return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);
1304}
1305CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)
1306{
1307 return ((CanTalonSRX*)handle)->GetEncPosition(*param);
1308}
1309CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)
1310{
1311 return ((CanTalonSRX*)handle)->GetEncVel(*param);
1312}
1313CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)
1314{
1315 return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);
1316}
1317CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)
1318{
1319 return ((CanTalonSRX*)handle)->GetQuadApin(*param);
1320}
1321CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)
1322{
1323 return ((CanTalonSRX*)handle)->GetQuadBpin(*param);
1324}
1325CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)
1326{
1327 return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);
1328}
1329CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)
1330{
1331 return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);
1332}
1333CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)
1334{
1335 return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);
1336}
1337CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)
1338{
1339 return ((CanTalonSRX*)handle)->GetTemp(*param);
1340}
1341CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)
1342{
1343 return ((CanTalonSRX*)handle)->GetBatteryV(*param);
1344}
1345CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)
1346{
1347 return ((CanTalonSRX*)handle)->GetResetCount(*param);
1348}
1349CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)
1350{
1351 return ((CanTalonSRX*)handle)->GetResetFlags(*param);
1352}
1353CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)
1354{
1355 return ((CanTalonSRX*)handle)->GetFirmVers(*param);
1356}
1357CTR_Code c_TalonSRX_SetDemand(void *handle, int param)
1358{
1359 return ((CanTalonSRX*)handle)->SetDemand(param);
1360}
1361CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)
1362{
1363 return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);
1364}
1365CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)
1366{
1367 return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);
1368}
1369CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)
1370{
1371 return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);
1372}
1373CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)
1374{
1375 return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);
1376}
1377CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)
1378{
1379 return ((CanTalonSRX*)handle)->SetModeSelect(param);
1380}
1381CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)
1382{
1383 return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);
1384}
1385CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)
1386{
1387 return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);
1388}
1389CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)
1390{
1391 return ((CanTalonSRX*)handle)->SetRampThrottle(param);
1392}
1393CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)
1394{
1395 return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);
1396}
1397CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param)
1398{
1399 return ((CanTalonSRX*)handle)->GetPulseWidthPosition(*param);
1400}
1401CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param)
1402{
1403 return ((CanTalonSRX*)handle)->GetPulseWidthVelocity(*param);
1404}
1405CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param)
1406{
1407 return ((CanTalonSRX*)handle)->GetPulseWidthRiseToFallUs(*param);
1408}
1409CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param)
1410{
1411 return ((CanTalonSRX*)handle)->GetPulseWidthRiseToRiseUs(*param);
1412}
1413CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param)
1414{
1415 return ((CanTalonSRX*)handle)->IsPulseWidthSensorPresent(*param);
1416}
1417}