public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveWindowSendable
| Modifier and Type | Class and Description |
|---|---|
static class |
Encoder.IndexingType |
CounterBase.EncodingType| Modifier and Type | Field and Description |
|---|---|
protected DigitalSource |
m_aSource
The a source
|
protected DigitalSource |
m_bSource
The b source
|
protected DigitalSource |
m_indexSource
The index source
|
kAnalogInputChannels, kAnalogOutputChannels, kDigitalChannels, kPDPChannels, kPDPModules, kPwmChannels, kRelayChannels, kSolenoidChannels, kSolenoidModules, kSystemClockTicksPerMicrosecond| Constructor and Description |
|---|
Encoder(DigitalSource aSource,
DigitalSource bSource)
Encoder constructor.
|
Encoder(DigitalSource aSource,
DigitalSource bSource,
boolean reverseDirection)
Encoder constructor.
|
Encoder(DigitalSource aSource,
DigitalSource bSource,
boolean reverseDirection,
CounterBase.EncodingType encodingType)
Encoder constructor.
|
Encoder(DigitalSource aSource,
DigitalSource bSource,
DigitalSource indexSource)
Encoder constructor.
|
Encoder(DigitalSource aSource,
DigitalSource bSource,
DigitalSource indexSource,
boolean reverseDirection)
Encoder constructor.
|
Encoder(int aChannel,
int bChannel)
Encoder constructor.
|
Encoder(int aChannel,
int bChannel,
boolean reverseDirection)
Encoder constructor.
|
Encoder(int aChannel,
int bChannel,
boolean reverseDirection,
CounterBase.EncodingType encodingType)
Encoder constructor.
|
Encoder(int aChannel,
int bChannel,
int indexChannel)
Encoder constructor.
|
Encoder(int aChannel,
int bChannel,
int indexChannel,
boolean reverseDirection)
Encoder constructor.
|
| Modifier and Type | Method and Description |
|---|---|
void |
free()
Free the resources used by this object
|
int |
get()
Gets the current count.
|
boolean |
getDirection()
The last direction the encoder value changed.
|
double |
getDistance()
Get the distance the robot has driven since the last reset.
|
int |
getEncodingScale() |
int |
getFPGAIndex() |
double |
getPeriod()
Deprecated.
Use getRate() in favor of this method. This returns unscaled
periods and getRate() scales using value from
setDistancePerPulse().
|
PIDSourceType |
getPIDSourceType()
Get which parameter of the device you are using as a process control
variable.
|
double |
getRate()
Get the current rate of the encoder.
|
int |
getRaw()
Gets the raw value from the encoder.
|
int |
getSamplesToAverage()
Get the Samples to Average which specifies the number of samples of the
timer to average when calculating the period.
|
java.lang.String |
getSmartDashboardType() |
boolean |
getStopped()
Determine if the encoder is stopped.
|
ITable |
getTable() |
void |
initTable(ITable subtable)
Initializes a table for this sendable object.
|
double |
pidGet()
Implement the PIDSource interface.
|
void |
reset()
Reset the Encoder distance to zero.
|
void |
setDistancePerPulse(double distancePerPulse)
Set the distance per pulse for this encoder.
|
void |
setIndexSource(DigitalSource source)
Set the index source for the encoder.
|
void |
setIndexSource(DigitalSource source,
Encoder.IndexingType type)
Set the index source for the encoder.
|
void |
setIndexSource(int channel)
Set the index source for the encoder.
|
void |
setIndexSource(int channel,
Encoder.IndexingType type)
Set the index source for the encoder.
|
void |
setMaxPeriod(double maxPeriod)
Sets the maximum period for stopped detection.
|
void |
setMinRate(double minRate)
Set the minimum rate of the device before the hardware reports it stopped.
|
void |
setPIDSourceType(PIDSourceType pidSource)
Set which parameter of the encoder you are using as a process control
variable.
|
void |
setReverseDirection(boolean reverseDirection)
Set the direction sensing for this encoder.
|
void |
setSamplesToAverage(int samplesToAverage)
Set the Samples to Average which specifies the number of samples of the
timer to average when calculating the period.
|
void |
startLiveWindowMode()
Start having this sendable object automatically respond to value changes
reflect the value on the table.
|
void |
stopLiveWindowMode()
Stop having this sendable object automatically respond to value changes.
|
void |
updateTable()
Update the table for this sendable object with the latest values.
|
checkAnalogInputChannel, checkAnalogOutputChannel, checkDigitalChannel, checkPDPChannel, checkPDPModule, checkPWMChannel, checkRelayChannel, checkSolenoidChannel, checkSolenoidModule, getDefaultSolenoidModule, setDefaultSolenoidModuleprotected DigitalSource m_aSource
protected DigitalSource m_bSource
protected DigitalSource m_indexSource
public Encoder(int aChannel, int bChannel, boolean reverseDirection)
aChannel - The a channel DIO channel. 0-9 are on-board, 10-25 are on
the MXP portbChannel - The b channel DIO channel. 0-9 are on-board, 10-25 are on
the MXP portreverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.public Encoder(int aChannel, int bChannel)
aChannel - The a channel digital input channel.bChannel - The b channel digital input channel.public Encoder(int aChannel, int bChannel, boolean reverseDirection, CounterBase.EncodingType encodingType)
aChannel - The a channel digital input channel.bChannel - The b channel digital input channel.reverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.encodingType - either k1X, k2X, or k4X to indicate 1X, 2X or 4X
decoding. If 4X is selected, then an encoder FPGA object is used and
the returned counts will be 4x the encoder spec'd value since all
rising and falling edges are counted. If 1X or 2X are selected then
a counter object will be used and the returned value will either
exactly match the spec'd count or be double (2x) the spec'd count.public Encoder(int aChannel, int bChannel, int indexChannel, boolean reverseDirection)
aChannel - The a channel digital input channel.bChannel - The b channel digital input channel.indexChannel - The index channel digital input channel.reverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.public Encoder(int aChannel, int bChannel, int indexChannel)
aChannel - The a channel digital input channel.bChannel - The b channel digital input channel.indexChannel - The index channel digital input channel.public Encoder(DigitalSource aSource, DigitalSource bSource, boolean reverseDirection)
aSource - The source that should be used for the a channel.bSource - the source that should be used for the b channel.reverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.public Encoder(DigitalSource aSource, DigitalSource bSource)
aSource - The source that should be used for the a channel.bSource - the source that should be used for the b channel.public Encoder(DigitalSource aSource, DigitalSource bSource, boolean reverseDirection, CounterBase.EncodingType encodingType)
aSource - The source that should be used for the a channel.bSource - the source that should be used for the b channel.reverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.encodingType - either k1X, k2X, or k4X to indicate 1X, 2X or 4X
decoding. If 4X is selected, then an encoder FPGA object is used and
the returned counts will be 4x the encoder spec'd value since all
rising and falling edges are counted. If 1X or 2X are selected then
a counter object will be used and the returned value will either
exactly match the spec'd count or be double (2x) the spec'd count.public Encoder(DigitalSource aSource, DigitalSource bSource, DigitalSource indexSource, boolean reverseDirection)
aSource - The source that should be used for the a channel.bSource - the source that should be used for the b channel.indexSource - the source that should be used for the index channel.reverseDirection - represents the orientation of the encoder and
inverts the output values if necessary so forward represents
positive values.public Encoder(DigitalSource aSource, DigitalSource bSource, DigitalSource indexSource)
aSource - The source that should be used for the a channel.bSource - the source that should be used for the b channel.indexSource - the source that should be used for the index channel.public int getFPGAIndex()
public int getEncodingScale()
public void free()
SensorBasefree in class SensorBasepublic int getRaw()
public int get()
get in interface CounterBasepublic void reset()
reset in interface CounterBasepublic double getPeriod()
getPeriod in interface CounterBasepublic void setMaxPeriod(double maxPeriod)
setMaxPeriod in interface CounterBasemaxPeriod - The maximum time between rising and falling edges before
the FPGA will report the device stopped. This is expressed in
seconds.public boolean getStopped()
getStopped in interface CounterBasepublic boolean getDirection()
getDirection in interface CounterBasepublic double getDistance()
public double getRate()
public void setMinRate(double minRate)
minRate - The minimum rate. The units are in distance per second as
scaled by the value from setDistancePerPulse().public void setDistancePerPulse(double distancePerPulse)
distancePerPulse - The scale factor that will be used to convert
pulses to useful units.public void setReverseDirection(boolean reverseDirection)
reverseDirection - true if the encoder direction should be reversedpublic void setSamplesToAverage(int samplesToAverage)
samplesToAverage - The number of samples to average from 1 to 127.public int getSamplesToAverage()
public void setPIDSourceType(PIDSourceType pidSource)
setPIDSourceType in interface PIDSourcepidSource - An enum to select the parameter.public PIDSourceType getPIDSourceType()
getPIDSourceType in interface PIDSourcepublic double pidGet()
public void setIndexSource(int channel, Encoder.IndexingType type)
channel - A DIO channel to set as the encoder indextype - The state that will cause the encoder to resetpublic void setIndexSource(int channel)
channel - A DIO channel to set as the encoder indexpublic void setIndexSource(DigitalSource source, Encoder.IndexingType type)
source - A digital source to set as the encoder indextype - The state that will cause the encoder to resetpublic void setIndexSource(DigitalSource source)
source - A digital source to set as the encoder indexpublic java.lang.String getSmartDashboardType()
getSmartDashboardType in interface Sendablepublic void updateTable()
updateTable in interface LiveWindowSendablepublic void startLiveWindowMode()
startLiveWindowMode in interface LiveWindowSendablepublic void stopLiveWindowMode()
stopLiveWindowMode in interface LiveWindowSendable