Package edu.wpi.first.wpilibj
Class AnalogEncoder
java.lang.Object
edu.wpi.first.wpilibj.AnalogEncoder
- All Implemented Interfaces:
Sendable
,AutoCloseable
Class for supporting continuous analog encoders, such as the US Digital MA3.
-
Constructor Summary
ConstructorDescriptionAnalogEncoder
(int channel) Construct a new AnalogEncoder attached to a specific AnalogIn channel.AnalogEncoder
(int channel, double fullRange, double expectedZero) Construct a new AnalogEncoder attached to a specific AnalogIn channel.AnalogEncoder
(AnalogInput analogInput) Construct a new AnalogEncoder attached to a specific AnalogInput.AnalogEncoder
(AnalogInput analogInput, double fullRange, double expectedZero) Construct a new AnalogEncoder attached to a specific AnalogInput. -
Method Summary
Modifier and TypeMethodDescriptionvoid
close()
double
get()
Get the encoder value.int
Get the channel number.void
initSendable
(SendableBuilder builder) Initializes thisSendable
object.void
setInverted
(boolean inverted) Set if this encoder is inverted.void
setVoltagePercentageRange
(double min, double max) Set the encoder voltage percentage range.
-
Constructor Details
-
AnalogEncoder
Construct a new AnalogEncoder attached to a specific AnalogIn channel.- Parameters:
channel
- the analog input channel to attach tofullRange
- the value to report at maximum travelexpectedZero
- the reading where you would expect a 0 from get()
-
AnalogEncoder
Construct a new AnalogEncoder attached to a specific AnalogInput.- Parameters:
analogInput
- the analog input to attach tofullRange
- the value to report at maximum travelexpectedZero
- the reading where you would expect a 0 from get()
-
AnalogEncoder
Construct a new AnalogEncoder attached to a specific AnalogIn channel.This has a fullRange of 1 and an expectedZero of 0.
- Parameters:
channel
- the analog input channel to attach to
-
AnalogEncoder
Construct a new AnalogEncoder attached to a specific AnalogInput.This has a fullRange of 1 and an expectedZero of 0.
- Parameters:
analogInput
- the analog input to attach to
-
-
Method Details
-
get
Get the encoder value.- Returns:
- the encoder value scaled by the full range input
-
setVoltagePercentageRange
Set the encoder voltage percentage range. Analog sensors are not always fully stable at the end of their travel ranges. Shrinking this range down can help mitigate issues with that.- Parameters:
min
- minimum voltage percentage (0-1 range)max
- maximum voltage percentage (0-1 range)
-
setInverted
Set if this encoder is inverted.- Parameters:
inverted
- true to invert the encoder, false otherwise
-
getChannel
Get the channel number.- Returns:
- The channel number.
-
close
- Specified by:
close
in interfaceAutoCloseable
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-