mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
C++
Added Get/clear routine for IntegralAccumulator Added missing status check in GetFirmwareVersion(). I don't expect this to affect anything. JAVA Renamed getRampRate to getCloseLoopRampRate in java to match the set routines in java, and match all routines in cpp. Added GetFirmwareVersion to java to match cpp. Added Get/clear routine for IntegralAccumulator Retested all three routines in java. Change-Id: I4ce9d9c87a379b9d4a76aae226e2072876218688
This commit is contained in:
committed by
James Kuszmaul
parent
e3ac0b628c
commit
19a7243bfc
@@ -438,7 +438,7 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
|
||||
return CanTalonJNI.intp_value(fp);
|
||||
}
|
||||
|
||||
public double getRampRate() {
|
||||
public double getCloseLoopRampRate() {
|
||||
// if(!(m_controlMode.equals(ControlMode.Position) || m_controlMode.equals(ControlMode.Speed))) {
|
||||
// throw new IllegalStateException("PID mode only applies in Position and Speed modes.");
|
||||
// }
|
||||
@@ -456,8 +456,41 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
|
||||
m_impl.GetCloseLoopRampRate(m_profile, new SWIGTYPE_p_int(fp, true));
|
||||
return CanTalonJNI.intp_value(fp);
|
||||
}
|
||||
/**
|
||||
* @return The version of the firmware running on the Talon
|
||||
*/
|
||||
public long GetFirmwareVersion() {
|
||||
|
||||
// Update the information that we have.
|
||||
m_impl.RequestParam(CanTalonSRX.param_t.eFirmVers);
|
||||
|
||||
// Briefly wait for new values from the Talon.
|
||||
Timer.delay(0.001);
|
||||
|
||||
long fp = CanTalonJNI.new_intp();
|
||||
m_impl.GetParamResponseInt32(CanTalonSRX.param_t.eFirmVers, new SWIGTYPE_p_int(fp, true));
|
||||
return CanTalonJNI.intp_value(fp);
|
||||
}
|
||||
public long GetIaccum() {
|
||||
|
||||
// Update the information that we have.
|
||||
m_impl.RequestParam(CanTalonSRX.param_t.ePidIaccum);
|
||||
|
||||
// Briefly wait for new values from the Talon.
|
||||
Timer.delay(0.001);
|
||||
|
||||
long fp = CanTalonJNI.new_intp();
|
||||
m_impl.GetParamResponseInt32(CanTalonSRX.param_t.ePidIaccum, new SWIGTYPE_p_int(fp, true));
|
||||
return CanTalonJNI.intp_value(fp);
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear the accumulator for I gain.
|
||||
*/
|
||||
public void ClearIaccum()
|
||||
{
|
||||
SWIGTYPE_p_CTR_Code status = m_impl.SetParam(CanTalonSRX.param_t.ePidIaccum, 0);
|
||||
}
|
||||
/**
|
||||
* Set the proportional value of the currently selected profile.
|
||||
*
|
||||
|
||||
@@ -435,6 +435,8 @@ public class CanTalonSRX extends CtreCanNode {
|
||||
public final static CanTalonSRX.param_t eResetFlags = new CanTalonSRX.param_t("eResetFlags", CanTalonJNI.CanTalonSRX_eResetFlags_get());
|
||||
public final static CanTalonSRX.param_t eFirmVers = new CanTalonSRX.param_t("eFirmVers", CanTalonJNI.CanTalonSRX_eFirmVers_get());
|
||||
public final static CanTalonSRX.param_t eSettingsChanged = new CanTalonSRX.param_t("eSettingsChanged", CanTalonJNI.CanTalonSRX_eSettingsChanged_get());
|
||||
public final static CanTalonSRX.param_t eQuadFilterEn = new CanTalonSRX.param_t("eQuadFilterEn", CanTalonJNI.CanTalonSRX_eQuadFilterEn_get());
|
||||
public final static CanTalonSRX.param_t ePidIaccum = new CanTalonSRX.param_t("ePidIaccum", CanTalonJNI.CanTalonSRX_ePidIaccum_get());
|
||||
|
||||
public final int swigValue() {
|
||||
return swigValue;
|
||||
@@ -470,7 +472,7 @@ public class CanTalonSRX extends CtreCanNode {
|
||||
swigNext = this.swigValue+1;
|
||||
}
|
||||
|
||||
private static param_t[] swigValues = { eProfileParamSlot0_P, eProfileParamSlot0_I, eProfileParamSlot0_D, eProfileParamSlot0_F, eProfileParamSlot0_IZone, eProfileParamSlot0_CloseLoopRampRate, eProfileParamSlot1_P, eProfileParamSlot1_I, eProfileParamSlot1_D, eProfileParamSlot1_F, eProfileParamSlot1_IZone, eProfileParamSlot1_CloseLoopRampRate, eProfileParamSoftLimitForThreshold, eProfileParamSoftLimitRevThreshold, eProfileParamSoftLimitForEnable, eProfileParamSoftLimitRevEnable, eOnBoot_BrakeMode, eOnBoot_LimitSwitch_Forward_NormallyClosed, eOnBoot_LimitSwitch_Reverse_NormallyClosed, eOnBoot_LimitSwitch_Forward_Disable, eOnBoot_LimitSwitch_Reverse_Disable, eFault_OverTemp, eFault_UnderVoltage, eFault_ForLim, eFault_RevLim, eFault_HardwareFailure, eFault_ForSoftLim, eFault_RevSoftLim, eStckyFault_OverTemp, eStckyFault_UnderVoltage, eStckyFault_ForLim, eStckyFault_RevLim, eStckyFault_ForSoftLim, eStckyFault_RevSoftLim, eAppliedThrottle, eCloseLoopErr, eFeedbackDeviceSelect, eRevMotDuringCloseLoopEn, eModeSelect, eProfileSlotSelect, eRampThrottle, eRevFeedbackSensor, eLimitSwitchEn, eLimitSwitchClosedFor, eLimitSwitchClosedRev, eSensorPosition, eSensorVelocity, eCurrent, eBrakeIsEnabled, eEncPosition, eEncVel, eEncIndexRiseEvents, eQuadApin, eQuadBpin, eQuadIdxpin, eAnalogInWithOv, eAnalogInVel, eTemp, eBatteryV, eResetCount, eResetFlags, eFirmVers, eSettingsChanged };
|
||||
private static param_t[] swigValues = { eProfileParamSlot0_P, eProfileParamSlot0_I, eProfileParamSlot0_D, eProfileParamSlot0_F, eProfileParamSlot0_IZone, eProfileParamSlot0_CloseLoopRampRate, eProfileParamSlot1_P, eProfileParamSlot1_I, eProfileParamSlot1_D, eProfileParamSlot1_F, eProfileParamSlot1_IZone, eProfileParamSlot1_CloseLoopRampRate, eProfileParamSoftLimitForThreshold, eProfileParamSoftLimitRevThreshold, eProfileParamSoftLimitForEnable, eProfileParamSoftLimitRevEnable, eOnBoot_BrakeMode, eOnBoot_LimitSwitch_Forward_NormallyClosed, eOnBoot_LimitSwitch_Reverse_NormallyClosed, eOnBoot_LimitSwitch_Forward_Disable, eOnBoot_LimitSwitch_Reverse_Disable, eFault_OverTemp, eFault_UnderVoltage, eFault_ForLim, eFault_RevLim, eFault_HardwareFailure, eFault_ForSoftLim, eFault_RevSoftLim, eStckyFault_OverTemp, eStckyFault_UnderVoltage, eStckyFault_ForLim, eStckyFault_RevLim, eStckyFault_ForSoftLim, eStckyFault_RevSoftLim, eAppliedThrottle, eCloseLoopErr, eFeedbackDeviceSelect, eRevMotDuringCloseLoopEn, eModeSelect, eProfileSlotSelect, eRampThrottle, eRevFeedbackSensor, eLimitSwitchEn, eLimitSwitchClosedFor, eLimitSwitchClosedRev, eSensorPosition, eSensorVelocity, eCurrent, eBrakeIsEnabled, eEncPosition, eEncVel, eEncIndexRiseEvents, eQuadApin, eQuadBpin, eQuadIdxpin, eAnalogInWithOv, eAnalogInVel, eTemp, eBatteryV, eResetCount, eResetFlags, eFirmVers, eSettingsChanged, eQuadFilterEn, ePidIaccum };
|
||||
private static int swigNext = 0;
|
||||
private final int swigValue;
|
||||
private final String swigName;
|
||||
|
||||
@@ -143,6 +143,8 @@ public class CanTalonJNI {
|
||||
public final static native int CanTalonSRX_eResetFlags_get();
|
||||
public final static native int CanTalonSRX_eFirmVers_get();
|
||||
public final static native int CanTalonSRX_eSettingsChanged_get();
|
||||
public final static native int CanTalonSRX_eQuadFilterEn_get();
|
||||
public final static native int CanTalonSRX_ePidIaccum_get();
|
||||
public final static native long CanTalonSRX_SetParam(long jarg1, CanTalonSRX jarg1_, int jarg2, double jarg3);
|
||||
public final static native long CanTalonSRX_RequestParam(long jarg1, CanTalonSRX jarg1_, int jarg2);
|
||||
public final static native long CanTalonSRX_GetParamResponse(long jarg1, CanTalonSRX jarg1_, int jarg2, long jarg3);
|
||||
|
||||
Reference in New Issue
Block a user