Class BaseTalon
java.lang.Object
com.ctre.phoenix.motorcontrol.can.BaseMotorController
com.ctre.phoenix.motorcontrol.can.BaseTalon
- All Implemented Interfaces:
IFollower
,IMotorController
,IMotorControllerEnhanced
,IInvertable
,IOutputSignal
public class BaseTalon extends BaseMotorController implements IMotorControllerEnhanced
CTRE Talon SRX Motor Controller when used on CAN Bus.
-
Field Summary
-
Constructor Summary
-
Method Summary
Modifier and Type Method Description protected ErrorCode
configAllSettings(BaseTalonConfiguration allConfigs)
Configures all persistent settings (overloaded so timeoutMs is 50 ms).protected ErrorCode
configAllSettings(BaseTalonConfiguration allConfigs, int timeoutMs)
Configures all persistent settings.ErrorCode
configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose)
Configures a limit switch for a local/remote source.ErrorCode
configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
Configures a limit switch for a local/remote source.ErrorCode
configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose)
Configures a limit switch for a local/remote source.ErrorCode
configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
Configures a limit switch for a local/remote source.ErrorCode
configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs)
Configures the supply (input) current limit.protected ErrorCode
configurePID(BaseTalonPIDSetConfiguration pid)
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).protected ErrorCode
configurePID(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs, boolean enableOptimizations)
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).ErrorCode
configVelocityMeasurementPeriod(VelocityMeasPeriod period)
Deprecated.Use the overload with SensorVelocityMeasPeriod instead.ErrorCode
configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs)
Deprecated.Use the overload with SensorVelocityMeasPeriod instead.ErrorCode
configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period)
Configures the period of each velocity sample.ErrorCode
configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs)
Configures the period of each velocity sample.ErrorCode
configVelocityMeasurementWindow(int windowSize)
Sets the number of velocity samples used in the rolling average velocity measurement.ErrorCode
configVelocityMeasurementWindow(int windowSize, int timeoutMs)
Sets the number of velocity samples used in the rolling average velocity measurement.protected void
getAllConfigs(BaseTalonConfiguration allConfigs)
Gets all persistant settings (overloaded so timeoutMs is 50 ms).protected void
getAllConfigs(BaseTalonConfiguration allConfigs, int timeoutMs)
Gets all persistant settings.double
getOutputCurrent()
Deprecated.Use getStatorCurrent/getSupplyCurrent instead.protected void
getPIDConfigs(BaseTalonPIDSetConfiguration pid)
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).protected void
getPIDConfigs(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs)
Gets all PID set persistant settings.double
getStatorCurrent()
Gets the stator/output current of the motor controller.int
getStatusFramePeriod(StatusFrameEnhanced frame)
Gets the period of the given status frame.int
getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs)
Gets the period of the given status frame.double
getSupplyCurrent()
Gets the supply/input current of the motor controller.protected TalonFXSensorCollection
getTalonFXSensorCollection()
protected TalonFXSimCollection
getTalonFXSimCollection()
protected SensorCollection
getTalonSRXSensorCollection()
protected TalonSRXSimCollection
getTalonSRXSimCollection()
int
isFwdLimitSwitchClosed()
Is forward limit switch closed.int
isRevLimitSwitchClosed()
Is reverse limit switch closed.ErrorCode
setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs)
Sets the period of the given status frame.ErrorCode
setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs, int timeoutMs)
Sets the period of the given status frame.Methods inherited from class com.ctre.phoenix.motorcontrol.can.BaseMotorController
baseConfigAllSettings, baseConfigurePID, baseGetAllConfigs, baseGetPIDConfigs, changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, clearStickyFaults, config_IntegralZone, config_IntegralZone, config_kD, config_kD, config_kF, config_kF, config_kI, config_kI, config_kP, config_kP, configAllowableClosedloopError, configAllowableClosedloopError, configAuxPIDPolarity, configAuxPIDPolarity, configClearPositionOnLimitF, configClearPositionOnLimitR, configClearPositionOnQuadIdx, configClosedLoopPeakOutput, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedLoopPeriod, configClosedloopRamp, configClosedloopRamp, configFactoryDefault, configFactoryDefault, configFeedbackNotContinuous, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configForwardSoftLimitThreshold, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configLimitSwitchDisableNeutralOnLOS, configMaxIntegralAccumulator, configMaxIntegralAccumulator, configMotionAcceleration, configMotionAcceleration, configMotionCruiseVelocity, configMotionCruiseVelocity, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryPeriod, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configMotionSCurveStrength, configNeutralDeadband, configNeutralDeadband, configNominalOutputForward, configNominalOutputForward, configNominalOutputReverse, configNominalOutputReverse, configOpenloopRamp, configOpenloopRamp, configPeakOutputForward, configPeakOutputForward, configPeakOutputReverse, configPeakOutputReverse, configPulseWidthPeriod_EdgesPerRot, configPulseWidthPeriod_FilterWindowSz, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteSensorClosedLoopDisableNeutralOnLOS, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSensorTerm, configSensorTerm, configSensorTerm, configSensorTerm, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, configSoftLimitDisableNeutralOnLOS, configureFilter, configureFilter, configureFilter, configureSlot, configureSlot, configVoltageCompSaturation, configVoltageCompSaturation, configVoltageMeasurementFilter, configVoltageMeasurementFilter, DestroyObject, enableVoltageCompensation, follow, follow, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryPosition, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopError, getClosedLoopTarget, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getErrorDerivative, getFaults, getFilterConfigs, getFilterConfigs, getFirmwareVersion, getHandle, getIntegralAccumulator, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getSelectedSensorPosition, getSelectedSensorPosition, getSelectedSensorVelocity, getSelectedSensorVelocity, getSlotConfigs, getSlotConfigs, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStickyFaults, getTemperature, getVictorSPXSimCollection, hasResetOccurred, isMotionProfileFinished, isMotionProfileTopLevelBufferFull, isVoltageCompensationEnabled, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setControlFramePeriod, setIntegralAccumulator, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, startMotionProfile, valueUpdated
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface com.ctre.phoenix.motorcontrol.IMotorController
changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, config_IntegralZone, config_kD, config_kF, config_kI, config_kP, configAllowableClosedloopError, configAuxPIDPolarity, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedloopRamp, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configGetCustomParam, configGetParameter, configGetParameter, configMaxIntegralAccumulator, configMotionAcceleration, configMotionCruiseVelocity, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configNeutralDeadband, configNominalOutputForward, configNominalOutputReverse, configOpenloopRamp, configPeakOutputForward, configPeakOutputReverse, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSensorTerm, configSetCustomParam, configSetParameter, configSetParameter, configVoltageCompSaturation, configVoltageMeasurementFilter, enableVoltageCompensation, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getFaults, getFirmwareVersion, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getSelectedSensorPosition, getSelectedSensorVelocity, getStatusFramePeriod, getStickyFaults, getTemperature, hasResetOccurred, isMotionProfileTopLevelBufferFull, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod
Methods inherited from interface com.ctre.phoenix.motorcontrol.IMotorControllerEnhanced
configSelectedFeedbackSensor
-
Constructor Details
-
Method Details
-
getTalonSRXSensorCollection
-
getTalonFXSensorCollection
-
getTalonSRXSimCollection
-
getTalonFXSimCollection
-
setStatusFramePeriod
Sets the period of the given status frame. User ensure CAN Bus utilization is not high. This setting is not persistent and is lost when device is reset. If this is a concern, calling application can use hasResetOccurred() to determine if the status frame needs to be reconfigured.- Specified by:
setStatusFramePeriod
in interfaceIMotorControllerEnhanced
- Parameters:
frame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setStatusFramePeriod
Sets the period of the given status frame. User ensure CAN Bus utilization is not high. This setting is not persistent and is lost when device is reset. If this is a concern, calling application can use hasResetOccurred() to determine if the status frame needs to be reconfigured.- Parameters:
frame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getStatusFramePeriod
Gets the period of the given status frame.- Specified by:
getStatusFramePeriod
in interfaceIMotorControllerEnhanced
- Overrides:
getStatusFramePeriod
in classBaseMotorController
- Parameters:
frame
- Frame to get the period of.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Period of the given status frame.
-
getStatusFramePeriod
Gets the period of the given status frame.- Overrides:
getStatusFramePeriod
in classBaseMotorController
- Parameters:
frame
- Frame to get the period of.- Returns:
- Period of the given status frame.
-
getOutputCurrent
Deprecated.Use getStatorCurrent/getSupplyCurrent instead.Gets the output current of the motor controller. In the case of TalonSRX class, this routine returns supply current for legacy reasons. In order to get the "true" output current, call GetStatorCurrent(). In the case of TalonFX class, this routine returns the true output stator current.- Specified by:
getOutputCurrent
in interfaceIMotorControllerEnhanced
- Overrides:
getOutputCurrent
in classBaseMotorController
- Returns:
- The output current (in amps).
-
getStatorCurrent
Gets the stator/output current of the motor controller.- Returns:
- The stator/output current (in amps).
-
getSupplyCurrent
Gets the supply/input current of the motor controller.- Returns:
- The supply/input current (in amps).
-
configVelocityMeasurementPeriod
Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.- Specified by:
configVelocityMeasurementPeriod
in interfaceIMotorControllerEnhanced
- Overrides:
configVelocityMeasurementPeriod
in classBaseMotorController
- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriodtimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configVelocityMeasurementPeriod
@Deprecated public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs)Deprecated.Use the overload with SensorVelocityMeasPeriod instead.Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.- Specified by:
configVelocityMeasurementPeriod
in interfaceIMotorControllerEnhanced
- Overrides:
configVelocityMeasurementPeriod
in classBaseMotorController
- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.motorcontrol.VelocityMeasPeriodtimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configVelocityMeasurementPeriod
Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.- Overrides:
configVelocityMeasurementPeriod
in classBaseMotorController
- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriod- Returns:
- Error Code generated by function. 0 indicates no error.
-
configVelocityMeasurementPeriod
Deprecated.Use the overload with SensorVelocityMeasPeriod instead.Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.- Overrides:
configVelocityMeasurementPeriod
in classBaseMotorController
- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.motorcontrol.VelocityMeasPeriod- Returns:
- Error Code generated by function. 0 indicates no error.
-
configVelocityMeasurementWindow
Sets the number of velocity samples used in the rolling average velocity measurement.- Specified by:
configVelocityMeasurementWindow
in interfaceIMotorControllerEnhanced
- Overrides:
configVelocityMeasurementWindow
in classBaseMotorController
- Parameters:
windowSize
- Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configVelocityMeasurementWindow
Sets the number of velocity samples used in the rolling average velocity measurement.- Overrides:
configVelocityMeasurementWindow
in classBaseMotorController
- Parameters:
windowSize
- Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configForwardLimitSwitchSource
public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.- Specified by:
configForwardLimitSwitchSource
in interfaceIMotorControllerEnhanced
- Overrides:
configForwardLimitSwitchSource
in classBaseMotorController
- Parameters:
type
- Limit switch source. User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.normalOpenOrClose
- Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configForwardLimitSwitchSource
public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose)Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.- Overrides:
configForwardLimitSwitchSource
in classBaseMotorController
- Parameters:
type
- Limit switch source. User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.normalOpenOrClose
- Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configReverseLimitSwitchSource
public ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.- Specified by:
configReverseLimitSwitchSource
in interfaceIMotorControllerEnhanced
- Parameters:
type
- Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.normalOpenOrClose
- Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configReverseLimitSwitchSource
public ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose)Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.- Parameters:
type
- Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.normalOpenOrClose
- Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configSupplyCurrentLimit
public ErrorCode configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs)Configures the supply (input) current limit.- Specified by:
configSupplyCurrentLimit
in interfaceIMotorControllerEnhanced
- Parameters:
currLimitCfg
- Current limit configurationtimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
isFwdLimitSwitchClosed
Is forward limit switch closed.- Returns:
- '1' iff forward limit switch input is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
-
isRevLimitSwitchClosed
Is reverse limit switch closed.- Returns:
- '1' iff reverse limit switch is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
-
configurePID
protected ErrorCode configurePID(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs, boolean enableOptimizations)Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settingspidIdx
- 0 for Primary closed-loop. 1 for auxiliary closed-loop.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.enableOptimizations
- Enable the optimization technique- Returns:
- Error Code generated by function. 0 indicates no error.
-
configurePID
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getPIDConfigs
Gets all PID set persistant settings.- Parameters:
pid
- Object with all of the PID set persistant settingspidIdx
- 0 for Primary closed-loop. 1 for auxiliary closed-loop.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
-
getPIDConfigs
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settings
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configAllSettings
Configures all persistent settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
-
getAllConfigs
Gets all persistant settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings
-