Fixed minor issues in CANTalon. Fixes artf3884, 3885, 3887.

Adds isEnabled and getSetpoint functions to CANTalon classes.
Sets m_controlEnabled=false in Java if changeControlMode(Disabled) is
called.

Change-Id: I08fd0972df22ad83c5578dd43dd6b3536f3b365b
This commit is contained in:
James Kuszmaul
2014-12-08 15:22:15 -05:00
parent 19a7243bfc
commit 9f2dcdeab6
3 changed files with 39 additions and 0 deletions

View File

@@ -64,12 +64,15 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
boolean m_controlEnabled;
int m_profile;
double m_setPoint;
public CANTalon(int deviceNumber) {
m_deviceNumber = deviceNumber;
m_impl = new CanTalonSRX(deviceNumber);
m_safetyHelper = new MotorSafetyHelper(this);
m_controlEnabled = true;
m_profile = 0;
m_setPoint = 0;
setProfile(m_profile);
changeControlMode(ControlMode.PercentVbus);
}
@@ -104,6 +107,7 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
*/
public void set(double outputValue) {
if (m_controlEnabled) {
m_setPoint = outputValue;
switch (m_controlMode) {
case PercentVbus:
m_impl.Set(outputValue);
@@ -319,6 +323,8 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
public void changeControlMode(ControlMode controlMode) {
m_controlMode = controlMode;
if (controlMode == ControlMode.Disabled)
m_controlEnabled = false;
// Disable until set() is called.
m_impl.SetModeSelect(ControlMode.Disabled.value);
}
@@ -337,6 +343,10 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
m_controlEnabled = false;
}
public boolean isControlEnabled() {
return m_controlEnabled;
}
/**
* Get the current proportional constant.
*
@@ -604,10 +614,18 @@ public class CANTalon implements MotorSafety, PIDOutput, SpeedController {
setIZone(izone);
setCloseLoopRampRate(ramprate);
}
public void setPID(double p, double i, double d) {
setPID(p, i, d, 0, 0, 0, m_profile);
}
/**
* @return The latest value set using set().
*/
public double getSetpoint() {
return m_setPoint;
}
/**
* Select which closed loop profile to use, and uses whatever PIDF gains and
* the such that are already there.