Class TalonFX
java.lang.Object
com.ctre.phoenix.motorcontrol.can.BaseMotorController
com.ctre.phoenix.motorcontrol.can.BaseTalon
com.ctre.phoenix.motorcontrol.can.TalonFX
- All Implemented Interfaces:
IFollower
,IMotorController
,IMotorControllerEnhanced
,IInvertable
,IOutputSignal
- Direct Known Subclasses:
WPI_TalonFX
CTRE Talon FX Motor Controller when used on CAN Bus.
// Example usage of a TalonFX motor controller
TalonFX motor = new TalonFX(0); // creates a new TalonFX with ID 0
TalonFXConfiguration config = new TalonFXConfiguration();
config.supplyCurrLimit.enable = true;
config.supplyCurrLimit.triggerThresholdCurrent = 40; // the peak supply current, in amps
config.supplyCurrLimit.triggerThresholdTime = 1.5; // the time at the peak supply current before the limit triggers, in sec
config.supplyCurrLimit.currentLimit = 30; // the current to maintain if the peak supply limit is triggered
motor.configAllSettings(config); // apply the config settings; this selects the quadrature encoder
motor.set(TalonFXControlMode.PercentOutput, 0.5); // runs the motor at 50% power
System.out.println(motor.getSelectedSensorPosition()); // prints the position of the selected sensor
System.out.println(motor.getSelectedSensorVelocity()); // prints the velocity recorded by the selected sensor
System.out.println(motor.getMotorOutputPercent()); // prints the percent output of the motor (0.5)
System.out.println(motor.getStatorCurrent()); // prints the output current of the motor
ErrorCode error = motor.getLastError(); // gets the last error generated by the motor controller
Faults faults = new Faults();
ErrorCode faultsError = motor.getFaults(faults); // fills faults with the current motor controller faults; returns the last error generated
motor.setStatusFramePeriod(StatusFrame.Status_2_Feedback0, 10); // changes the period of the Status 2 frame (getSelectedSensor*()) to 10ms
-
Field Summary
Fields inherited from class com.ctre.phoenix.motorcontrol.can.BaseMotorController
m_handle
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionconfigAllSettings
(TalonFXConfiguration allConfigs) Configures all persistent settings.configAllSettings
(TalonFXConfiguration allConfigs, int timeoutMs) Configures all persistent settings.configGetMotorCommutation
(int timeoutMs) configGetStatorCurrentLimit
(StatorCurrentLimitConfiguration currLimitConfigsToFill) Gets the stator (output) current limit configuration.configGetStatorCurrentLimit
(StatorCurrentLimitConfiguration currLimitConfigsToFill, int timeoutMs) Gets the stator (output) current limit configuration.configGetSupplyCurrentLimit
(SupplyCurrentLimitConfiguration currLimitConfigsToFill) Gets the supply (input) current limit configuration.configGetSupplyCurrentLimit
(SupplyCurrentLimitConfiguration currLimitConfigsToFill, int timeoutMs) Gets the supply (input) current limit configuration.configIntegratedSensorAbsoluteRange
(AbsoluteSensorRange absoluteSensorRange) Sets the signage and range of the "Absolute Position" signal.configIntegratedSensorAbsoluteRange
(AbsoluteSensorRange absoluteSensorRange, int timeoutMs) Sets the signage and range of the "Absolute Position" signal.configIntegratedSensorInitializationStrategy
(SensorInitializationStrategy initializationStrategy) Pick the strategy on how to initialize the integrated sensor register.configIntegratedSensorInitializationStrategy
(SensorInitializationStrategy initializationStrategy, int timeoutMs) Pick the strategy on how to initialize the integrated sensor register.configIntegratedSensorOffset
(double offsetDegrees) Adjusts the zero point for the integrated sensor absolute position register.configIntegratedSensorOffset
(double offsetDegrees, int timeoutMs) Adjusts the zero point for the integrated sensor absolute position register.configMotorCommutation
(MotorCommutation motorCommutation) Configure the motor commutation type.configMotorCommutation
(MotorCommutation motorCommutation, int timeoutMs) Configure the motor commutation type.configSelectedFeedbackSensor
(TalonFXFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) Select the feedback device for the motor controller.configStatorCurrentLimit
(StatorCurrentLimitConfiguration currLimitCfg) Configures the stator (output) current limit.configStatorCurrentLimit
(StatorCurrentLimitConfiguration currLimitCfg, int timeoutMs) Configures the stator (output) current limit.configSupplyCurrentLimit
(SupplyCurrentLimitConfiguration currLimitCfg) Configures the supply (input) current limit.configSupplyCurrentLimit
(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs) Configures the supply (input) current limit.protected ErrorCode
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).protected ErrorCode
configurePID
(TalonFXPIDSetConfiguration pid, int pidIdx, int timeoutMs) Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).getAllConfigs
(TalonFXConfiguration allConfigs) Gets all persistant settings (overloaded so timeoutMs is 50 ms).getAllConfigs
(TalonFXConfiguration allConfigs, int timeoutMs) Gets all persistant settings.void
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).void
getPIDConfigs
(TalonFXPIDSetConfiguration pid, int pidIdx, int timeoutMs) Gets all PID set persistant settings.void
set
(TalonFXControlMode mode, double value) Sets the appropriate output on the talon, depending on the mode.void
set
(TalonFXControlMode mode, double demand0, DemandType demand1Type, double demand1) void
setInverted
(TalonFXInvertType invertType) Inverts the hbridge output of the motor controller in relation to the master if present This does not impact sensor phase and should not be used to correct sensor polarity.Methods inherited from class com.ctre.phoenix.motorcontrol.can.BaseTalon
configAllSettings, configAllSettings, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configurePID, configurePID, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementWindow, configVelocityMeasurementWindow, getAllConfigs, getAllConfigs, getOutputCurrent, getPIDConfigs, getPIDConfigs, getStatorCurrent, getStatusFramePeriod, getStatusFramePeriod, getSupplyCurrent, getTalonFXSensorCollection, getTalonFXSimCollection, getTalonSRXSensorCollection, getTalonSRXSimCollection, isFwdLimitSwitchClosed, isRevLimitSwitchClosed, setStatusFramePeriod, setStatusFramePeriod
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.IFollower
follow, valueUpdated
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
-
TalonFX
Constructor- Parameters:
deviceNumber
- [0,62]canbus
- Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
-
TalonFX
Constructor- Parameters:
deviceNumber
- [0,62]
-
-
Method Details
-
set
Sets the appropriate output on the talon, depending on the mode.- Parameters:
mode
- The output mode to apply. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. In Follower mode, the output value is the integer device ID of the talon to duplicate.value
- The setpoint value, as described above. Standard Driving Example: _talonLeft.set(ControlMode.PercentOutput, leftJoy); _talonRght.set(ControlMode.PercentOutput, rghtJoy);
-
set
- Parameters:
mode
- Sets the appropriate output on the talon, depending on the mode.demand0
- The output value to apply. such as advanced feed forward and/or auxiliary close-looping in firmware. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. See In Follower mode, the output value is the integer device ID of the talon to duplicate.demand1Type
- The demand type for demand1. Neutral: Ignore demand1 and apply no change to the demand0 output. AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary PID is always executed as standard Position PID control. ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the demand0 output. In PercentOutput the demand0 output is the motor output, and in closed-loop modes the demand0 output is the output of PID0.demand1
- Supplmental output value. AuxPID: Target position in Sensor Units ArbitraryFeedForward: Percent Output between -1.0 and 1.0 Arcade Drive Example: _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn); Drive Straight Example: Note: Selected Sensor Configuration is necessary for both PID0 and PID1. _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading); Drive Straight to a Distance Example: Note: Other configurations (sensor selection, PID gains, etc.) need to be set. _talonLeft.follow(_talonRght, FollwerType.AuxOutput1); _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
-
setInverted
Inverts the hbridge output of the motor controller in relation to the master if present This does not impact sensor phase and should not be used to correct sensor polarity. This will allow you to either: - Spin counterclockwise (default) - Spin Clockwise (invert direction) - Always follow the master regardless of master's inversion - Always oppose the master regardless of master's inversion- Parameters:
invertType
- Invert state to set.
-
configSelectedFeedbackSensor
public ErrorCode configSelectedFeedbackSensor(TalonFXFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs) Select the feedback device for the motor controller.- Parameters:
feedbackDevice
- Talon FX feedback Device to select.pidIdx
- 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.- 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
- Overrides:
configSupplyCurrentLimit
in classBaseTalon
- 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.
-
configSupplyCurrentLimit
Configures the supply (input) current limit.- Parameters:
currLimitCfg
- Current limit configuration- Returns:
- Error Code generated by function. 0 indicates no error.
-
configStatorCurrentLimit
public ErrorCode configStatorCurrentLimit(StatorCurrentLimitConfiguration currLimitCfg, int timeoutMs) Configures the stator (output) current limit.- 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.
-
configStatorCurrentLimit
Configures the stator (output) current limit.- Parameters:
currLimitCfg
- Current limit configuration- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetSupplyCurrentLimit
public ErrorCode configGetSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitConfigsToFill, int timeoutMs) Gets the supply (input) current limit configuration.- Parameters:
currLimitConfigsToFill
- Configuration object to fill with read values.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetSupplyCurrentLimit
public ErrorCode configGetSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitConfigsToFill) Gets the supply (input) current limit configuration.- Parameters:
currLimitConfigsToFill
- Configuration object to fill with read values..- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetStatorCurrentLimit
public ErrorCode configGetStatorCurrentLimit(StatorCurrentLimitConfiguration currLimitConfigsToFill, int timeoutMs) Gets the stator (output) current limit configuration.- Parameters:
currLimitConfigsToFill
- Configuration object to fill with read values.timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetStatorCurrentLimit
public ErrorCode configGetStatorCurrentLimit(StatorCurrentLimitConfiguration currLimitConfigsToFill) Gets the stator (output) current limit configuration.- Parameters:
currLimitConfigsToFill
- Configuration object to fill with read values.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configMotorCommutation
Configure the motor commutation type.- Parameters:
motorCommutation
- Motor Commutation Type.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.
-
configMotorCommutation
Configure the motor commutation type.- Parameters:
motorCommutation
- Motor Commutation Type.
-
configGetMotorCommutation
- Parameters:
timeoutMs
- Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.- Returns:
- The motor commutation type.
-
configGetMotorCommutation
- Returns:
- The motor commutation type.
-
configIntegratedSensorAbsoluteRange
public ErrorCode configIntegratedSensorAbsoluteRange(AbsoluteSensorRange absoluteSensorRange, int timeoutMs) Sets the signage and range of the "Absolute Position" signal. Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...- Parameters:
absoluteSensorRange
- Desired Sign/Range for the absolute position register.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.
-
configIntegratedSensorAbsoluteRange
Sets the signage and range of the "Absolute Position" signal. Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc... Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...- Parameters:
absoluteSensorRange
- Desired Sign/Range for the absolute position register.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configIntegratedSensorOffset
Adjusts the zero point for the integrated sensor absolute position register. The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) and a hard-limited mechanism may have such a discontinuity in its functional range. In which case use this config to move the discontinuity outside of the function range.- Parameters:
offsetDegrees
- Offset in degreestimeoutMs
- 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.
-
configIntegratedSensorOffset
Adjusts the zero point for the integrated sensor absolute position register. The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) and a hard-limited mechanism may have such a discontinuity in its functional range. In which case use this config to move the discontinuity outside of the function range.- Parameters:
offsetDegrees
- Offset in degrees- Returns:
- Error Code generated by function. 0 indicates no error.
-
configIntegratedSensorInitializationStrategy
public ErrorCode configIntegratedSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy, int timeoutMs) Pick the strategy on how to initialize the integrated sensor register. Depending on the mechanism, it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the product is reset.- Parameters:
initializationStrategy
- The sensor initialization strategy to use. This will impact the behavior the next time product boots up.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.
-
configIntegratedSensorInitializationStrategy
public ErrorCode configIntegratedSensorInitializationStrategy(SensorInitializationStrategy initializationStrategy) Pick the strategy on how to initialize the integrated sensor register. Depending on the mechanism, it may be desirable to auto set the Position register to match the Absolute Position (swerve for example). Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo). TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the product is reset.- Parameters:
initializationStrategy
- The sensor initialization strategy to use. This will impact the behavior the next time product boots up.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getSensorCollection
- Returns:
- object that can get/set individual raw sensor values.
-
getSimCollection
- Returns:
- object that can get/set simulation inputs.
-
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 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.- 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.- 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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant 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.
-