001/* ----------------------------------------------------------------------------
002 * This file was automatically generated by SWIG (http://www.swig.org).
003 * Version 2.0.11
004 *
005 * Do not make changes to this file unless you know what you are doing--modify
006 * the SWIG interface file instead.
007 * ----------------------------------------------------------------------------- */
008
009package edu.wpi.first.wpilibj;
010
011import edu.wpi.first.wpilibj.hal.CanTalonSRX;
012import edu.wpi.first.wpilibj.hal.CanTalonJNI;
013import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_double;
014import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_int;
015import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_uint32_t;
016import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_CTR_Code;
017
018public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
019        private MotorSafetyHelper m_safetyHelper;
020        public enum ControlMode {
021                PercentVbus(0), Follower(5), Voltage(4), Position(1), Speed(2), Current(3), Disabled(15);
022
023    public int value;
024    public static ControlMode valueOf(int value) {
025                        for(ControlMode mode : values()) {
026                                if(mode.value == value) {
027                                        return mode;
028                                }
029                        }
030
031                        return null;
032    }
033
034    private ControlMode(int value) {
035      this.value = value;
036    }
037        }
038
039  public enum FeedbackDevice {
040                QuadEncoder(0), AnalogPot(2), AnalogEncoder(3), EncRising(4), EncFalling(5);
041
042    public int value;
043
044    public static FeedbackDevice valueOf(int value) {
045                        for(FeedbackDevice mode : values()) {
046                                if(mode.value == value) {
047                                        return mode;
048                                }
049                        }
050
051                        return null;
052    }
053
054    private FeedbackDevice(int value) {
055      this.value = value;
056    }
057        }
058  /** enumerated types for frame rate ms */
059  public enum StatusFrameRate {
060                General(0), Feedback(1), QuadEncoder(2), AnalogTempVbat(3);
061    public int value;
062    public static StatusFrameRate valueOf(int value) {
063                        for(StatusFrameRate mode : values()) {
064                                if(mode.value == value) {
065                                        return mode;
066                                }
067                        }
068                        return null;
069    }
070    private StatusFrameRate(int value) {
071      this.value = value;
072    }
073  }
074
075
076  private CanTalonSRX m_impl;
077  ControlMode m_controlMode;
078  private static double kDelayForSolicitedSignals = 0.004;
079
080  int m_deviceNumber;
081  boolean m_controlEnabled;
082  int m_profile;
083
084  double m_setPoint;
085
086  public CANTalon(int deviceNumber) {
087    m_deviceNumber = deviceNumber;
088    m_impl = new CanTalonSRX(deviceNumber);
089    m_safetyHelper = new MotorSafetyHelper(this);
090    m_controlEnabled = true;
091    m_profile = 0;
092    m_setPoint = 0;
093    setProfile(m_profile);
094    applyControlMode(ControlMode.PercentVbus);
095  }
096  public CANTalon(int deviceNumber,int controlPeriodMs) {
097    m_deviceNumber = deviceNumber;
098    m_impl = new CanTalonSRX(deviceNumber,controlPeriodMs); /* bound period to be within [1 ms,95 ms] */
099    m_safetyHelper = new MotorSafetyHelper(this);
100    m_controlEnabled = true;
101    m_profile = 0;
102    m_setPoint = 0;
103    setProfile(m_profile);
104    applyControlMode(ControlMode.PercentVbus);
105  }
106
107  @Override
108  public void pidWrite(double output)
109     {
110    if (getControlMode() == ControlMode.PercentVbus) {
111      set(output);
112    }
113    else {
114                        throw new IllegalStateException("PID only supported in PercentVbus mode");
115    }
116  }
117
118  public void delete() {
119    m_impl.delete();
120  }
121
122  /**
123   * Sets the appropriate output on the talon, depending on the mode.
124   *
125   * In PercentVbus, the output is between -1.0 and 1.0, with 0.0 as stopped.
126   * In Follower mode, the output is the integer device ID of the talon to duplicate.
127   * In Voltage mode, outputValue is in volts.
128   * In Current mode, outputValue is in amperes.
129   * In Speed mode, outputValue is in position change / 10ms.
130   * In Position mode, outputValue is in encoder ticks or an analog value,
131   *   depending on the sensor.
132   *
133   * @param outputValue The setpoint value, as described above.
134   */
135  public void set(double outputValue) {
136    /* feed safety helper since caller just updated our output */
137    m_safetyHelper.feed();
138    if (m_controlEnabled) {
139      m_setPoint = outputValue;
140      switch (m_controlMode) {
141        case PercentVbus:
142          m_impl.Set(outputValue);
143          break;
144        case Follower:
145          m_impl.SetDemand((int)outputValue);
146          break;
147        case Voltage:
148          // Voltage is an 8.8 fixed point number.
149          int volts = (int)(outputValue * 256);
150          m_impl.SetDemand(volts);
151          break;
152        case Speed:
153          m_impl.SetDemand((int)outputValue);
154          break;
155        case Position:
156          m_impl.SetDemand((int)outputValue);
157          break;
158        default:
159          break;
160      }
161      m_impl.SetModeSelect(m_controlMode.value);
162    }
163  }
164
165  /**
166   * Sets the output of the Talon.
167   *
168   * @param outputValue See set().
169   * @param thisValueDoesNotDoAnything corresponds to syncGroup from Jaguar; not relevant here.
170   */
171  @Override
172  public void set(double outputValue, byte thisValueDoesNotDoAnything) {
173    set(outputValue);
174  }
175
176  /**
177   * Flips the sign (multiplies by negative one) the sensor values going into
178   *the talon.
179   *
180   * This only affects position and velocity closed loop control. Allows for
181   *   situations where you may have a sensor flipped and going in the wrong
182   *   direction.
183   *
184   * @param flip True if sensor input should be flipped; False if not.
185   */
186  public void reverseSensor(boolean flip) {
187    m_impl.SetRevFeedbackSensor(flip ? 1 : 0);
188  }
189
190   /**
191    * Flips the sign (multiplies by negative one) the throttle values going into
192    *  the motor on the talon in closed loop modes.
193    *
194    * @param flip True if motor output should be flipped; False if not.
195    */
196  public void reverseOutput(boolean flip) {
197    m_impl.SetRevMotDuringCloseLoopEn(flip ? 1 : 0);
198  }
199
200  /**
201   * Gets the current status of the Talon (usually a sensor value).
202   *
203   * In Current mode: returns output current.
204   * In Speed mode: returns current speed.
205   * In Position mode: returns current sensor position.
206   * In PercentVbus and Follower modes: returns current applied throttle.
207   *
208   * @return The current sensor value of the Talon.
209   */
210  public double get() {
211    long valuep = CanTalonJNI.new_intp();
212    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
213    switch (m_controlMode) {
214      case Voltage:
215        return getOutputVoltage();
216      case Current:
217        return getOutputCurrent();
218      case Speed:
219        m_impl.GetSensorVelocity(swigp);
220        return (double)CanTalonJNI.intp_value(valuep);
221      case Position:
222        m_impl.GetSensorPosition(swigp);
223        return (double)CanTalonJNI.intp_value(valuep);
224      case PercentVbus:
225      default:
226        m_impl.GetAppliedThrottle(swigp);
227        return (double)CanTalonJNI.intp_value(valuep) / 1023.0;
228    }
229  }
230
231  /**
232   * Get the current encoder position, regardless of whether it is the current feedback device.
233   *
234   * @return The current position of the encoder.
235   */
236  public int getEncPosition() {
237    long valuep = CanTalonJNI.new_intp();
238    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
239    m_impl.GetEncPosition(swigp);
240    return CanTalonJNI.intp_value(valuep);
241  }
242
243  /**
244   * Get the current encoder velocity, regardless of whether it is the current feedback device.
245   *
246   * @return The current speed of the encoder.
247   */
248  public int getEncVelocity() {
249    long valuep = CanTalonJNI.new_intp();
250    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
251    m_impl.GetEncVel(swigp);
252    return CanTalonJNI.intp_value(valuep);
253  }
254
255  /**
256   * Get the number of of rising edges seen on the index pin.
257   *
258   * @return number of rising edges on idx pin.
259   */
260  public int getNumberOfQuadIdxRises() {
261    long valuep = CanTalonJNI.new_intp();
262    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
263    m_impl.GetEncIndexRiseEvents(swigp);
264    return CanTalonJNI.intp_value(valuep);
265  }
266  /**
267   * @return IO level of QUADA pin.
268   */
269  public int getPinStateQuadA(){
270    long valuep = CanTalonJNI.new_intp();
271    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
272    m_impl.GetQuadApin(swigp);
273    return CanTalonJNI.intp_value(valuep);
274  }
275  /**
276   * @return IO level of QUADB pin.
277   */
278  public int getPinStateQuadB() {
279    long valuep = CanTalonJNI.new_intp();
280    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
281    m_impl.GetQuadBpin(swigp);
282    return CanTalonJNI.intp_value(valuep);
283  }
284  /**
285   * @return IO level of QUAD Index pin.
286   */
287  public int getPinStateQuadIdx(){
288    long valuep = CanTalonJNI.new_intp();
289    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
290    m_impl.GetQuadIdxpin(swigp);
291    return CanTalonJNI.intp_value(valuep);
292  }
293
294  /**
295   * Get the current analog in position, regardless of whether it is the current
296   * feedback device.
297   *
298   * @return The 24bit analog position.  The bottom ten bits is the ADC (0 - 1023) on
299   *                                                            the analog pin of the Talon. The upper 14 bits
300   *                                                            tracks the overflows and underflows (continuous sensor).
301   */
302  public int getAnalogInPosition() {
303    long valuep = CanTalonJNI.new_intp();
304    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
305    m_impl.GetAnalogInWithOv(swigp);
306    return CanTalonJNI.intp_value(valuep);
307  }
308  /**
309   * Get the current analog in position, regardless of whether it is the current
310   * feedback device.
311   * @return The ADC (0 - 1023) on analog pin of the Talon.
312   */
313  public int getAnalogInRaw() {
314    return getAnalogInPosition() & 0x3FF;
315  }
316  /**
317   * Get the current encoder velocity, regardless of whether it is the current
318   * feedback device.
319   *
320   * @return The current speed of the analog in device.
321   */
322  public int getAnalogInVelocity() {
323    long valuep = CanTalonJNI.new_intp();
324    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
325    m_impl.GetAnalogInVel(swigp);
326    return CanTalonJNI.intp_value(valuep);
327  }
328
329  /**
330   * Get the current difference between the setpoint and the sensor value.
331   *
332   * @return The error, in whatever units are appropriate.
333   */
334  public int getClosedLoopError() {
335    long valuep = CanTalonJNI.new_intp();
336    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
337    m_impl.GetCloseLoopErr(swigp);
338    return CanTalonJNI.intp_value(valuep);
339  }
340  // Returns true if limit switch is closed. false if open.
341  public boolean isFwdLimitSwitchClosed() {
342    long valuep = CanTalonJNI.new_intp();
343    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
344    m_impl.GetLimitSwitchClosedFor(swigp);
345    return (CanTalonJNI.intp_value(valuep)==0) ? true : false;
346  }
347  // Returns true if limit switch is closed. false if open.
348  public boolean isRevLimitSwitchClosed() {
349    long valuep = CanTalonJNI.new_intp();
350    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
351    m_impl.GetLimitSwitchClosedRev(swigp);
352    return (CanTalonJNI.intp_value(valuep)==0) ? true : false;
353  }
354  // Returns true if break is enabled during neutral. false if coast.
355  public boolean getBrakeEnableDuringNeutral() {
356    long valuep = CanTalonJNI.new_intp();
357    SWIGTYPE_p_int swigp = new SWIGTYPE_p_int(valuep, true);
358    m_impl.GetBrakeIsEnabled(swigp);
359    return (CanTalonJNI.intp_value(valuep)==0) ? false : true;
360  }
361  /**
362   *  Returns temperature of Talon, in degrees Celsius.
363   */
364  public double getTemp() {
365    long tempp = CanTalonJNI.new_doublep(); // Create a new swig pointer.
366    m_impl.GetTemp(new SWIGTYPE_p_double(tempp, true));
367    return CanTalonJNI.doublep_value(tempp);
368  }
369
370  /**
371   *  Returns the current going through the Talon, in Amperes.
372   */
373  public double getOutputCurrent() {
374    long curp = CanTalonJNI.new_doublep(); // Create a new swig pointer.
375    m_impl.GetCurrent(new SWIGTYPE_p_double(curp, true));
376    return CanTalonJNI.doublep_value(curp);
377  }
378
379  /**
380   * @return The voltage being output by the Talon, in Volts.
381   */
382  public double getOutputVoltage() {
383    long throttlep = CanTalonJNI.new_intp();
384    m_impl.GetAppliedThrottle(new SWIGTYPE_p_int(throttlep, true));
385    double voltage = getBusVoltage() * (double)CanTalonJNI.intp_value(throttlep) / 1023.0;
386    return voltage;
387  }
388
389  /**
390   * @return The voltage at the battery terminals of the Talon, in Volts.
391   */
392  public double getBusVoltage() {
393    long voltagep = CanTalonJNI.new_doublep();
394    SWIGTYPE_p_CTR_Code status = m_impl.GetBatteryV(new SWIGTYPE_p_double(voltagep, true));
395    /* Note: This section needs the JNI bindings regenerated with
396     pointer_functions for CTR_Code included in order to be able to catch notice
397     and throw errors.
398     if (CanTalonJNI.CTR_Codep_value(status) != 0) {
399       // TODO throw an error.
400     }*/
401
402    return CanTalonJNI.doublep_value(voltagep);
403  }
404
405  /**
406 * TODO documentation (see CANJaguar.java)
407 *
408 * @return The position of the sensor currently providing feedback.
409 *                      When using analog sensors, 0 units corresponds to 0V, 1023 units corresponds to 3.3V
410 *                      When using an analog encoder (wrapping around 1023 to 0 is possible) the units are still 3.3V per 1023 units.
411 *                      When using quadrature, each unit is a quadrature edge (4X) mode.
412 */
413  public double getPosition() {
414    long positionp = CanTalonJNI.new_intp();
415    m_impl.GetSensorPosition(new SWIGTYPE_p_int(positionp, true));
416    return CanTalonJNI.intp_value(positionp);
417  }
418
419  public void setPosition(double pos) {
420    m_impl.SetSensorPosition((int)pos);
421  }
422
423/**
424 * TODO documentation (see CANJaguar.java)
425 *
426 * @return The speed of the sensor currently providing feedback.
427 *
428 * The speed units will be in the sensor's native ticks per 100ms.
429 *
430 * For analog sensors, 3.3V corresponds to 1023 units.
431 *              So a speed of 200 equates to ~0.645 dV per 100ms or 6.451 dV per second.
432 *              If this is an analog encoder, that likely means 1.9548 rotations per sec.
433 * For quadrature encoders, each unit corresponds a quadrature edge (4X).
434 *              So a 250 count encoder will produce 1000 edge events per rotation.
435 *              An example speed of 200 would then equate to 20% of a rotation per 100ms,
436 *              or 10 rotations per second.
437 */
438  public double getSpeed() {
439    long speedp = CanTalonJNI.new_intp();
440    m_impl.GetSensorVelocity(new SWIGTYPE_p_int(speedp, true));
441    return CanTalonJNI.intp_value(speedp);
442  }
443
444  public ControlMode getControlMode() {
445    return m_controlMode;
446  }
447  /**
448   * Fixup the m_controlMode so set() serializes the correct demand value.
449   * Also fills the modeSelecet in the control frame to disabled.
450   * @param controlMode Control mode to ultimately enter once user calls set().
451   * @see #set
452   */  
453  private void applyControlMode(ControlMode controlMode) {
454    m_controlMode = controlMode;
455    if (controlMode == ControlMode.Disabled)
456      m_controlEnabled = false;
457    // Disable until set() is called.
458    m_impl.SetModeSelect(ControlMode.Disabled.value);
459  }
460  public void changeControlMode(ControlMode controlMode) {
461    if(m_controlMode == controlMode){
462      /* we already are in this mode, don't perform disable workaround */
463    }else{
464      applyControlMode(controlMode);
465    }
466  }
467
468  public void setFeedbackDevice(FeedbackDevice device) {
469    m_impl.SetFeedbackDeviceSelect(device.value);
470  }
471  public void setStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs){
472    m_impl.SetStatusFrameRate(stateFrame.value,periodMs);
473  }
474  public void enableControl() {
475    changeControlMode(m_controlMode);
476                m_controlEnabled = true;
477  }
478
479  public void disableControl() {
480    m_impl.SetModeSelect(ControlMode.Disabled.value);
481                m_controlEnabled = false;
482  }
483
484  public boolean isControlEnabled() {
485    return m_controlEnabled;
486  }
487
488  /**
489   * Get the current proportional constant.
490   *
491   * @return double proportional constant for current profile.
492   */
493  public double getP() {
494                //if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
495                //      throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
496                //}
497
498    // Update the information that we have.
499    if (m_profile == 0)
500      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_P);
501    else
502      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_P);
503
504    // Briefly wait for new values from the Talon.
505    Timer.delay(kDelayForSolicitedSignals);
506
507    long pp = CanTalonJNI.new_doublep();
508    m_impl.GetPgain(m_profile, new SWIGTYPE_p_double(pp, true));
509    return CanTalonJNI.doublep_value(pp);
510  }
511
512  public double getI() {
513                //if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
514                //      throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
515                //}
516
517    // Update the information that we have.
518    if (m_profile == 0)
519      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_I);
520    else
521      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_I);
522
523    // Briefly wait for new values from the Talon.
524    Timer.delay(kDelayForSolicitedSignals);
525
526    long ip = CanTalonJNI.new_doublep();
527    m_impl.GetIgain(m_profile, new SWIGTYPE_p_double(ip, true));
528    return CanTalonJNI.doublep_value(ip);
529  }
530
531  public double getD() {
532                //if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
533                //      throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
534                //}
535
536    // Update the information that we have.
537    if (m_profile == 0)
538      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_D);
539    else
540      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_D);
541
542    // Briefly wait for new values from the Talon.
543    Timer.delay(kDelayForSolicitedSignals);
544
545    long dp = CanTalonJNI.new_doublep();
546    m_impl.GetDgain(m_profile, new SWIGTYPE_p_double(dp, true));
547    return CanTalonJNI.doublep_value(dp);
548  }
549
550  public double getF() {
551                //if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
552                //      throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
553                //}
554
555    // Update the information that we have.
556    if (m_profile == 0)
557      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_F);
558    else
559      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_F);
560
561    // Briefly wait for new values from the Talon.
562    Timer.delay(kDelayForSolicitedSignals);
563
564    long fp = CanTalonJNI.new_doublep();
565    m_impl.GetFgain(m_profile, new SWIGTYPE_p_double(fp, true));
566    return CanTalonJNI.doublep_value(fp);
567  }
568
569  public double getIZone() {
570                //if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
571                //      throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
572                //}
573
574    // Update the information that we have.
575    if (m_profile == 0)
576      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_IZone);
577    else
578      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_IZone);
579
580    // Briefly wait for new values from the Talon.
581    Timer.delay(kDelayForSolicitedSignals);
582
583    long fp = CanTalonJNI.new_intp();
584    m_impl.GetIzone(m_profile, new SWIGTYPE_p_int(fp, true));
585    return CanTalonJNI.intp_value(fp);
586  }
587  /**
588   * Get the closed loop ramp rate for the current profile.
589   *
590   * Limits the rate at which the throttle will change.
591   * Only affects position and speed closed loop modes.
592   *
593   * @return rampRate Maximum change in voltage, in volts / sec.
594   * @see #setProfile For selecting a certain profile.
595   */
596  public double getCloseLoopRampRate() {
597        //      if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
598        //              throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
599        //      }
600
601    // Update the information that we have.
602    if (m_profile == 0)
603      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot0_CloseLoopRampRate);
604    else
605      m_impl.RequestParam(CanTalonSRX.param_t.eProfileParamSlot1_CloseLoopRampRate);
606
607    // Briefly wait for new values from the Talon.
608    Timer.delay(kDelayForSolicitedSignals);
609
610    long fp = CanTalonJNI.new_intp();
611    m_impl.GetCloseLoopRampRate(m_profile, new SWIGTYPE_p_int(fp, true));
612    double throttlePerMs = CanTalonJNI.intp_value(fp);
613        return throttlePerMs / 1023.0 * 12.0 * 1000.0;
614  }
615  /**
616  * @return The version of the firmware running on the Talon
617  */
618  public long GetFirmwareVersion() {
619
620    // Update the information that we have.
621    m_impl.RequestParam(CanTalonSRX.param_t.eFirmVers);
622
623    // Briefly wait for new values from the Talon.
624    Timer.delay(kDelayForSolicitedSignals);
625
626    long fp = CanTalonJNI.new_intp();
627    m_impl.GetParamResponseInt32(CanTalonSRX.param_t.eFirmVers, new SWIGTYPE_p_int(fp, true));
628    return CanTalonJNI.intp_value(fp);
629  }
630  public long GetIaccum() {
631
632    // Update the information that we have.
633    m_impl.RequestParam(CanTalonSRX.param_t.ePidIaccum);
634
635    // Briefly wait for new values from the Talon.
636    Timer.delay(kDelayForSolicitedSignals);
637
638    long fp = CanTalonJNI.new_intp();
639    m_impl.GetParamResponseInt32(CanTalonSRX.param_t.ePidIaccum, new SWIGTYPE_p_int(fp, true));
640    return CanTalonJNI.intp_value(fp);
641  }
642
643        /**
644         * Clear the accumulator for I gain.
645         */
646        public void ClearIaccum()
647        {
648                SWIGTYPE_p_CTR_Code status = m_impl.SetParam(CanTalonSRX.param_t.ePidIaccum, 0);
649        }
650  /**
651   * Set the proportional value of the currently selected profile.
652   *
653   * @param p Proportional constant for the currently selected PID profile.
654   * @see #setProfile For selecting a certain profile.
655   */
656  public void setP(double p) {
657    m_impl.SetPgain(m_profile, p);
658  }
659
660  /**
661   * Set the integration constant of the currently selected profile.
662   *
663   * @param i Integration constant for the currently selected PID profile.
664   * @see #setProfile For selecting a certain profile.
665   */
666  public void setI(double i) {
667    m_impl.SetIgain(m_profile, i);
668  }
669
670  /**
671   * Set the derivative constant of the currently selected profile.
672   *
673   * @param d Derivative constant for the currently selected PID profile.
674   * @see #setProfile For selecting a certain profile.
675   */
676  public void setD(double d) {
677    m_impl.SetDgain(m_profile, d);
678  }
679
680  /**
681   * Set the feedforward value of the currently selected profile.
682   *
683   * @param f Feedforward constant for the currently selected PID profile.
684   * @see #setProfile For selecting a certain profile.
685   */
686  public void setF(double f) {
687    m_impl.SetFgain(m_profile, f);
688  }
689
690   /**
691    * Set the integration zone of the current Closed Loop profile.
692    *
693    * Whenever the error is larger than the izone value, the accumulated
694    *  integration error is cleared so that high errors aren't racked up when at
695    *  high errors.
696    * An izone value of 0 means no difference from a standard PIDF loop.
697    *
698    * @param izone Width of the integration zone.
699    * @see #setProfile For selecting a certain profile.
700    */
701  public void setIZone(int izone) {
702    m_impl.SetIzone(m_profile, izone);
703  }
704
705  /**
706   * Set the closed loop ramp rate for the current profile.
707   *
708   * Limits the rate at which the throttle will change.
709   * Only affects position and speed closed loop modes.
710   *
711   * @param rampRate Maximum change in voltage, in volts / sec.
712   * @see #setProfile For selecting a certain profile.
713   */
714  public void setCloseLoopRampRate(double rampRate) {
715    // CanTalonSRX takes units of Throttle (0 - 1023) / 1ms.
716    int rate = (int) (rampRate * 1023.0 / 12.0 / 1000.0);
717    m_impl.SetCloseLoopRampRate(m_profile, rate);
718  }
719
720  /**
721   * Set the voltage ramp rate for the current profile.
722   *
723   * Limits the rate at which the throttle will change.
724   * Affects all modes.
725   *
726   * @param rampRate Maximum change in voltage, in volts / sec.
727   */
728  public void setVoltageRampRate(double rampRate) {
729    // CanTalonSRX takes units of Throttle (0 - 1023) / 10ms.
730    int rate = (int) (rampRate * 1023.0 / 12.0 /100.0);
731    m_impl.SetRampThrottle(rate);
732  }
733
734  /**
735   * Sets control values for closed loop control.
736   *
737   * @param p Proportional constant.
738   * @param i Integration constant.
739   * @param d Differential constant.
740   * @param f Feedforward constant.
741   * @param izone Integration zone -- prevents accumulation of integration error
742   *   with large errors. Setting this to zero will ignore any izone stuff.
743   * @param closeLoopRampRate Closed loop ramp rate. Maximum change in voltage, in volts / sec.
744   * @param profile which profile to set the pid constants for. You can have two
745   *   profiles, with values of 0 or 1, allowing you to keep a second set of values
746   *   on hand in the talon. In order to switch profiles without recalling setPID,
747   *   you must call setProfile().
748   */
749  public void setPID(double p, double i, double d, double f, int izone, double closeLoopRampRate, int profile)
750    {
751    if (profile != 0 && profile != 1)
752      throw new IllegalArgumentException("Talon PID profile must be 0 or 1.");
753    m_profile = profile;
754    setProfile(profile);
755    setP(p);
756    setI(i);
757    setD(d);
758    setF(f);
759    setIZone(izone);
760    setCloseLoopRampRate(closeLoopRampRate);
761  }
762
763  public void setPID(double p, double i, double d) {
764    setPID(p, i, d, 0, 0, 0, m_profile);
765  }
766
767  /**
768   * @return The latest value set using set().
769   */
770  public double getSetpoint() {
771    return m_setPoint;
772  }
773
774  /**
775   * Select which closed loop profile to use, and uses whatever PIDF gains and
776   * the such that are already there.
777   */
778  public void setProfile(int profile)
779     {
780    if (profile != 0 && profile != 1)
781      throw new IllegalArgumentException("Talon PID profile must be 0 or 1.");
782    m_profile = profile;
783    m_impl.SetProfileSlotSelect(m_profile);
784  }
785
786        /**
787        * Common interface for stopping a motor.
788        *
789        * @deprecated Use disableControl instead.
790        */
791        @Override
792        @Deprecated
793        public void stopMotor() {
794                disableControl();
795        }
796
797  @Override
798  public void disable() {
799    disableControl();
800  }
801
802        public int getDeviceID() {
803                return m_deviceNumber;
804        }
805
806  // TODO: Documentation for all these accessors/setters for misc. stuff.
807  public void setForwardSoftLimit(int forwardLimit) {
808    m_impl.SetForwardSoftLimit(forwardLimit);
809  }
810
811  public void enableForwardSoftLimit(boolean enable) {
812    m_impl.SetForwardSoftEnable(enable ? 1 : 0);
813  }
814
815  public void setReverseSoftLimit(int reverseLimit) {
816    m_impl.SetReverseSoftLimit(reverseLimit);
817  }
818
819  public void enableReverseSoftLimit(boolean enable) {
820    m_impl.SetReverseSoftEnable(enable ? 1 : 0);
821  }
822
823  public void clearStickyFaults() {
824    m_impl.ClearStickyFaults();
825  }
826
827  public void enableLimitSwitch(boolean forward, boolean reverse) {
828    int mask = 4 + (forward ? 1 : 0) * 2 + (reverse ? 1 : 0);
829    m_impl.SetOverrideLimitSwitchEn(mask);
830  }
831  /**
832   * Configure the fwd limit switch to be normally open or normally closed.
833   * Talon will disable momentarilly if the Talon's current setting
834   * is dissimilar to the caller's requested setting.
835   *
836   * Since Talon saves setting to flash this should only affect
837   * a given Talon initially during robot install.
838   *
839   * @param normallyOpen true for normally open.  false for normally closed.
840   */
841  public void ConfigFwdLimitSwitchNormallyOpen(boolean normallyOpen)
842  {
843        SWIGTYPE_p_CTR_Code status = m_impl.SetParam(CanTalonSRX.param_t.eOnBoot_LimitSwitch_Forward_NormallyClosed,normallyOpen ? 0 : 1);
844  }
845  /**
846   * Configure the rev limit switch to be normally open or normally closed.
847   * Talon will disable momentarilly if the Talon's current setting
848   * is dissimilar to the caller's requested setting.
849   *
850   * Since Talon saves setting to flash this should only affect
851   * a given Talon initially during robot install.
852   *
853   * @param normallyOpen true for normally open.  false for normally closed.
854   */
855  public void ConfigRevLimitSwitchNormallyOpen(boolean normallyOpen)
856  {
857        SWIGTYPE_p_CTR_Code status = m_impl.SetParam(CanTalonSRX.param_t.eOnBoot_LimitSwitch_Reverse_NormallyClosed,normallyOpen ? 0 : 1);
858  }
859
860  public void enableBrakeMode(boolean brake) {
861    m_impl.SetOverrideBrakeType(brake ? 2 : 1);
862  }
863
864  public int getFaultOverTemp() {
865    long valuep = CanTalonJNI.new_intp();
866    m_impl.GetFault_OverTemp(new SWIGTYPE_p_int(valuep, true));
867    return CanTalonJNI.intp_value(valuep);
868  }
869
870  public int getFaultUnderVoltage() {
871    long valuep = CanTalonJNI.new_intp();
872    m_impl.GetFault_UnderVoltage(new SWIGTYPE_p_int(valuep, true));
873    return CanTalonJNI.intp_value(valuep);
874  }
875
876  public int getFaultForLim() {
877    long valuep = CanTalonJNI.new_intp();
878    m_impl.GetFault_ForLim(new SWIGTYPE_p_int(valuep, true));
879    return CanTalonJNI.intp_value(valuep);
880  }
881
882  public int getFaultRevLim() {
883    long valuep = CanTalonJNI.new_intp();
884    m_impl.GetFault_RevLim(new SWIGTYPE_p_int(valuep, true));
885    return CanTalonJNI.intp_value(valuep);
886  }
887
888  public int getFaultHardwareFailure() {
889    long valuep = CanTalonJNI.new_intp();
890    m_impl.GetFault_HardwareFailure(new SWIGTYPE_p_int(valuep, true));
891    return CanTalonJNI.intp_value(valuep);
892  }
893
894  public int getFaultForSoftLim() {
895    long valuep = CanTalonJNI.new_intp();
896    m_impl.GetFault_ForSoftLim(new SWIGTYPE_p_int(valuep, true));
897    return CanTalonJNI.intp_value(valuep);
898  }
899
900  public int getFaultRevSoftLim() {
901    long valuep = CanTalonJNI.new_intp();
902    m_impl.GetFault_RevSoftLim(new SWIGTYPE_p_int(valuep, true));
903    return CanTalonJNI.intp_value(valuep);
904  }
905
906  public int getStickyFaultOverTemp() {
907    long valuep = CanTalonJNI.new_intp();
908    m_impl.GetStckyFault_OverTemp(new SWIGTYPE_p_int(valuep, true));
909    return CanTalonJNI.intp_value(valuep);
910  }
911
912  public int getStickyFaultUnderVoltage() {
913    long valuep = CanTalonJNI.new_intp();
914    m_impl.GetStckyFault_UnderVoltage(new SWIGTYPE_p_int(valuep, true));
915    return CanTalonJNI.intp_value(valuep);
916  }
917
918  public int getStickyFaultForLim() {
919    long valuep = CanTalonJNI.new_intp();
920    m_impl.GetStckyFault_ForLim(new SWIGTYPE_p_int(valuep, true));
921    return CanTalonJNI.intp_value(valuep);
922  }
923
924  public int getStickyFaultRevLim() {
925    long valuep = CanTalonJNI.new_intp();
926    m_impl.GetStckyFault_RevLim(new SWIGTYPE_p_int(valuep, true));
927    return CanTalonJNI.intp_value(valuep);
928  }
929
930  public int getStickyFaultForSoftLim() {
931    long valuep = CanTalonJNI.new_intp();
932    m_impl.GetStckyFault_ForSoftLim(new SWIGTYPE_p_int(valuep, true));
933    return CanTalonJNI.intp_value(valuep);
934  }
935
936  public int getStickyFaultRevSoftLim() {
937    long valuep = CanTalonJNI.new_intp();
938    m_impl.GetStckyFault_RevSoftLim(new SWIGTYPE_p_int(valuep, true));
939    return CanTalonJNI.intp_value(valuep);
940  }
941
942
943        @Override
944        public void setExpiration(double timeout) {
945                m_safetyHelper.setExpiration(timeout);
946        }
947
948        @Override
949        public double getExpiration() {
950                return m_safetyHelper.getExpiration();
951        }
952
953        @Override
954        public boolean isAlive() {
955                return m_safetyHelper.isAlive();
956        }
957
958        @Override
959        public boolean isSafetyEnabled() {
960                return m_safetyHelper.isSafetyEnabled();
961        }
962
963        @Override
964        public void setSafetyEnabled(boolean enabled) {
965                m_safetyHelper.setSafetyEnabled(enabled);
966        }
967
968        @Override
969        public String getDescription() {
970                return "CANJaguar ID "+m_deviceNumber;
971        }
972}