Package com.thethriftybot.devices
Class ThriftyNova
java.lang.Object
com.thethriftybot.devices.ThriftyNova
- All Implemented Interfaces:
MotorController,AutoCloseable
API for interfacing with the Thrifty Nova motor controller.
URL to docs here:
https://docs.home.thethriftybot.com
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic final classAn internal CAN frame frequency configuration structure.static enumDifferent types of current control.static enumDifferent encoder types.static enumDifferent types of external encoder that can be used.static enumIO mask bits for the motor controller.static enumDifferent types of motors that can be driven by the controller.static final classAn internal PID controller configuration structure.static enumThe various PID configuration slots.static final classConfiguration structure for ThriftyNova motor controller. -
Field Summary
FieldsModifier and TypeFieldDescriptionCAN frequency configuration interface.protected intprotected intprotected final NetworkTableInterfaceprotected booleanList<com.thethriftybot.devices.ThriftyNova.Error> List of configuration errors.final ThriftyNova.PIDConfigPID slot 0 configuration interface.final ThriftyNova.PIDConfigPID slot 1 configuration interface. -
Constructor Summary
ConstructorsConstructorDescriptionThriftyNova(int canID) Instantiate a new ThriftyMotor objectThriftyNova(int canID, ThriftyNova.MotorType motorType) Instantiate a new ThriftyMotor object using a CAN identifier.ThriftyNova(int canID, NetworkTableInterface netTableIO) Instantiate a new ThriftyMotor object with a custom CAN Interface. -
Method Summary
Modifier and TypeMethodDescriptionvoidApplies a configuration object to the motor controller.booleanGets whether hard limits are enabled.booleanGets whether soft limits are enabled.voidClear the error buffer.voidclose()voiddisable()enableHardLimits(boolean enable) Enable / disable hard limits.enableSoftLimits(boolean enable) Enable / disable soft limits.voidFactory resets the motor controller to its default state.voidfollow(int followerID) Drives the motor using the parameters of the configured followed motor controller.doubleget()Returns the last set point specified by the user in any control method.intGets the absolute encoder offset value.booleanGet the absolute wrapping state.Gets the alterante quadrature index state.booleanGet the brake mode status of the motor.doubleReturns the error to the last set point that was input, based on last used control mode (position or velocity), and encoder type (internal or quaderature).Gets the current type being used for limiting.List<com.thethriftybot.devices.ThriftyNova.Error> Returns a list of the errors that have populated in the buffer.Gets the forward limit switch state.doubleGets the forward soft limit.intgetID()Returns the CAN ID the device was initialized with.booleanGet the inversion status of the motor.booleanGets the inversion of the motor.boolean[]Gets the IO state of the motor controller.doubleGets the maximum current limit.doubleGet the maximum forward percent output.doubleGet the maximum reverse percent output.Gets the motor type being used for the motor controller.doubleGets the encoder position measurement.doubleGets the absolute encoder position.doubleGets the internal encoder position.doubleGets the quadrature encoder position.getQuadA()Gets the Quadrature encoder A state.getQuadB()Gets the Quadrature encoder B state.Gets the Quadrature encoder index state.doubleGets the ramp down time in seconds.doubleGets the ramp up time in seconds.Gets the reverse limit switch state.doubleGets the reverse soft limit.doubleReturns the last set point specified by the user in any control method.doubleGets the stator current measurement.doubleGets the supply current measurement.doubleGets the temperature of the motor controller.booleanGets the temperature throttle enable state.doubleGets the encoder velocity measurement.doubleGets the internal encoder velocity.doubleGets the quadrature encoder velocity.doubleGets the voltage measurement.doubleGet the voltage compensation value.booleanhasError(com.thethriftybot.devices.ThriftyNova.Error err) Checks if there is a specific error present in the buffer.booleanprotected doubleprotected intprotected intreceiveStatusFrame(int index, int startByte, int endByte) protected intreceiveStatusFrameByBit(int index, int startBit, int endBit) voidset(double percentOutput) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.voidset(double percentOutput, double feedForward) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.setAbsInverted(boolean inverted) Invert the absolute encoder direction.setAbsOffset(int offset) Sets the absolute encoder offset.setAbsoluteWrapping(boolean enabled) Set the absolute wrapping state.setBrakeMode(boolean brakeMode) Set the brake mode status of the motor.voidsetEncoderPosition(double position) Sets the encoder position.Set the external encoder type.setExtSlEnabled(boolean enable) Enable or disable external encoder soft limits.setExtSlForward(double position) Set the external encoder forward soft limit position.setExtSlReverse(double position) Set the external encoder reverse soft limit position.setExtSlSource(int source) Set the external encoder soft limits source.setInversion(boolean inverted) Set the inversion status of the motor.voidsetInverted(boolean inverted) Set the inversion status of the motor.setLaserCANID(int id) Sets the CAN ID of the LaserCAN sensor.setLaserDistance(int distance) Sets the stopping distance for the LaserCAN sensor.setLaserEnable(boolean enable) Enables or disables the LaserCAN stop feature.setMaxCurrent(ThriftyNova.CurrentType currentType, double maxCurrent) Set the max current the motor can draw in amps.setMaxOutput(double maxOutput) Set the maximum percent output.setMaxOutput(double maxFwd, double maxRev) Set the maximum forward and reverse percent output.setMotorType(ThriftyNova.MotorType motorType) Sets the motor type to use for the motor controller.voidsetNTLogging(boolean enabled) Enable or disable NetworkTable logging.voidsetPercent(double percentOutput) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.voidsetPercent(double percentOutput, double feedForward) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.voidsetPosition(double targetPosition) Drives the motor towards the given position using the configured PID controller.voidsetPosition(double targetPosition, double feedForward) Drives the motor towards the given position using the configured PID controller.voidsetPositionAbs(double targetPosition) Sets the target position using the absolute encoder.voidsetPositionAbs(double targetPosition, double feedForward) Sets the target position using the absolute encoder.voidsetPositionInternal(double targetPosition) Sets the target position using the internal encoder.voidsetPositionInternal(double targetPosition, double feedForward) Sets the target position using the internal encoder with feed forward.voidsetPositionQuad(double targetPosition) Sets the target position using the quadrature encoder.voidsetPositionQuad(double targetPosition, double feedForward) Sets the target position using the quadrature encoder with feed forward.setRampDown(double rampDown) Sets the time to ramp down in seconds from 0 to 10.setRampUp(double rampUp) Sets the time to ramp up in seconds from 0 to 10.setSoftLimits(double revLimit, double fwdLimit) Sets the soft limits that the motor will not cross if soft limits are enabled.setTempThrottleEnable(boolean enabled) Sets the temperature throttle enable state.voidsetVelocity(double targetVelocity) Drives the motor at the given velocity using the configured PID controller.voidsetVelocity(double targetVelocity, double feedForward) Drives the motor at the given velocity using the configured PID controller.voidsetVelocityInternal(double targetVelocity) Sets the target velocity using the internal encoder.voidsetVelocityInternal(double targetVelocity, double feedForward) Sets the target velocity using the internal encoder with feed forward.voidsetVelocityQuad(double targetVelocity) Sets the target velocity using the quadrature encoder.voidsetVelocityQuad(double targetVelocity, double feedForward) Sets the target velocity using the quadrature encoder with feed forward.setVoltageCompensation(double vcomp) Sets the voltage compensation value.voidvoidCalls every status/feedback getter that has a network table entrystatic voidUpdates the network tables for all ThriftyNova motors.useEncoderType(ThriftyNova.EncoderType encoderType) Set the encoder type to use for feedback control.usePIDSlot(ThriftyNova.PIDSlot pidSlot) Set the PID slot to use for feedback control.Zeros the absolute encoder reading at the current position.Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj.motorcontrol.MotorController
setVoltage, setVoltage
-
Field Details
-
errors
List of configuration errors. -
pid0
PID slot 0 configuration interface. -
pid1
PID slot 1 configuration interface. -
canFreq
CAN frequency configuration interface. -
canID
protected int canID -
deviceHandle
protected int deviceHandle -
deviceTable
-
doNTLogging
protected boolean doNTLogging
-
-
Constructor Details
-
ThriftyNova
public ThriftyNova(int canID) Instantiate a new ThriftyMotor object- Parameters:
canID- The CAN identifier for the particular device.
-
ThriftyNova
Instantiate a new ThriftyMotor object using a CAN identifier.- Parameters:
canID- The CAN identifier for the particular device.motorType- The type of motor being controlled.
-
ThriftyNova
Instantiate a new ThriftyMotor object with a custom CAN Interface.- Parameters:
canID- The CAN identifier for the particular device.netTableIO- The NetworkTable interface to use.
-
-
Method Details
-
getErrors
Returns a list of the errors that have populated in the buffer.- Returns:
- A list of errors.
-
clearErrors
public void clearErrors()Clear the error buffer. -
hasError
public boolean hasError(com.thethriftybot.devices.ThriftyNova.Error err) Checks if there is a specific error present in the buffer.- Parameters:
err- The error to check for.- Returns:
- If the error exists or not.
-
setInverted
public void setInverted(boolean inverted) Set the inversion status of the motor. Same as setInversion, but does not return a value to satisfy the MotorController interface.- Specified by:
setInvertedin interfaceMotorController- Parameters:
inverted- If the motor be inverted or not.
-
setInversion
Set the inversion status of the motor.- Parameters:
inverted- If the motor be inverted or not.- Returns:
- The ThriftyNova object.
-
getInversion
public boolean getInversion()Get the inversion status of the motor.- Returns:
- The inversion status.
-
getInverted
public boolean getInverted()Gets the inversion of the motor.- Specified by:
getInvertedin interfaceMotorController- Returns:
- The inversion of the motor.
-
setBrakeMode
Set the brake mode status of the motor.- Parameters:
brakeMode- If the motor should be in brake mode or not.- Returns:
- The ThriftyNova object.
-
getBrakeMode
public boolean getBrakeMode()Get the brake mode status of the motor.- Returns:
- The brake mode status.
-
setMaxOutput
Set the maximum percent output.- Parameters:
maxOutput- Max forward [0, 1].- Returns:
- The ThriftyNova object.
-
setMaxOutput
Set the maximum forward and reverse percent output.- Parameters:
maxFwd- Max forward output [0, 1].maxRev- Max reverse output [0, 1].- Returns:
- The ThriftyNova object.
-
getMaxForwardOutput
public double getMaxForwardOutput()Get the maximum forward percent output.- Returns:
- The maximum forward percent output.
-
getMaxReverseOutput
public double getMaxReverseOutput()Get the maximum reverse percent output.- Returns:
- The maximum reverse percent output.
-
setRampUp
Sets the time to ramp up in seconds from 0 to 10. For example, an input of 0.5 will ramp the motor from idle to 100% over the course of 0.5 seconds.- Parameters:
rampUp- The ramp up time.- Returns:
- The ThriftyNova object.
-
setRampDown
Sets the time to ramp down in seconds from 0 to 10. For example, an input of 0.5 will ramp the motor from 100% to idle over the course of 0.5 seconds.- Parameters:
rampDown- The ramp down time.- Returns:
- The ThriftyNova object.
-
getRampUp
public double getRampUp()Gets the ramp up time in seconds.- Returns:
- The ramp up time.
-
getRampDown
public double getRampDown()Gets the ramp down time in seconds.- Returns:
- The ramp down time.
-
setMaxCurrent
Set the max current the motor can draw in amps. Motor speed will be capped to satisfy the max current. Also set the what current reading is used for limiting calculations, between: - Stator: Uses the total draw of phase a, b, and c. - Supply: Uses stator plus the draw of the controller itself.- Parameters:
currentType- The current reading used for limiting calculations.maxCurrent- The max current.- Returns:
- The ThriftyNova object.
-
setSoftLimits
Sets the soft limits that the motor will not cross if soft limits are enabled.- Parameters:
revLimit- The reverse number of rotations the motor will not go past.fwdLimit- The forward number of rotations the motor will not go past.- Returns:
- The ThriftyNova object.
-
enableSoftLimits
Enable / disable soft limits.- Parameters:
enable- If soft limits should be enabled.- Returns:
- The ThriftyNova object.
-
enableHardLimits
Enable / disable hard limits.- Parameters:
enable- If hard limits should be enabled.- Returns:
- The ThriftyNova object.
-
getMaxCurrent
public double getMaxCurrent()Gets the maximum current limit.- Returns:
- The maximum current limit in amps.
-
getCurrentType
Gets the current type being used for limiting.- Returns:
- The current type.
-
getForwardSoftLimit
public double getForwardSoftLimit()Gets the forward soft limit.- Returns:
- The forward soft limit position.
-
getReverseSoftLimit
public double getReverseSoftLimit()Gets the reverse soft limit.- Returns:
- The reverse soft limit position.
-
areSoftLimitsEnabled
public boolean areSoftLimitsEnabled()Gets whether soft limits are enabled.- Returns:
- True if soft limits are enabled.
-
areHardLimitsEnabled
public boolean areHardLimitsEnabled()Gets whether hard limits are enabled.- Returns:
- True if hard limits are enabled.
-
setAbsOffset
Sets the absolute encoder offset.- Parameters:
offset- The number of ticks (1/4096 rotation) to offset by.- Returns:
- The ThriftyNova object.
-
getAbsOffset
public int getAbsOffset()Gets the absolute encoder offset value.- Returns:
- The current offset in ticks (1/4096 rotation).
-
zeroAbsEncoder
Zeros the absolute encoder reading at the current position.- Returns:
- The ThriftyNova object.
-
setTempThrottleEnable
Sets the temperature throttle enable state.- Parameters:
enabled- True to enable temperature throttling, false to disable.- Returns:
- The ThriftyNova object.
-
getTempThrottleEnable
public boolean getTempThrottleEnable()Gets the temperature throttle enable state.- Returns:
- True if temperature throttling is enabled, false otherwise.
-
setMotorType
Sets the motor type to use for the motor controller.- Parameters:
motorType- The type of motor to use.- Returns:
- The ThriftyNova object.
-
getMotorType
Gets the motor type being used for the motor controller.- Returns:
- The motor type.
-
setVoltageCompensation
Sets the voltage compensation value.- Parameters:
vcomp- The voltage compensation value.- Returns:
- The ThriftyNova object.
-
getVoltageCompensationEnabled
public double getVoltageCompensationEnabled()Get the voltage compensation value.- Returns:
- The voltage compensation value.
-
useEncoderType
Set the encoder type to use for feedback control.- Parameters:
encoderType- The encoder type to use.- Returns:
- The ThriftyNova object.
-
setExternalEncoder
Set the external encoder type.- Parameters:
external- The external encoder type.- Returns:
- The ThriftyNova object.
-
setAbsoluteWrapping
Set the absolute wrapping state.- Parameters:
enabled- True to enable absolute wrapping, false to disable.- Returns:
- The ThriftyNova object.
-
getAbsoluteWrapping
public boolean getAbsoluteWrapping()Get the absolute wrapping state.- Returns:
- True if absolute wrapping is enabled, false otherwise.
-
usePIDSlot
Set the PID slot to use for feedback control.- Parameters:
pidSlot- The PID slot to use.- Returns:
- The ThriftyNova object.
-
setNTLogging
public void setNTLogging(boolean enabled) Enable or disable NetworkTable logging.- Parameters:
enabled- True to enable logging, false to disable.
-
setPercent
public void setPercent(double percentOutput) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.- Parameters:
percentOutput- The percent output of the motor from [-1, 1].
-
setPercent
public void setPercent(double percentOutput, double feedForward) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.- Parameters:
percentOutput- The percent output of the motor from [-1, 1].feedForward- The feed forward value.
-
set
public void set(double percentOutput) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.- Specified by:
setin interfaceMotorController- Parameters:
percentOutput- The percent output of the motor from [-1, 1].
-
set
public void set(double percentOutput, double feedForward) Sets the percent output of the motor from between 1.0 (full forward) and -1.0 (full reverse), where 0.0 is full stop.- Parameters:
percentOutput- The percent output of the motor from [-1, 1].feedForward- The feed forward value to use (0-12v).
-
disable
public void disable()- Specified by:
disablein interfaceMotorController
-
stopMotor
public void stopMotor()- Specified by:
stopMotorin interfaceMotorController
-
setPosition
public void setPosition(double targetPosition, double feedForward) Drives the motor towards the given position using the configured PID controller.- Parameters:
targetPosition- The position to target in rotations.feedForward- The feed forward value to use (0-12v).`
-
setPosition
public void setPosition(double targetPosition) Drives the motor towards the given position using the configured PID controller.- Parameters:
targetPosition- The position to target in rotations.
-
setPositionInternal
public void setPositionInternal(double targetPosition, double feedForward) Sets the target position using the internal encoder with feed forward.- Parameters:
targetPosition- The target position to set in rotations.feedForward- The feed forward value to set (0-12v).
-
setPositionInternal
public void setPositionInternal(double targetPosition) Sets the target position using the internal encoder.- Parameters:
targetPosition- The target position to set in rotations.
-
setPositionQuad
public void setPositionQuad(double targetPosition, double feedForward) Sets the target position using the quadrature encoder with feed forward.- Parameters:
targetPosition- The target position to set in rotations.feedForward- The feed forward value to set (0-12v).
-
setPositionQuad
public void setPositionQuad(double targetPosition) Sets the target position using the quadrature encoder.- Parameters:
targetPosition- The target position to set in rotations.
-
setPositionAbs
public void setPositionAbs(double targetPosition, double feedForward) Sets the target position using the absolute encoder.- Parameters:
targetPosition- The target position to set in rotations.feedForward- The feed forward value to set (0-12v).
-
setPositionAbs
public void setPositionAbs(double targetPosition) Sets the target position using the absolute encoder.- Parameters:
targetPosition- The target position to set.
-
setVelocity
public void setVelocity(double targetVelocity, double feedForward) Drives the motor at the given velocity using the configured PID controller.- Parameters:
targetVelocity- The velocity to target in revs/sec.feedForward- The feed forward value to use (0-12v).
-
setVelocity
public void setVelocity(double targetVelocity) Drives the motor at the given velocity using the configured PID controller.- Parameters:
targetVelocity- The velocity to target.
-
setVelocityInternal
public void setVelocityInternal(double targetVelocity, double feedForward) Sets the target velocity using the internal encoder with feed forward.- Parameters:
targetVelocity- The target velocity to set.feedForward- The feed forward value to set (0-12v).
-
setVelocityInternal
public void setVelocityInternal(double targetVelocity) Sets the target velocity using the internal encoder.- Parameters:
targetVelocity- The target velocity to set.
-
setVelocityQuad
public void setVelocityQuad(double targetVelocity, double feedForward) Sets the target velocity using the quadrature encoder with feed forward.- Parameters:
targetVelocity- The target velocity to set.feedForward- The feed forward value to set (0-12v).
-
setVelocityQuad
public void setVelocityQuad(double targetVelocity) Sets the target velocity using the quadrature encoder.- Parameters:
targetVelocity- The target velocity to set.
-
follow
public void follow(int followerID) Drives the motor using the parameters of the configured followed motor controller. Follower mode is dependant on the fault status frame. The slower that frame is sent, the slower the follower motor will update.- Parameters:
followerID- The target ID to follow.
-
updateStatusNT
public void updateStatusNT()Calls every status/feedback getter that has a network table entry -
getPosition
public double getPosition()Gets the encoder position measurement.- Returns:
- The position measurement in rotations.
-
getPositionInternal
public double getPositionInternal()Gets the internal encoder position.- Returns:
- The internal encoder position in rotations.
-
getPositionQuad
public double getPositionQuad()Gets the quadrature encoder position.- Returns:
- The quadrature encoder position in rotations.
-
getPositionAbs
public double getPositionAbs()Gets the absolute encoder position.- Returns:
- The absolute encoder position in rotations.
-
getVelocity
public double getVelocity()Gets the encoder velocity measurement.- Returns:
- The velocity measurement (rev/sec).
-
getVelocityInternal
public double getVelocityInternal()Gets the internal encoder velocity.- Returns:
- The internal encoder velocity (rev/sec).
-
getVelocityQuad
public double getVelocityQuad()Gets the quadrature encoder velocity.- Returns:
- The quadrature encoder velocity (rev/sec).
-
getVoltage
public double getVoltage()Gets the voltage measurement.- Returns:
- The voltage measurement in volts.
-
getIOState
public boolean[] getIOState()Gets the IO state of the motor controller.Each element in the array corresponds to a specific I/O signal:
- Index 0: FWD_LIMIT -
trueif the forward limit sensor is active. - Index 1: QUAD_INDEX -
trueif the quad index sensor is active. - Index 2: REV_LIMIT -
trueif the reverse limit sensor is active. - Index 3: ALT_QUAD_INDEX -
trueif the alternate quad index sensor is active. - Index 4: QUAD_A -
trueif the QUAD_A signal is high. - Index 5: QUAD_B -
trueif the QUAD_B signal is high.
- Returns:
- The array containing the IO state.
- Index 0: FWD_LIMIT -
-
getReverseLimit
Gets the reverse limit switch state.- Returns:
- The reverse limit switch state.
-
getForwardLimit
Gets the forward limit switch state.- Returns:
- The forward limit switch state.
-
getQuadIndex
Gets the Quadrature encoder index state.- Returns:
- The Quadrature encoder index state.
-
getQuadA
Gets the Quadrature encoder A state.- Returns:
- The Quadrature encoder A state.
-
getQuadB
Gets the Quadrature encoder B state.- Returns:
- The Quadrature encoder B state.
-
getAltQuadIndex
Gets the alterante quadrature index state.- Returns:
- The alternate quadrature index state.
-
getStatorCurrent
public double getStatorCurrent()Gets the stator current measurement.- Returns:
- The stator current measurement.
-
getSupplyCurrent
public double getSupplyCurrent()Gets the supply current measurement.- Returns:
- The supply current measurement.
-
getTemperature
public double getTemperature()Gets the temperature of the motor controller.- Returns:
- The temperature of the motor controller.
-
getSetPoint
public double getSetPoint()Returns the last set point specified by the user in any control method. Percent output set point becomes zero.- Returns:
- The current set point.
-
get
public double get()Returns the last set point specified by the user in any control method. Percent output set point becomes zero.- Specified by:
getin interfaceMotorController- Returns:
- The current set point.
-
getClosedLoopError
public double getClosedLoopError()Returns the error to the last set point that was input, based on last used control mode (position or velocity), and encoder type (internal or quaderature).- Returns:
- The closed loop error.
-
setEncoderPosition
public void setEncoderPosition(double position) Sets the encoder position.- Parameters:
position- The position to set the encoder to.
-
setExtSlEnabled
Enable or disable external encoder soft limits.- Parameters:
enable- True to enable, false to disable.- Returns:
- The ThriftyNova object.
-
setExtSlSource
Set the external encoder soft limits source.- Parameters:
source- 0 for quadrature, 1 for absolute.- Returns:
- The ThriftyNova object.
-
setExtSlForward
Set the external encoder forward soft limit position.- Parameters:
position- The position in rotations.- Returns:
- The ThriftyNova object.
-
setExtSlReverse
Set the external encoder reverse soft limit position.- Parameters:
position- The position in rotations.- Returns:
- The ThriftyNova object.
-
setAbsInverted
Invert the absolute encoder direction.- Parameters:
inverted- true to invert, false for normal.- Returns:
- The ThriftyNova object.
-
setLaserEnable
Enables or disables the LaserCAN stop feature.- Parameters:
enable- True to enable, false to disable.- Returns:
- The ThriftyNova object.
-
setLaserCANID
Sets the CAN ID of the LaserCAN sensor.- Parameters:
id- The CAN ID of the LaserCAN sensor.- Returns:
- The ThriftyNova object.
-
setLaserDistance
Sets the stopping distance for the LaserCAN sensor.- Parameters:
distance- The distance in millimeters.- Returns:
- The ThriftyNova object.
-
factoryReset
public void factoryReset()Factory resets the motor controller to its default state. -
applyConfig
Applies a configuration object to the motor controller. Only non-null fields in the configuration object will be applied.- Parameters:
config- The configuration object to apply.
-
close
- Specified by:
closein interfaceAutoCloseable- Throws:
Exception
-
updateStatusNTGlobal
public static void updateStatusNTGlobal()Updates the network tables for all ThriftyNova motors. -
getID
public int getID()Returns the CAN ID the device was initialized with.- Returns:
- The device's CAN ID
-
receiveStatusFrame
protected int receiveStatusFrame(int index, int startByte, int endByte) -
receiveStatusFrameByBit
protected int receiveStatusFrameByBit(int index, int startBit, int endBit) -
logNT
-
logNT
-
logNT
-
logNT
-