blob: f9372129d5b00d36b5141660c49be968a37d74e2 [file] [log] [blame]
Brian Silverman26e4e522015-12-17 01:56:40 -05001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2014. All Rights Reserved. */
3/* Open Source Software - may be modified and shared by FRC teams. The code */
4/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
5/*----------------------------------------------------------------------------*/
6
7#include "CANTalon.h"
8#include "WPIErrors.h"
9#include <unistd.h> // usleep
10#include <sstream>
11/**
12 * Number of adc engineering units per 0 to 3.3V sweep.
13 * This is necessary for scaling Analog Position in rotations/RPM.
14 */
15const double kNativeAdcUnitsPerRotation = 1024.0;
16/**
17 * Number of pulse width engineering units per full rotation.
18 * This is necessary for scaling Pulse Width Decoded Position in rotations/RPM.
19 */
20const double kNativePwdUnitsPerRotation = 4096.0;
21/**
22 * Number of minutes per 100ms unit. Useful for scaling velocities
23 * measured by Talon's 100ms timebase to rotations per minute.
24 */
25const double kMinutesPer100msUnit = 1.0/600.0;
26
27/**
28 * Constructor for the CANTalon device.
29 * @param deviceNumber The CAN ID of the Talon SRX
30 */
31CANTalon::CANTalon(int deviceNumber)
32 : m_deviceNumber(deviceNumber),
33 m_impl(new CanTalonSRX(deviceNumber)),
34 m_safetyHelper(new MotorSafetyHelper(this)) {
35 ApplyControlMode(m_controlMode);
36 m_impl->SetProfileSlotSelect(m_profile);
37 m_isInverted = false;
38}
39/**
40 * Constructor for the CANTalon device.
41 * @param deviceNumber The CAN ID of the Talon SRX
42 * @param controlPeriodMs The period in ms to send the CAN control frame.
43 * Period is bounded to [1ms,95ms].
44 */
45CANTalon::CANTalon(int deviceNumber, int controlPeriodMs)
46 : m_deviceNumber(deviceNumber),
47 m_impl(new CanTalonSRX(deviceNumber,controlPeriodMs)),
48 m_safetyHelper(new MotorSafetyHelper(this)) {
49 ApplyControlMode(m_controlMode);
50 m_impl->SetProfileSlotSelect(m_profile);
51}
52
53CANTalon::~CANTalon() {
54 if (m_table != nullptr) m_table->RemoveTableListener(this);
55 if (m_hasBeenMoved) return;
56 Disable();
57}
58
59/**
60* Write out the PID value as seen in the PIDOutput base object.
61*
62* @deprecated Call Set instead.
63*
64* @param output Write out the PercentVbus value as was computed by the
65* PIDController
66*/
67void CANTalon::PIDWrite(float output) {
68 if (GetControlMode() == kPercentVbus) {
69 Set(output);
70 } else {
71 wpi_setWPIErrorWithContext(IncompatibleMode,
72 "PID only supported in PercentVbus mode");
73 }
74}
75
76/**
77 * Retrieve the current sensor value. Equivalent to Get().
78 *
79 * @return The current sensor value of the Talon.
80 */
81double CANTalon::PIDGet() { return Get(); }
82
83/**
84 * Gets the current status of the Talon (usually a sensor value).
85 *
86 * In Current mode: returns output current.
87 * In Speed mode: returns current speed.
88 * In Position mode: returns current sensor position.
89 * In PercentVbus and Follower modes: returns current applied throttle.
90 *
91 * @return The current sensor value of the Talon.
92 */
93float CANTalon::Get() const {
94 int value;
95 switch (m_controlMode) {
96 case kVoltage:
97 return GetOutputVoltage();
98 case kCurrent:
99 return GetOutputCurrent();
100 case kSpeed:
101 m_impl->GetSensorVelocity(value);
102 return ScaleNativeUnitsToRpm(m_feedbackDevice, value);
103 case kPosition:
104 m_impl->GetSensorPosition(value);
105 return ScaleNativeUnitsToRotations(m_feedbackDevice, value);
106 case kPercentVbus:
107 case kFollower:
108 default:
109 m_impl->GetAppliedThrottle(value);
110 return (float)value / 1023.0;
111 }
112}
113
114/**
115 * Sets the appropriate output on the talon, depending on the mode.
116 *
117 * In PercentVbus, the output is between -1.0 and 1.0, with 0.0 as stopped.
118 * In Voltage mode, output value is in volts.
119 * In Current mode, output value is in amperes.
120 * In Speed mode, output value is in position change / 10ms.
121 * In Position mode, output value is in encoder ticks or an analog value,
122 * depending on the sensor.
123 * In Follower mode, the output value is the integer device ID of the talon to
124 * duplicate.
125 *
126 * @param outputValue The setpoint value, as described above.
127 * @see SelectProfileSlot to choose between the two sets of gains.
128 */
129void CANTalon::Set(float value, uint8_t syncGroup) {
130 /* feed safety helper since caller just updated our output */
131 m_safetyHelper->Feed();
132 if (m_controlEnabled) {
133 m_setPoint = value; /* cache set point for GetSetpoint() */
134 CTR_Code status = CTR_OKAY;
135 switch (m_controlMode) {
136 case CANSpeedController::kPercentVbus: {
137 m_impl->Set(m_isInverted ? -value : value);
138 status = CTR_OKAY;
139 } break;
140 case CANSpeedController::kFollower: {
141 status = m_impl->SetDemand((int)value);
142 } break;
143 case CANSpeedController::kVoltage: {
144 // Voltage is an 8.8 fixed point number.
145 int volts = int((m_isInverted ? -value : value) * 256);
146 status = m_impl->SetDemand(volts);
147 } break;
148 case CANSpeedController::kSpeed:
149 /* if the caller has provided scaling info, apply it */
150 status = m_impl->SetDemand(ScaleVelocityToNativeUnits(m_feedbackDevice, m_isInverted ? -value : value));
151 break;
152 case CANSpeedController::kPosition:
153 status = m_impl->SetDemand(ScaleRotationsToNativeUnits(m_feedbackDevice, value));
154 break;
155 case CANSpeedController::kCurrent: {
156 double milliamperes = (m_isInverted ? -value : value) * 1000.0; /* mA*/
157 status = m_impl->SetDemand(milliamperes);
158 } break;
159 default:
160 wpi_setWPIErrorWithContext(
161 IncompatibleMode,
162 "The CAN Talon does not support this control mode.");
163 break;
164 }
165 if (status != CTR_OKAY) {
166 wpi_setErrorWithContext(status, getHALErrorMessage(status));
167 }
168
169 status = m_impl->SetModeSelect(m_sendMode);
170
171 if (status != CTR_OKAY) {
172 wpi_setErrorWithContext(status, getHALErrorMessage(status));
173 }
174 }
175}
176
177/**
178 * Sets the setpoint to value. Equivalent to Set().
179 */
180void CANTalon::SetSetpoint(float value) { Set(value); }
181
182/**
183 * Resets the integral term and disables the controller.
184 */
185void CANTalon::Reset() {
186 ClearIaccum();
187 Disable();
188}
189
190/**
191 * Disables control of the talon, causing the motor to brake or coast
192 * depending on its mode (see the Talon SRX Software Reference manual
193 * for more information).
194 */
195void CANTalon::Disable() {
196 m_impl->SetModeSelect((int)CANTalon::kDisabled);
197 m_controlEnabled = false;
198}
199
200/**
201 * Enables control of the Talon, allowing the motor to move.
202 */
203void CANTalon::EnableControl() {
204 SetControlMode(m_controlMode);
205 m_controlEnabled = true;
206}
207
208/**
209 * Enables control of the Talon, allowing the motor to move.
210 */
211void CANTalon::Enable() { EnableControl(); }
212
213/**
214 * @return Whether the Talon is currently enabled.
215 */
216bool CANTalon::IsControlEnabled() const { return m_controlEnabled; }
217
218/**
219 * @return Whether the Talon is currently enabled.
220 */
221bool CANTalon::IsEnabled() const { return IsControlEnabled(); }
222
223/**
224 * @param p Proportional constant to use in PID loop.
225 * @see SelectProfileSlot to choose between the two sets of gains.
226 */
227void CANTalon::SetP(double p) {
228 CTR_Code status = m_impl->SetPgain(m_profile, p);
229 if (status != CTR_OKAY) {
230 wpi_setErrorWithContext(status, getHALErrorMessage(status));
231 }
232}
233
234/**
235 * Set the integration constant of the currently selected profile.
236 *
237 * @param i Integration constant for the currently selected PID profile.
238 * @see SelectProfileSlot to choose between the two sets of gains.
239 */
240void CANTalon::SetI(double i) {
241 CTR_Code status = m_impl->SetIgain(m_profile, i);
242 if (status != CTR_OKAY) {
243 wpi_setErrorWithContext(status, getHALErrorMessage(status));
244 }
245}
246
247/**
248 * Set the derivative constant of the currently selected profile.
249 *
250 * @param d Derivative constant for the currently selected PID profile.
251 * @see SelectProfileSlot to choose between the two sets of gains.
252 */
253void CANTalon::SetD(double d) {
254 CTR_Code status = m_impl->SetDgain(m_profile, d);
255 if (status != CTR_OKAY) {
256 wpi_setErrorWithContext(status, getHALErrorMessage(status));
257 }
258}
259/**
260 * Set the feedforward value of the currently selected profile.
261 *
262 * @param f Feedforward constant for the currently selected PID profile.
263 * @see SelectProfileSlot to choose between the two sets of gains.
264 */
265void CANTalon::SetF(double f) {
266 CTR_Code status = m_impl->SetFgain(m_profile, f);
267 if (status != CTR_OKAY) {
268 wpi_setErrorWithContext(status, getHALErrorMessage(status));
269 }
270}
271/**
272 * Set the Izone to a nonzero value to auto clear the integral accumulator
273 * when the absolute value of CloseLoopError exceeds Izone.
274 *
275 * @see SelectProfileSlot to choose between the two sets of gains.
276 */
277void CANTalon::SetIzone(unsigned iz) {
278 CTR_Code status = m_impl->SetIzone(m_profile, iz);
279 if (status != CTR_OKAY) {
280 wpi_setErrorWithContext(status, getHALErrorMessage(status));
281 }
282}
283/**
284 * SRX has two available slots for PID.
285 * @param slotIdx one or zero depending on which slot caller wants.
286 */
287void CANTalon::SelectProfileSlot(int slotIdx) {
288 m_profile = (slotIdx == 0) ? 0 : 1; /* only get two slots for now */
289 CTR_Code status = m_impl->SetProfileSlotSelect(m_profile);
290 if (status != CTR_OKAY) {
291 wpi_setErrorWithContext(status, getHALErrorMessage(status));
292 }
293}
294/**
295 * Sets control values for closed loop control.
296 *
297 * @param p Proportional constant.
298 * @param i Integration constant.
299 * @param d Differential constant.
300 * This function does not modify F-gain. Considerable passing a zero for f
301 * using
302 * the four-parameter function.
303 */
304void CANTalon::SetPID(double p, double i, double d) {
305 SetP(p);
306 SetI(i);
307 SetD(d);
308}
309/**
310 * Sets control values for closed loop control.
311 *
312 * @param p Proportional constant.
313 * @param i Integration constant.
314 * @param d Differential constant.
315 * @param f Feedforward constant.
316 */
317void CANTalon::SetPID(double p, double i, double d, double f) {
318 SetP(p);
319 SetI(i);
320 SetD(d);
321 SetF(f);
322}
323/**
324 * Select the feedback device to use in closed-loop
325 */
326void CANTalon::SetFeedbackDevice(FeedbackDevice feedbackDevice) {
327 /* save the selection so that future setters/getters know which scalars to apply */
328 m_feedbackDevice = feedbackDevice;
329 /* pass feedback to actual CAN frame */
330 CTR_Code status = m_impl->SetFeedbackDeviceSelect((int)feedbackDevice);
331 if (status != CTR_OKAY) {
332 wpi_setErrorWithContext(status, getHALErrorMessage(status));
333 }
334}
335/**
336 * Select the feedback device to use in closed-loop
337 */
338void CANTalon::SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs) {
339 CTR_Code status = m_impl->SetStatusFrameRate((int)stateFrame, periodMs);
340 if (status != CTR_OKAY) {
341 wpi_setErrorWithContext(status, getHALErrorMessage(status));
342 }
343}
344
345/**
346 * Get the current proportional constant.
347 *
348 * @return double proportional constant for current profile.
349 * @see SelectProfileSlot to choose between the two sets of gains.
350 */
351double CANTalon::GetP() const {
352 CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_P
353 : CanTalonSRX::eProfileParamSlot0_P;
354 // Update the info in m_impl.
355 CTR_Code status = m_impl->RequestParam(param);
356 if (status != CTR_OKAY) {
357 wpi_setErrorWithContext(status, getHALErrorMessage(status));
358 }
359 usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
360 double p;
361 status = m_impl->GetPgain(m_profile, p);
362 if (status != CTR_OKAY) {
363 wpi_setErrorWithContext(status, getHALErrorMessage(status));
364 }
365 return p;
366}
367
368/**
369 * TODO documentation (see CANJaguar.cpp)
370 * @see SelectProfileSlot to choose between the two sets of gains.
371 */
372double CANTalon::GetI() const {
373 CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_I
374 : CanTalonSRX::eProfileParamSlot0_I;
375 // Update the info in m_impl.
376 CTR_Code status = m_impl->RequestParam(param);
377 if (status != CTR_OKAY) {
378 wpi_setErrorWithContext(status, getHALErrorMessage(status));
379 }
380 usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
381
382 double i;
383 status = m_impl->GetIgain(m_profile, i);
384 if (status != CTR_OKAY) {
385 wpi_setErrorWithContext(status, getHALErrorMessage(status));
386 }
387 return i;
388}
389
390/**
391 * TODO documentation (see CANJaguar.cpp)
392 * @see SelectProfileSlot to choose between the two sets of gains.
393 */
394double CANTalon::GetD() const {
395 CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_D
396 : CanTalonSRX::eProfileParamSlot0_D;
397 // Update the info in m_impl.
398 CTR_Code status = m_impl->RequestParam(param);
399 if (status != CTR_OKAY) {
400 wpi_setErrorWithContext(status, getHALErrorMessage(status));
401 }
402 usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
403
404 double d;
405 status = m_impl->GetDgain(m_profile, d);
406 if (status != CTR_OKAY) {
407 wpi_setErrorWithContext(status, getHALErrorMessage(status));
408 }
409 return d;
410}
411/**
412 *
413 * @see SelectProfileSlot to choose between the two sets of gains.
414 */
415double CANTalon::GetF() const {
416 CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_F
417 : CanTalonSRX::eProfileParamSlot0_F;
418 // Update the info in m_impl.
419 CTR_Code status = m_impl->RequestParam(param);
420 if (status != CTR_OKAY) {
421 wpi_setErrorWithContext(status, getHALErrorMessage(status));
422 }
423
424 usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
425 double f;
426 status = m_impl->GetFgain(m_profile, f);
427 if (status != CTR_OKAY) {
428 wpi_setErrorWithContext(status, getHALErrorMessage(status));
429 }
430 return f;
431}
432/**
433 * @see SelectProfileSlot to choose between the two sets of gains.
434 */
435int CANTalon::GetIzone() const {
436 CanTalonSRX::param_t param = m_profile
437 ? CanTalonSRX::eProfileParamSlot1_IZone
438 : CanTalonSRX::eProfileParamSlot0_IZone;
439 // Update the info in m_impl.
440 CTR_Code status = m_impl->RequestParam(param);
441 if (status != CTR_OKAY) {
442 wpi_setErrorWithContext(status, getHALErrorMessage(status));
443 }
444 usleep(kDelayForSolicitedSignalsUs);
445
446 int iz;
447 status = m_impl->GetIzone(m_profile, iz);
448 if (status != CTR_OKAY) {
449 wpi_setErrorWithContext(status, getHALErrorMessage(status));
450 }
451 return iz;
452}
453
454/**
455 * @return the current setpoint; ie, whatever was last passed to Set().
456 */
457double CANTalon::GetSetpoint() const { return m_setPoint; }
458
459/**
460 * Returns the voltage coming in from the battery.
461 *
462 * @return The input voltage in volts.
463 */
464float CANTalon::GetBusVoltage() const {
465 double voltage;
466 CTR_Code status = m_impl->GetBatteryV(voltage);
467 if (status != CTR_OKAY) {
468 wpi_setErrorWithContext(status, getHALErrorMessage(status));
469 }
470 return voltage;
471}
472
473/**
474 * @return The voltage being output by the Talon, in Volts.
475 */
476float CANTalon::GetOutputVoltage() const {
477 int throttle11;
478 CTR_Code status = m_impl->GetAppliedThrottle(throttle11);
479 float voltage = GetBusVoltage() * (float(throttle11) / 1023.0);
480 if (status != CTR_OKAY) {
481 wpi_setErrorWithContext(status, getHALErrorMessage(status));
482 }
483 return voltage;
484}
485
486/**
487 * Returns the current going through the Talon, in Amperes.
488 */
489float CANTalon::GetOutputCurrent() const {
490 double current;
491
492 CTR_Code status = m_impl->GetCurrent(current);
493 if (status != CTR_OKAY) {
494 wpi_setErrorWithContext(status, getHALErrorMessage(status));
495 }
496
497 return current;
498}
499
500/**
501 * Returns temperature of Talon, in degrees Celsius.
502 */
503float CANTalon::GetTemperature() const {
504 double temp;
505
506 CTR_Code status = m_impl->GetTemp(temp);
507 if (temp != CTR_OKAY) {
508 wpi_setErrorWithContext(status, getHALErrorMessage(status));
509 }
510 return temp;
511}
512/**
513 * Set the position value of the selected sensor. This is useful for zero-ing
514 * quadrature encoders.
515 * Continuous sensors (like analog encoderes) can also partially be set (the
516 * portion of the postion based on overflows).
517 */
518void CANTalon::SetPosition(double pos) {
519 int32_t nativePos = ScaleRotationsToNativeUnits(m_feedbackDevice, pos);
520 CTR_Code status = m_impl->SetSensorPosition(nativePos);
521 if (status != CTR_OKAY) {
522 wpi_setErrorWithContext(status, getHALErrorMessage(status));
523 }
524}
525/**
526 * TODO documentation (see CANJaguar.cpp)
527 *
528 * @return The position of the sensor currently providing feedback.
529 * When using analog sensors, 0 units corresponds to 0V, 1023
530 * units corresponds to 3.3V
531 * When using an analog encoder (wrapping around 1023 => 0 is
532 * possible) the units are still 3.3V per 1023 units.
533 * When using quadrature, each unit is a quadrature edge (4X)
534 * mode.
535 */
536double CANTalon::GetPosition() const {
537 int32_t position;
538 CTR_Code status = m_impl->GetSensorPosition(position);
539 if (status != CTR_OKAY) {
540 wpi_setErrorWithContext(status, getHALErrorMessage(status));
541 }
542 return ScaleNativeUnitsToRotations(m_feedbackDevice, position);
543}
544/**
545 * If sensor and motor are out of phase, sensor can be inverted
546 * (position and velocity multiplied by -1).
547 * @see GetPosition and @see GetSpeed.
548 */
549void CANTalon::SetSensorDirection(bool reverseSensor) {
550 CTR_Code status = m_impl->SetRevFeedbackSensor(reverseSensor ? 1 : 0);
551 if (status != CTR_OKAY) {
552 wpi_setErrorWithContext(status, getHALErrorMessage(status));
553 }
554}
555/**
556 * Flips the sign (multiplies by negative one) the throttle values going into
557 * the motor on the talon in closed loop modes. Typically the application
558 * should use SetSensorDirection to keep sensor and motor in phase.
559 * @see SetSensorDirection
560 * However this routine is helpful for reversing the motor direction
561 * when Talon is in slave mode, or when using a single-direction position
562 * sensor in a closed-loop mode.
563 *
564 * @param reverseOutput True if motor output should be flipped; False if not.
565 */
566void CANTalon::SetClosedLoopOutputDirection(bool reverseOutput) {
567 CTR_Code status = m_impl->SetRevMotDuringCloseLoopEn(reverseOutput ? 1 : 0);
568 if (status != CTR_OKAY) {
569 wpi_setErrorWithContext(status, getHALErrorMessage(status));
570 }
571}
572/**
573 * Returns the current error in the controller.
574 *
575 * @return the difference between the setpoint and the sensor value.
576 */
577int CANTalon::GetClosedLoopError() const {
578 int error;
579 /* retrieve the closed loop error in native units */
580 CTR_Code status = m_impl->GetCloseLoopErr(error);
581 if (status != CTR_OKAY) {
582 wpi_setErrorWithContext(status, getHALErrorMessage(status));
583 }
584 return error;
585}
586/**
587 * Set the allowable closed loop error.
588 * @param allowableCloseLoopError allowable closed loop error for selected profile.
589 * mA for Curent closed loop.
590 * Talon Native Units for position and velocity.
591 */
592void CANTalon::SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError)
593{
594 /* grab param enum */
595 CanTalonSRX::param_t param;
596 if (m_profile == 1) {
597 param = CanTalonSRX::eProfileParamSlot1_AllowableClosedLoopErr;
598 } else {
599 param = CanTalonSRX::eProfileParamSlot0_AllowableClosedLoopErr;
600 }
601 /* send allowable close loop er in native units */
602 ConfigSetParameter(param, allowableCloseLoopError);
603}
604
605/**
606 * TODO documentation (see CANJaguar.cpp)
607 *
608 * @returns The speed of the sensor currently providing feedback.
609 *
610 * The speed units will be in the sensor's native ticks per 100ms.
611 *
612 * For analog sensors, 3.3V corresponds to 1023 units.
613 * So a speed of 200 equates to ~0.645 dV per 100ms or 6.451 dV per
614 * second.
615 * If this is an analog encoder, that likely means 1.9548 rotations
616 * per sec.
617 * For quadrature encoders, each unit corresponds a quadrature edge (4X).
618 * So a 250 count encoder will produce 1000 edge events per
619 * rotation.
620 * An example speed of 200 would then equate to 20% of a rotation
621 * per 100ms,
622 * or 10 rotations per second.
623 */
624double CANTalon::GetSpeed() const {
625 int32_t speed;
626 CTR_Code status = m_impl->GetSensorVelocity(speed);
627 if (status != CTR_OKAY) {
628 wpi_setErrorWithContext(status, getHALErrorMessage(status));
629 }
630 return ScaleNativeUnitsToRpm(m_feedbackDevice, speed);
631}
632
633/**
634 * Get the position of whatever is in the analog pin of the Talon, regardless of
635 * whether it is actually being used for feedback.
636 *
637 * @returns The 24bit analog value. The bottom ten bits is the ADC (0 - 1023)
638 * on the analog pin of the Talon.
639 * The upper 14 bits tracks the overflows and
640 * underflows (continuous sensor).
641 */
642int CANTalon::GetAnalogIn() const {
643 int position;
644 CTR_Code status = m_impl->GetAnalogInWithOv(position);
645 if (status != CTR_OKAY) {
646 wpi_setErrorWithContext(status, getHALErrorMessage(status));
647 }
648 return position;
649}
650
651void CANTalon::SetAnalogPosition(int newPosition) {
652 CTR_Code status = m_impl->SetParam(CanTalonSRX::eAinPosition, newPosition);
653 if (status != CTR_OKAY) {
654 wpi_setErrorWithContext(status, getHALErrorMessage(status));
655 }
656}
657/**
658 * Get the position of whatever is in the analog pin of the Talon, regardless of
659 * whether it is actually being used for feedback.
660 *
661 * @returns The ADC (0 - 1023) on analog pin of the Talon.
662 */
663int CANTalon::GetAnalogInRaw() const { return GetAnalogIn() & 0x3FF; }
664/**
665 * Get the position of whatever is in the analog pin of the Talon, regardless of
666 * whether it is actually being used for feedback.
667 *
668 * @returns The value (0 - 1023) on the analog pin of the Talon.
669 */
670int CANTalon::GetAnalogInVel() const {
671 int vel;
672 CTR_Code status = m_impl->GetAnalogInVel(vel);
673 if (status != CTR_OKAY) {
674 wpi_setErrorWithContext(status, getHALErrorMessage(status));
675 }
676 return vel;
677}
678
679/**
680 * Get the position of whatever is in the analog pin of the Talon, regardless of
681 * whether it is actually being used for feedback.
682 *
683 * @returns The value (0 - 1023) on the analog pin of the Talon.
684 */
685int CANTalon::GetEncPosition() const {
686 int position;
687 CTR_Code status = m_impl->GetEncPosition(position);
688 if (status != CTR_OKAY) {
689 wpi_setErrorWithContext(status, getHALErrorMessage(status));
690 }
691 return position;
692}
693void CANTalon::SetEncPosition(int newPosition) {
694 CTR_Code status = m_impl->SetParam(CanTalonSRX::eEncPosition, newPosition);
695 if (status != CTR_OKAY) {
696 wpi_setErrorWithContext(status, getHALErrorMessage(status));
697 }
698}
699
700/**
701 * Get the position of whatever is in the analog pin of the Talon, regardless of
702 * whether it is actually being used for feedback.
703 *
704 * @returns The value (0 - 1023) on the analog pin of the Talon.
705 */
706int CANTalon::GetEncVel() const {
707 int vel;
708 CTR_Code status = m_impl->GetEncVel(vel);
709 if (status != CTR_OKAY) {
710 wpi_setErrorWithContext(status, getHALErrorMessage(status));
711 }
712 return vel;
713}
714int CANTalon::GetPulseWidthPosition() const {
715 int param;
716 CTR_Code status = m_impl->GetPulseWidthPosition(param);
717 if (status != CTR_OKAY)
718 wpi_setErrorWithContext(status, getHALErrorMessage(status));
719 return param;
720}
721void CANTalon::SetPulseWidthPosition(int newPosition)
722{
723 CTR_Code status = m_impl->SetParam(CanTalonSRX::ePwdPosition, newPosition);
724 if (status != CTR_OKAY) {
725 wpi_setErrorWithContext(status, getHALErrorMessage(status));
726 }
727}
728int CANTalon::GetPulseWidthVelocity()const
729{
730 int param;
731 CTR_Code status = m_impl->GetPulseWidthVelocity(param);
732 if (status != CTR_OKAY)
733 wpi_setErrorWithContext(status, getHALErrorMessage(status));
734 return param;
735}
736int CANTalon::GetPulseWidthRiseToFallUs()const
737{
738 int param;
739 CTR_Code status = m_impl->GetPulseWidthRiseToFallUs(param);
740 if (status != CTR_OKAY)
741 wpi_setErrorWithContext(status, getHALErrorMessage(status));
742 return param;
743}
744int CANTalon::GetPulseWidthRiseToRiseUs()const
745{
746 int param;
747 CTR_Code status = m_impl->GetPulseWidthRiseToRiseUs(param);
748 if (status != CTR_OKAY)
749 wpi_setErrorWithContext(status, getHALErrorMessage(status));
750 return param;
751}
752/**
753 * @param which feedback sensor to check it if is connected.
754 * @return status of caller's specified sensor type.
755 */
756CANTalon::FeedbackDeviceStatus CANTalon::IsSensorPresent(FeedbackDevice feedbackDevice)const
757{
758 FeedbackDeviceStatus retval = FeedbackStatusUnknown;
759 int param;
760 /* detecting sensor health depends on which sensor caller cares about */
761 switch (feedbackDevice) {
762 case QuadEncoder:
763 case AnalogPot:
764 case AnalogEncoder:
765 case EncRising:
766 case EncFalling:
767 /* no real good way to tell if these sensor
768 are actually present so return status unknown. */
769 break;
770 case PulseWidth:
771 case CtreMagEncoder_Relative:
772 case CtreMagEncoder_Absolute:
773 /* all of these require pulse width signal to be present. */
774 CTR_Code status = m_impl->IsPulseWidthSensorPresent(param);
775 if (status != CTR_OKAY) {
776 /* we're not getting status info, signal unknown status */
777 } else {
778 /* param is updated */
779 if (param) {
780 /* pulse signal is present, sensor must be working since it always
781 generates a pulse waveform.*/
782 retval = FeedbackStatusPresent;
783 } else {
784 /* no pulse present, sensor disconnected */
785 retval = FeedbackStatusNotPresent;
786 }
787 }
788 break;
789 }
790 return retval;
791}
792/**
793 * @return IO level of QUADA pin.
794 */
795int CANTalon::GetPinStateQuadA() const {
796 int retval;
797 CTR_Code status = m_impl->GetQuadApin(retval);
798 if (status != CTR_OKAY) {
799 wpi_setErrorWithContext(status, getHALErrorMessage(status));
800 }
801 return retval;
802}
803/**
804 * @return IO level of QUADB pin.
805 */
806int CANTalon::GetPinStateQuadB() const {
807 int retval;
808 CTR_Code status = m_impl->GetQuadBpin(retval);
809 if (status != CTR_OKAY) {
810 wpi_setErrorWithContext(status, getHALErrorMessage(status));
811 }
812 return retval;
813}
814/**
815 * @return IO level of QUAD Index pin.
816 */
817int CANTalon::GetPinStateQuadIdx() const {
818 int retval;
819 CTR_Code status = m_impl->GetQuadIdxpin(retval);
820 if (status != CTR_OKAY) {
821 wpi_setErrorWithContext(status, getHALErrorMessage(status));
822 }
823 return retval;
824}
825/**
826 * @return '1' iff forward limit switch is closed, 0 iff switch is open.
827 * This function works regardless if limit switch feature is enabled.
828 */
829int CANTalon::IsFwdLimitSwitchClosed() const {
830 int retval;
831 CTR_Code status = m_impl->GetLimitSwitchClosedFor(
832 retval); /* rename this func, '1' => open, '0' => closed */
833 if (status != CTR_OKAY) {
834 wpi_setErrorWithContext(status, getHALErrorMessage(status));
835 }
836 return retval ? 0 : 1;
837}
838/**
839 * @return '1' iff reverse limit switch is closed, 0 iff switch is open.
840 * This function works regardless if limit switch feature is enabled.
841 */
842int CANTalon::IsRevLimitSwitchClosed() const {
843 int retval;
844 CTR_Code status = m_impl->GetLimitSwitchClosedRev(
845 retval); /* rename this func, '1' => open, '0' => closed */
846 if (status != CTR_OKAY) {
847 wpi_setErrorWithContext(status, getHALErrorMessage(status));
848 }
849 return retval ? 0 : 1;
850}
851/*
852 * Simple accessor for tracked rise eventso index pin.
853 * @return number of rising edges on idx pin.
854 */
855int CANTalon::GetNumberOfQuadIdxRises() const {
856 int rises;
857 CTR_Code status = m_impl->GetEncIndexRiseEvents(
858 rises); /* rename this func, '1' => open, '0' => closed */
859 if (status != CTR_OKAY) {
860 wpi_setErrorWithContext(status, getHALErrorMessage(status));
861 }
862 return rises;
863}
864/*
865 * @param rises integral value to set into index-rises register. Great way to
866 * zero the index count.
867 */
868void CANTalon::SetNumberOfQuadIdxRises(int rises) {
869 CTR_Code status = m_impl->SetParam(
870 CanTalonSRX::eEncIndexRiseEvents,
871 rises); /* rename this func, '1' => open, '0' => closed */
872 if (status != CTR_OKAY) {
873 wpi_setErrorWithContext(status, getHALErrorMessage(status));
874 }
875}
876/**
877 * TODO documentation (see CANJaguar.cpp)
878 */
879bool CANTalon::GetForwardLimitOK() const {
880 int limSwit = 0;
881 int softLim = 0;
882 CTR_Code status = CTR_OKAY;
883 status = m_impl->GetFault_ForSoftLim(softLim);
884 if (status != CTR_OKAY) {
885 wpi_setErrorWithContext(status, getHALErrorMessage(status));
886 }
887 status = m_impl->GetFault_ForLim(limSwit);
888 if (status != CTR_OKAY) {
889 wpi_setErrorWithContext(status, getHALErrorMessage(status));
890 }
891 /* If either fault is asserted, signal caller we are disabled (with false?) */
892 return (softLim | limSwit) ? false : true;
893}
894
895/**
896 * TODO documentation (see CANJaguar.cpp)
897 */
898bool CANTalon::GetReverseLimitOK() const {
899 int limSwit = 0;
900 int softLim = 0;
901 CTR_Code status = CTR_OKAY;
902 status = m_impl->GetFault_RevSoftLim(softLim);
903 if (status != CTR_OKAY) {
904 wpi_setErrorWithContext(status, getHALErrorMessage(status));
905 }
906 status = m_impl->GetFault_RevLim(limSwit);
907 if (status != CTR_OKAY) {
908 wpi_setErrorWithContext(status, getHALErrorMessage(status));
909 }
910 /* If either fault is asserted, signal caller we are disabled (with false?) */
911 return (softLim | limSwit) ? false : true;
912}
913
914/**
915 * TODO documentation (see CANJaguar.cpp)
916 */
917uint16_t CANTalon::GetFaults() const {
918 uint16_t retval = 0;
919 int val;
920 CTR_Code status = CTR_OKAY;
921
922 /* temperature */
923 val = 0;
924 status = m_impl->GetFault_OverTemp(val);
925 if (status != CTR_OKAY)
926 wpi_setErrorWithContext(status, getHALErrorMessage(status));
927 retval |= (val) ? CANSpeedController::kTemperatureFault : 0;
928
929 /* voltage */
930 val = 0;
931 status = m_impl->GetFault_UnderVoltage(val);
932 if (status != CTR_OKAY)
933 wpi_setErrorWithContext(status, getHALErrorMessage(status));
934 retval |= (val) ? CANSpeedController::kBusVoltageFault : 0;
935
936 /* fwd-limit-switch */
937 val = 0;
938 status = m_impl->GetFault_ForLim(val);
939 if (status != CTR_OKAY)
940 wpi_setErrorWithContext(status, getHALErrorMessage(status));
941 retval |= (val) ? CANSpeedController::kFwdLimitSwitch : 0;
942
943 /* rev-limit-switch */
944 val = 0;
945 status = m_impl->GetFault_RevLim(val);
946 if (status != CTR_OKAY)
947 wpi_setErrorWithContext(status, getHALErrorMessage(status));
948 retval |= (val) ? CANSpeedController::kRevLimitSwitch : 0;
949
950 /* fwd-soft-limit */
951 val = 0;
952 status = m_impl->GetFault_ForSoftLim(val);
953 if (status != CTR_OKAY)
954 wpi_setErrorWithContext(status, getHALErrorMessage(status));
955 retval |= (val) ? CANSpeedController::kFwdSoftLimit : 0;
956
957 /* rev-soft-limit */
958 val = 0;
959 status = m_impl->GetFault_RevSoftLim(val);
960 if (status != CTR_OKAY)
961 wpi_setErrorWithContext(status, getHALErrorMessage(status));
962 retval |= (val) ? CANSpeedController::kRevSoftLimit : 0;
963
964 return retval;
965}
966uint16_t CANTalon::GetStickyFaults() const {
967 uint16_t retval = 0;
968 int val;
969 CTR_Code status = CTR_OKAY;
970
971 /* temperature */
972 val = 0;
973 status = m_impl->GetStckyFault_OverTemp(val);
974 if (status != CTR_OKAY)
975 wpi_setErrorWithContext(status, getHALErrorMessage(status));
976 retval |= (val) ? CANSpeedController::kTemperatureFault : 0;
977
978 /* voltage */
979 val = 0;
980 status = m_impl->GetStckyFault_UnderVoltage(val);
981 if (status != CTR_OKAY)
982 wpi_setErrorWithContext(status, getHALErrorMessage(status));
983 retval |= (val) ? CANSpeedController::kBusVoltageFault : 0;
984
985 /* fwd-limit-switch */
986 val = 0;
987 status = m_impl->GetStckyFault_ForLim(val);
988 if (status != CTR_OKAY)
989 wpi_setErrorWithContext(status, getHALErrorMessage(status));
990 retval |= (val) ? CANSpeedController::kFwdLimitSwitch : 0;
991
992 /* rev-limit-switch */
993 val = 0;
994 status = m_impl->GetStckyFault_RevLim(val);
995 if (status != CTR_OKAY)
996 wpi_setErrorWithContext(status, getHALErrorMessage(status));
997 retval |= (val) ? CANSpeedController::kRevLimitSwitch : 0;
998
999 /* fwd-soft-limit */
1000 val = 0;
1001 status = m_impl->GetStckyFault_ForSoftLim(val);
1002 if (status != CTR_OKAY)
1003 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1004 retval |= (val) ? CANSpeedController::kFwdSoftLimit : 0;
1005
1006 /* rev-soft-limit */
1007 val = 0;
1008 status = m_impl->GetStckyFault_RevSoftLim(val);
1009 if (status != CTR_OKAY)
1010 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1011 retval |= (val) ? CANSpeedController::kRevSoftLimit : 0;
1012
1013 return retval;
1014}
1015void CANTalon::ClearStickyFaults() {
1016 CTR_Code status = m_impl->ClearStickyFaults();
1017 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1018}
1019
1020/**
1021 * Set the maximum voltage change rate. This ramp rate is in affect regardless
1022 * of which control mode
1023 * the TALON is in.
1024 *
1025 * When in PercentVbus or Voltage output mode, the rate at which the voltage
1026 * changes can
1027 * be limited to reduce current spikes. Set this to 0.0 to disable rate
1028 * limiting.
1029 *
1030 * @param rampRate The maximum rate of voltage change in Percent Voltage mode in
1031 * V/s.
1032 */
1033void CANTalon::SetVoltageRampRate(double rampRate) {
1034 /* Caller is expressing ramp as Voltage per sec, assuming 12V is full.
1035 Talon's throttle ramp is in dThrot/d10ms. 1023 is full fwd, -1023 is
1036 full rev. */
1037 double rampRatedThrotPer10ms = (rampRate * 1023.0 / 12.0) / 100;
1038 CTR_Code status = m_impl->SetRampThrottle((int)rampRatedThrotPer10ms);
1039 if (status != CTR_OKAY) {
1040 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1041 }
1042}
1043void CANTalon::SetVoltageCompensationRampRate(double rampRate) {
1044 /* when in voltage compensation mode, the voltage compensation rate
1045 directly caps the change in target voltage */
1046 CTR_Code status = CTR_OKAY;
1047 status = m_impl->SetVoltageCompensationRate(rampRate / 1000);
1048 if (status != CTR_OKAY) {
1049 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1050 }
1051}
1052/**
1053 * Sets a voltage change rate that applies only when a close loop contorl mode
1054 * is enabled.
1055 * This allows close loop specific ramp behavior.
1056 *
1057 * @param rampRate The maximum rate of voltage change in Percent Voltage mode in
1058 * V/s.
1059 */
1060void CANTalon::SetCloseLoopRampRate(double rampRate) {
1061 CTR_Code status = m_impl->SetCloseLoopRampRate(
1062 m_profile, rampRate * 1023.0 / 12.0 / 1000.0);
1063 if (status != CTR_OKAY) {
1064 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1065 }
1066}
1067
1068/**
1069 * @return The version of the firmware running on the Talon
1070 */
1071uint32_t CANTalon::GetFirmwareVersion() const {
1072 int firmwareVersion;
1073 CTR_Code status = m_impl->RequestParam(CanTalonSRX::eFirmVers);
1074 if (status != CTR_OKAY) {
1075 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1076 }
1077 usleep(kDelayForSolicitedSignalsUs);
1078 status =
1079 m_impl->GetParamResponseInt32(CanTalonSRX::eFirmVers, firmwareVersion);
1080 if (status != CTR_OKAY) {
1081 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1082 }
1083
1084 /* only sent once on boot */
1085 // CTR_Code status = m_impl->GetFirmVers(firmwareVersion);
1086 // if (status != CTR_OKAY) {
1087 // wpi_setErrorWithContext(status, getHALErrorMessage(status));
1088 //}
1089
1090 return firmwareVersion;
1091}
1092/**
1093 * @return The accumulator for I gain.
1094 */
1095int CANTalon::GetIaccum() const {
1096 CTR_Code status = m_impl->RequestParam(CanTalonSRX::ePidIaccum);
1097 if (status != CTR_OKAY) {
1098 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1099 }
1100 usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
1101 int iaccum;
1102 status = m_impl->GetParamResponseInt32(CanTalonSRX::ePidIaccum, iaccum);
1103 if (status != CTR_OKAY) {
1104 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1105 }
1106 return iaccum;
1107}
1108/**
1109 * Clear the accumulator for I gain.
1110 */
1111void CANTalon::ClearIaccum() {
1112 CTR_Code status = m_impl->SetParam(CanTalonSRX::ePidIaccum, 0);
1113 if (status != CTR_OKAY) {
1114 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1115 }
1116}
1117
1118/**
1119 * TODO documentation (see CANJaguar.cpp)
1120 */
1121void CANTalon::ConfigNeutralMode(NeutralMode mode) {
1122 CTR_Code status = CTR_OKAY;
1123 switch (mode) {
1124 default:
1125 case kNeutralMode_Jumper: /* use default setting in flash based on
1126 webdash/BrakeCal button selection */
1127 status = m_impl->SetOverrideBrakeType(
1128 CanTalonSRX::kBrakeOverride_UseDefaultsFromFlash);
1129 break;
1130 case kNeutralMode_Brake:
1131 status = m_impl->SetOverrideBrakeType(
1132 CanTalonSRX::kBrakeOverride_OverrideBrake);
1133 break;
1134 case kNeutralMode_Coast:
1135 status = m_impl->SetOverrideBrakeType(
1136 CanTalonSRX::kBrakeOverride_OverrideCoast);
1137 break;
1138 }
1139 if (status != CTR_OKAY) {
1140 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1141 }
1142}
1143/**
1144 * @return nonzero if brake is enabled during neutral. Zero if coast is enabled
1145 * during neutral.
1146 */
1147int CANTalon::GetBrakeEnableDuringNeutral() const {
1148 int brakeEn = 0;
1149 CTR_Code status = m_impl->GetBrakeIsEnabled(brakeEn);
1150 if (status != CTR_OKAY) {
1151 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1152 }
1153 return brakeEn;
1154}
1155/**
1156 * Configure how many codes per revolution are generated by your encoder.
1157 *
1158 * @param codesPerRev The number of counts per revolution.
1159 */
1160void CANTalon::ConfigEncoderCodesPerRev(uint16_t codesPerRev) {
1161 /* first save the scalar so that all getters/setter work as the user expects */
1162 m_codesPerRev = codesPerRev;
1163 /* next send the scalar to the Talon over CAN. This is so that the Talon can report
1164 it to whoever needs it, like the webdash. Don't bother checking the return,
1165 this is only for instrumentation and is not necessary for Talon functionality. */
1166 (void)m_impl->SetParam(CanTalonSRX::eNumberEncoderCPR, m_codesPerRev);
1167}
1168
1169/**
1170 * Configure the number of turns on the potentiometer.
1171 *
1172 * @param turns The number of turns of the potentiometer.
1173 */
1174void CANTalon::ConfigPotentiometerTurns(uint16_t turns) {
1175 /* first save the scalar so that all getters/setter work as the user expects */
1176 m_numPotTurns = turns;
1177 /* next send the scalar to the Talon over CAN. This is so that the Talon can report
1178 it to whoever needs it, like the webdash. Don't bother checking the return,
1179 this is only for instrumentation and is not necessary for Talon functionality. */
1180 (void)m_impl->SetParam(CanTalonSRX::eNumberPotTurns, m_numPotTurns);
1181}
1182
1183/**
1184 * @deprecated not implemented
1185 */
1186void CANTalon::ConfigSoftPositionLimits(double forwardLimitPosition,
1187 double reverseLimitPosition) {
1188 ConfigLimitMode(kLimitMode_SoftPositionLimits);
1189 ConfigForwardLimit(forwardLimitPosition);
1190 ConfigReverseLimit(reverseLimitPosition);
1191}
1192
1193/**
1194 * TODO documentation (see CANJaguar.cpp)
1195 */
1196void CANTalon::DisableSoftPositionLimits() {
1197 ConfigLimitMode(kLimitMode_SwitchInputsOnly);
1198}
1199
1200/**
1201 * TODO documentation (see CANJaguar.cpp)
1202 * Configures the soft limit enable (wear leveled persistent memory).
1203 * Also sets the limit switch overrides.
1204 */
1205void CANTalon::ConfigLimitMode(LimitMode mode) {
1206 CTR_Code status = CTR_OKAY;
1207 switch (mode) {
1208 case kLimitMode_SwitchInputsOnly: /** Only use switches for limits */
1209 /* turn OFF both limits. SRX has individual enables and polarity for each
1210 * limit switch.*/
1211 status = m_impl->SetForwardSoftEnable(false);
1212 if (status != CTR_OKAY) {
1213 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1214 }
1215 status = m_impl->SetReverseSoftEnable(false);
1216 if (status != CTR_OKAY) {
1217 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1218 }
1219 /* override enable the limit switches, this circumvents the webdash */
1220 status = m_impl->SetOverrideLimitSwitchEn(
1221 CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev);
1222 if (status != CTR_OKAY) {
1223 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1224 }
1225 break;
1226 case kLimitMode_SoftPositionLimits: /** Use both switches and soft limits */
1227 /* turn on both limits. SRX has individual enables and polarity for each
1228 * limit switch.*/
1229 status = m_impl->SetForwardSoftEnable(true);
1230 if (status != CTR_OKAY) {
1231 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1232 }
1233 status = m_impl->SetReverseSoftEnable(true);
1234 if (status != CTR_OKAY) {
1235 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1236 }
1237 /* override enable the limit switches, this circumvents the webdash */
1238 status = m_impl->SetOverrideLimitSwitchEn(
1239 CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev);
1240 if (status != CTR_OKAY) {
1241 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1242 }
1243 break;
1244
1245 case kLimitMode_SrxDisableSwitchInputs: /** disable both limit switches and
1246 soft limits */
1247 /* turn on both limits. SRX has individual enables and polarity for each
1248 * limit switch.*/
1249 status = m_impl->SetForwardSoftEnable(false);
1250 if (status != CTR_OKAY) {
1251 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1252 }
1253 status = m_impl->SetReverseSoftEnable(false);
1254 if (status != CTR_OKAY) {
1255 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1256 }
1257 /* override enable the limit switches, this circumvents the webdash */
1258 status = m_impl->SetOverrideLimitSwitchEn(
1259 CanTalonSRX::kLimitSwitchOverride_DisableFwd_DisableRev);
1260 if (status != CTR_OKAY) {
1261 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1262 }
1263 break;
1264 }
1265}
1266
1267/**
1268 * TODO documentation (see CANJaguar.cpp)
1269 */
1270void CANTalon::ConfigForwardLimit(double forwardLimitPosition) {
1271 CTR_Code status = CTR_OKAY;
1272 int32_t nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, forwardLimitPosition);
1273 status = m_impl->SetForwardSoftLimit(nativeLimitPos);
1274 if (status != CTR_OKAY) {
1275 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1276 }
1277}
1278/**
1279 * Change the fwd limit switch setting to normally open or closed.
1280 * Talon will disable momentarilly if the Talon's current setting
1281 * is dissimilar to the caller's requested setting.
1282 *
1283 * Since Talon saves setting to flash this should only affect
1284 * a given Talon initially during robot install.
1285 *
1286 * @param normallyOpen true for normally open. false for normally closed.
1287 */
1288void CANTalon::ConfigFwdLimitSwitchNormallyOpen(bool normallyOpen) {
1289 CTR_Code status =
1290 m_impl->SetParam(CanTalonSRX::eOnBoot_LimitSwitch_Forward_NormallyClosed,
1291 normallyOpen ? 0 : 1);
1292 if (status != CTR_OKAY) {
1293 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1294 }
1295}
1296/**
1297 * Change the rev limit switch setting to normally open or closed.
1298 * Talon will disable momentarilly if the Talon's current setting
1299 * is dissimilar to the caller's requested setting.
1300 *
1301 * Since Talon saves setting to flash this should only affect
1302 * a given Talon initially during robot install.
1303 *
1304 * @param normallyOpen true for normally open. false for normally closed.
1305 */
1306void CANTalon::ConfigRevLimitSwitchNormallyOpen(bool normallyOpen) {
1307 CTR_Code status =
1308 m_impl->SetParam(CanTalonSRX::eOnBoot_LimitSwitch_Reverse_NormallyClosed,
1309 normallyOpen ? 0 : 1);
1310 if (status != CTR_OKAY) {
1311 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1312 }
1313}
1314/**
1315 * TODO documentation (see CANJaguar.cpp)
1316 */
1317void CANTalon::ConfigReverseLimit(double reverseLimitPosition) {
1318 CTR_Code status = CTR_OKAY;
1319 int32_t nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, reverseLimitPosition);
1320 status = m_impl->SetReverseSoftLimit(nativeLimitPos);
1321 if (status != CTR_OKAY) {
1322 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1323 }
1324}
1325/**
1326 * TODO documentation (see CANJaguar.cpp)
1327 */
1328void CANTalon::ConfigMaxOutputVoltage(double voltage) {
1329 /* config peak throttle when in closed-loop mode in the fwd and rev direction. */
1330 ConfigPeakOutputVoltage(voltage, -voltage);
1331}
1332void CANTalon::ConfigPeakOutputVoltage(double forwardVoltage,double reverseVoltage) {
1333 /* bounds checking */
1334 if (forwardVoltage > 12)
1335 forwardVoltage = 12;
1336 else if (forwardVoltage < 0)
1337 forwardVoltage = 0;
1338 if (reverseVoltage > 0)
1339 reverseVoltage = 0;
1340 else if (reverseVoltage < -12)
1341 reverseVoltage = -12;
1342 /* config calls */
1343 ConfigSetParameter(CanTalonSRX::ePeakPosOutput, 1023 * forwardVoltage / 12.0);
1344 ConfigSetParameter(CanTalonSRX::ePeakNegOutput, 1023 * reverseVoltage / 12.0);
1345}
1346void CANTalon::ConfigNominalOutputVoltage(double forwardVoltage,double reverseVoltage) {
1347 /* bounds checking */
1348 if (forwardVoltage > 12)
1349 forwardVoltage = 12;
1350 else if (forwardVoltage < 0)
1351 forwardVoltage = 0;
1352 if (reverseVoltage > 0)
1353 reverseVoltage = 0;
1354 else if (reverseVoltage < -12)
1355 reverseVoltage = -12;
1356 /* config calls */
1357 ConfigSetParameter(CanTalonSRX::eNominalPosOutput,1023*forwardVoltage/12.0);
1358 ConfigSetParameter(CanTalonSRX::eNominalNegOutput,1023*reverseVoltage/12.0);
1359}
1360/**
1361 * General set frame. Since the parameter is a general integral type, this can
1362 * be used for testing future features.
1363 */
1364void CANTalon::ConfigSetParameter(uint32_t paramEnum, double value) {
1365 CTR_Code status;
1366 /* config peak throttle when in closed-loop mode in the positive direction. */
1367 status = m_impl->SetParam((CanTalonSRX::param_t)paramEnum,value);
1368 if (status != CTR_OKAY) {
1369 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1370 }
1371}
1372/**
1373 * General get frame. Since the parameter is a general integral type, this can
1374 * be used for testing future features.
1375 */
1376bool CANTalon::GetParameter(uint32_t paramEnum, double & dvalue) const {
1377 bool retval = true;
1378 /* send the request frame */
1379 CTR_Code status = m_impl->RequestParam((CanTalonSRX::param_t)paramEnum);
1380 if (status != CTR_OKAY) {
1381 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1382 retval = false;
1383 }
1384 /* small yield for getting response */
1385 usleep(kDelayForSolicitedSignalsUs);
1386 /* get the last received update */
1387 status = m_impl->GetParamResponse((CanTalonSRX::param_t)paramEnum, dvalue);
1388 if (status != CTR_OKAY) {
1389 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1390 retval = false;
1391 }
1392 return retval;
1393}
1394
1395/**
1396 * TODO documentation (see CANJaguar.cpp)
1397 */
1398void CANTalon::ConfigFaultTime(float faultTime) {
1399 /* SRX does not have fault time. SRX motor drive is only disabled for soft
1400 * limits and limit-switch faults. */
1401 wpi_setWPIErrorWithContext(IncompatibleMode, "Fault Time not supported.");
1402}
1403
1404/**
1405 * Fixup the sendMode so Set() serializes the correct demand value.
1406 * Also fills the modeSelecet in the control frame to disabled.
1407 * @param mode Control mode to ultimately enter once user calls Set().
1408 * @see Set()
1409 */
1410void CANTalon::ApplyControlMode(CANSpeedController::ControlMode mode) {
1411 m_controlMode = mode;
1412 HALReport(HALUsageReporting::kResourceType_CANTalonSRX, m_deviceNumber + 1,
1413 mode);
1414 switch (mode) {
1415 case kPercentVbus:
1416 m_sendMode = kThrottle;
1417 break;
1418 case kCurrent:
1419 m_sendMode = kCurrentMode;
1420 break;
1421 case kSpeed:
1422 m_sendMode = kSpeedMode;
1423 break;
1424 case kPosition:
1425 m_sendMode = kPositionMode;
1426 break;
1427 case kVoltage:
1428 m_sendMode = kVoltageMode;
1429 break;
1430 case kFollower:
1431 m_sendMode = kFollowerMode;
1432 break;
1433 }
1434 // Keep the talon disabled until Set() is called.
1435 CTR_Code status = m_impl->SetModeSelect((int)kDisabled);
1436 if (status != CTR_OKAY) {
1437 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1438 }
1439}
1440/**
1441 * TODO documentation (see CANJaguar.cpp)
1442 */
1443void CANTalon::SetControlMode(CANSpeedController::ControlMode mode) {
1444 if (m_controlMode == mode) {
1445 /* we already are in this mode, don't perform disable workaround */
1446 } else {
1447 ApplyControlMode(mode);
1448 }
1449}
1450
1451/**
1452 * TODO documentation (see CANJaguar.cpp)
1453 */
1454CANSpeedController::ControlMode CANTalon::GetControlMode() const {
1455 return m_controlMode;
1456}
1457
1458void CANTalon::SetExpiration(float timeout) {
1459 m_safetyHelper->SetExpiration(timeout);
1460}
1461
1462float CANTalon::GetExpiration() const {
1463 return m_safetyHelper->GetExpiration();
1464}
1465
1466bool CANTalon::IsAlive() const { return m_safetyHelper->IsAlive(); }
1467
1468bool CANTalon::IsSafetyEnabled() const {
1469 return m_safetyHelper->IsSafetyEnabled();
1470}
1471
1472void CANTalon::SetSafetyEnabled(bool enabled) {
1473 m_safetyHelper->SetSafetyEnabled(enabled);
1474}
1475
1476void CANTalon::GetDescription(std::ostringstream& desc) const {
1477 desc << "CANTalon ID " << m_deviceNumber;
1478}
1479/**
1480 * @param devToLookup FeedbackDevice to lookup the scalar for. Because Talon
1481 * allows multiple sensors to be attached simultaneously, caller must
1482 * specify which sensor to lookup.
1483 * @return The number of native Talon units per rotation of the selected sensor.
1484 * Zero if the necessary sensor information is not available.
1485 * @see ConfigEncoderCodesPerRev
1486 * @see ConfigPotentiometerTurns
1487 */
1488double CANTalon::GetNativeUnitsPerRotationScalar(FeedbackDevice devToLookup)const
1489{
1490 bool scalingAvail = false;
1491 CTR_Code status = CTR_OKAY;
1492 double retval = 0;
1493 switch (devToLookup) {
1494 case QuadEncoder:
1495 { /* When caller wants to lookup Quadrature, the QEI may be in 1x if the selected feedback is edge counter.
1496 * Additionally if the quadrature source is the CTRE Mag encoder, then the CPR is known.
1497 * This is nice in that the calling app does not require knowing the CPR at all.
1498 * So do both checks here.
1499 */
1500 int32_t qeiPulsePerCount = 4; /* default to 4x */
1501 switch (m_feedbackDevice) {
1502 case CtreMagEncoder_Relative:
1503 case CtreMagEncoder_Absolute:
1504 /* we assume the quadrature signal comes from the MagEnc,
1505 of which we know the CPR already */
1506 retval = kNativePwdUnitsPerRotation;
1507 scalingAvail = true;
1508 break;
1509 case EncRising: /* Talon's QEI is setup for 1x, so perform 1x math */
1510 case EncFalling:
1511 qeiPulsePerCount = 1;
1512 break;
1513 case QuadEncoder: /* Talon's QEI is 4x */
1514 default: /* pulse width and everything else, assume its regular quad use. */
1515 break;
1516 }
1517 if (scalingAvail) {
1518 /* already deduced the scalar above, we're done. */
1519 } else {
1520 /* we couldn't deduce the scalar just based on the selection */
1521 if (0 == m_codesPerRev) {
1522 /* caller has never set the CPR. Most likely caller
1523 is just using engineering units so fall to the
1524 bottom of this func.*/
1525 } else {
1526 /* Talon expects PPR units */
1527 retval = qeiPulsePerCount * m_codesPerRev;
1528 scalingAvail = true;
1529 }
1530 }
1531 } break;
1532 case EncRising:
1533 case EncFalling:
1534 if (0 == m_codesPerRev) {
1535 /* caller has never set the CPR. Most likely caller
1536 is just using engineering units so fall to the
1537 bottom of this func.*/
1538 } else {
1539 /* Talon expects PPR units */
1540 retval = 1 * m_codesPerRev;
1541 scalingAvail = true;
1542 }
1543 break;
1544 case AnalogPot:
1545 case AnalogEncoder:
1546 if (0 == m_numPotTurns) {
1547 /* caller has never set the CPR. Most likely caller
1548 is just using engineering units so fall to the
1549 bottom of this func.*/
1550 } else {
1551 retval = (double)kNativeAdcUnitsPerRotation / m_numPotTurns;
1552 scalingAvail = true;
1553 }
1554 break;
1555 case CtreMagEncoder_Relative:
1556 case CtreMagEncoder_Absolute:
1557 case PulseWidth:
1558 retval = kNativePwdUnitsPerRotation;
1559 scalingAvail = true;
1560 break;
1561 }
1562 /* handle any detected errors */
1563 if (status != CTR_OKAY) {
1564 wpi_setErrorWithContext(status, getHALErrorMessage(status));
1565 }
1566 /* if scaling information is not possible, signal caller
1567 by returning zero */
1568 if (false == scalingAvail)
1569 retval = 0;
1570 return retval;
1571}
1572/**
1573 * @param fullRotations double precision value representing number of rotations of selected feedback sensor.
1574 * If user has never called the config routine for the selected sensor, then the caller
1575 * is likely passing rotations in engineering units already, in which case it is returned
1576 * as is.
1577 * @see ConfigPotentiometerTurns
1578 * @see ConfigEncoderCodesPerRev
1579 * @return fullRotations in native engineering units of the Talon SRX firmware.
1580 */
1581int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup,double fullRotations)const
1582{
1583 /* first assume we don't have config info, prep the default return */
1584 int32_t retval = (int32_t)fullRotations;
1585 /* retrieve scaling info */
1586 double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
1587 /* apply scalar if its available */
1588 if (scalar > 0)
1589 retval = (int32_t)(fullRotations*scalar);
1590 return retval;
1591}
1592/**
1593 * @param rpm double precision value representing number of rotations per minute of selected feedback sensor.
1594 * If user has never called the config routine for the selected sensor, then the caller
1595 * is likely passing rotations in engineering units already, in which case it is returned
1596 * as is.
1597 * @see ConfigPotentiometerTurns
1598 * @see ConfigEncoderCodesPerRev
1599 * @return sensor velocity in native engineering units of the Talon SRX firmware.
1600 */
1601int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup,double rpm)const
1602{
1603 /* first assume we don't have config info, prep the default return */
1604 int32_t retval = (int32_t)rpm;
1605 /* retrieve scaling info */
1606 double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
1607 /* apply scalar if its available */
1608 if (scalar > 0)
1609 retval = (int32_t)(rpm * kMinutesPer100msUnit * scalar);
1610 return retval;
1611}
1612/**
1613 * @param nativePos integral position of the feedback sensor in native Talon SRX units.
1614 * If user has never called the config routine for the selected sensor, then the return
1615 * will be in TALON SRX units as well to match the behavior in the 2015 season.
1616 * @see ConfigPotentiometerTurns
1617 * @see ConfigEncoderCodesPerRev
1618 * @return double precision number of rotations, unless config was never performed.
1619 */
1620double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup,int32_t nativePos)const
1621{
1622 /* first assume we don't have config info, prep the default return */
1623 double retval = (double)nativePos;
1624 /* retrieve scaling info */
1625 double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
1626 /* apply scalar if its available */
1627 if (scalar > 0)
1628 retval = ((double)nativePos) / scalar;
1629 return retval;
1630}
1631/**
1632 * @param nativeVel integral velocity of the feedback sensor in native Talon SRX units.
1633 * If user has never called the config routine for the selected sensor, then the return
1634 * will be in TALON SRX units as well to match the behavior in the 2015 season.
1635 * @see ConfigPotentiometerTurns
1636 * @see ConfigEncoderCodesPerRev
1637 * @return double precision of sensor velocity in RPM, unless config was never performed.
1638 */
1639double CANTalon::ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int32_t nativeVel)const
1640{
1641 /* first assume we don't have config info, prep the default return */
1642 double retval = (double)nativeVel;
1643 /* retrieve scaling info */
1644 double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
1645 /* apply scalar if its available */
1646 if (scalar > 0)
1647 retval = (double)(nativeVel) / (scalar*kMinutesPer100msUnit);
1648 return retval;
1649}
1650
1651/**
1652 * Enables Talon SRX to automatically zero the Sensor Position whenever an
1653 * edge is detected on the index signal.
1654 * @param enable boolean input, pass true to enable feature or false to disable.
1655 * @param risingEdge boolean input, pass true to clear the position on rising edge,
1656 * pass false to clear the position on falling edge.
1657 */
1658void CANTalon::EnableZeroSensorPositionOnIndex(bool enable, bool risingEdge)
1659{
1660 if (enable) {
1661 /* enable the feature, update the edge polarity first to ensure
1662 it is correct before the feature is enabled. */
1663 ConfigSetParameter(CanTalonSRX::eQuadIdxPolarity,risingEdge ? 1 : 0);
1664 ConfigSetParameter(CanTalonSRX::eClearPositionOnIdx,1);
1665 } else {
1666 /* disable the feature first, then update the edge polarity. */
1667 ConfigSetParameter(CanTalonSRX::eClearPositionOnIdx,0);
1668 ConfigSetParameter(CanTalonSRX::eQuadIdxPolarity,risingEdge ? 1 : 0);
1669 }
1670}
1671/**
1672* Common interface for inverting direction of a speed controller.
1673* Only works in PercentVbus, speed, and Voltage modes.
1674* @param isInverted The state of inversion, true is inverted.
1675*/
1676void CANTalon::SetInverted(bool isInverted) { m_isInverted = isInverted; }
1677
1678/**
1679 * Common interface for the inverting direction of a speed controller.
1680 *
1681 * @return isInverted The state of inversion, true is inverted.
1682 *
1683 */
1684bool CANTalon::GetInverted() const { return m_isInverted; }
1685
1686/**
1687 * Common interface for stopping the motor
1688 * Part of the MotorSafety interface
1689 *
1690 * @deprecated Call Disable instead.
1691*/
1692void CANTalon::StopMotor() { Disable(); }
1693
1694void CANTalon::ValueChanged(ITable* source, llvm::StringRef key,
1695 std::shared_ptr<nt::Value> value, bool isNew) {
1696 if(key == "Mode" && value->IsDouble()) SetControlMode(static_cast<CANSpeedController::ControlMode>(value->GetDouble()));
1697 if(key == "p" && value->IsDouble()) SetP(value->GetDouble());
1698 if(key == "i" && value->IsDouble()) SetI(value->GetDouble());
1699 if(key == "d" && value->IsDouble()) SetD(value->GetDouble());
1700 if(key == "f" && value->IsDouble()) SetF(value->GetDouble());
1701 if(key == "Enabled" && value->IsBoolean()) {
1702 if (value->GetBoolean()) {
1703 Enable();
1704 } else {
1705 Disable();
1706 }
1707 }
1708 if(key == "Value" && value->IsDouble()) Set(value->GetDouble());
1709}
1710
1711bool CANTalon::IsModePID(CANSpeedController::ControlMode mode) const {
1712 return mode == kCurrent || mode == kSpeed || mode == kPosition;
1713}
1714
1715void CANTalon::UpdateTable() {
1716 if (m_table != nullptr) {
1717 m_table->PutString("~TYPE~", "CANSpeedController");
1718 m_table->PutString("Type", "CANTalon");
1719 m_table->PutString("Mode", GetModeName(m_controlMode));
1720 m_table->PutNumber("p", GetP());
1721 m_table->PutNumber("i", GetI());
1722 m_table->PutNumber("d", GetD());
1723 m_table->PutNumber("f", GetF());
1724 m_table->PutBoolean("Enabled", IsControlEnabled());
1725 m_table->PutNumber("Value", Get());
1726 }
1727}
1728
1729void CANTalon::StartLiveWindowMode() {
1730 if (m_table != nullptr) {
1731 m_table->AddTableListener(this, true);
1732 }
1733}
1734
1735void CANTalon::StopLiveWindowMode() {
1736 if (m_table != nullptr) {
1737 m_table->RemoveTableListener(this);
1738 }
1739}
1740
1741std::string CANTalon::GetSmartDashboardType() const {
1742 return "CANSpeedController";
1743}
1744
1745void CANTalon::InitTable(std::shared_ptr<ITable> subTable) {
1746 m_table = subTable;
1747 UpdateTable();
1748}
1749
1750std::shared_ptr<ITable> CANTalon::GetTable() const { return m_table; }