mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
Added an Accelerometer interface
ADXL345_I2C, ADXL345_SPI, and BuiltInAccelerometer implement this interface. The analog accelerometer class Accelerometer was renamed to AnalogAccelerometer. Change-Id: Iaae79d582a24c36c372f5fd4ea6df37be289b9c1
This commit is contained in:
@@ -9,120 +9,142 @@ package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class ADXL345_I2C extends SensorBase {
|
||||
public class ADXL345_I2C extends SensorBase implements Accelerometer {
|
||||
|
||||
private static final byte kAddress = 0x1D;
|
||||
private static final byte kPowerCtlRegister = 0x2D;
|
||||
private static final byte kDataFormatRegister = 0x31;
|
||||
private static final byte kDataRegister = 0x32;
|
||||
private static final double kGsPerLSB = 0.00390625;
|
||||
private static final byte kPowerCtl_Link = 0x20, kPowerCtl_AutoSleep = 0x10, kPowerCtl_Measure = 0x08, kPowerCtl_Sleep = 0x04;
|
||||
private static final byte kDataFormat_SelfTest = (byte) 0x80, kDataFormat_SPI = 0x40, kDataFormat_IntInvert = 0x20, kDataFormat_FullRes = 0x08, kDataFormat_Justify = 0x04;
|
||||
private static final byte kAddress = 0x1D;
|
||||
private static final byte kPowerCtlRegister = 0x2D;
|
||||
private static final byte kDataFormatRegister = 0x31;
|
||||
private static final byte kDataRegister = 0x32;
|
||||
private static final double kGsPerLSB = 0.00390625;
|
||||
private static final byte kPowerCtl_Link = 0x20, kPowerCtl_AutoSleep = 0x10, kPowerCtl_Measure = 0x08, kPowerCtl_Sleep = 0x04;
|
||||
private static final byte kDataFormat_SelfTest = (byte) 0x80, kDataFormat_SPI = 0x40, kDataFormat_IntInvert = 0x20, kDataFormat_FullRes = 0x08, kDataFormat_Justify = 0x04;
|
||||
|
||||
public static class DataFormat_Range {
|
||||
public static class Axes {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte k2G_val = 0x00;
|
||||
static final byte k4G_val = 0x01;
|
||||
static final byte k8G_val = 0x02;
|
||||
static final byte k16G_val = 0x03;
|
||||
public static final DataFormat_Range k2G = new DataFormat_Range(k2G_val);
|
||||
public static final DataFormat_Range k4G = new DataFormat_Range(k4G_val);
|
||||
public static final DataFormat_Range k8G = new DataFormat_Range(k8G_val);
|
||||
public static final DataFormat_Range k16G = new DataFormat_Range(k16G_val);
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte kX_val = 0x00;
|
||||
static final byte kY_val = 0x02;
|
||||
static final byte kZ_val = 0x04;
|
||||
public static final Axes kX = new Axes(kX_val);
|
||||
public static final Axes kY = new Axes(kY_val);
|
||||
public static final Axes kZ = new Axes(kZ_val);
|
||||
|
||||
private DataFormat_Range(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
private Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
public static class Axes {
|
||||
public static class AllAxes {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte kX_val = 0x00;
|
||||
static final byte kY_val = 0x02;
|
||||
static final byte kZ_val = 0x04;
|
||||
public static final Axes kX = new Axes(kX_val);
|
||||
public static final Axes kY = new Axes(kY_val);
|
||||
public static final Axes kZ = new Axes(kZ_val);
|
||||
public double XAxis;
|
||||
public double YAxis;
|
||||
public double ZAxis;
|
||||
}
|
||||
private I2C m_i2c;
|
||||
|
||||
private Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
public ADXL345_I2C(I2C.Port port, Range range) {
|
||||
m_i2c = new I2C(port, kAddress);
|
||||
|
||||
public static class AllAxes {
|
||||
// Turn on the measurements
|
||||
m_i2c.write(kPowerCtlRegister, kPowerCtl_Measure);
|
||||
|
||||
public double XAxis;
|
||||
public double YAxis;
|
||||
public double ZAxis;
|
||||
}
|
||||
private I2C m_i2c;
|
||||
setRange(range);
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
public ADXL345_I2C(I2C.Port port, DataFormat_Range range) {
|
||||
m_i2c = new I2C(port, kAddress);
|
||||
|
||||
// Turn on the measurements
|
||||
m_i2c.write(kPowerCtlRegister, kPowerCtl_Measure);
|
||||
// Specify the data format to read
|
||||
m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | range.value);
|
||||
UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
|
||||
}
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
|
||||
}
|
||||
/** {inheritdoc} */
|
||||
@Override
|
||||
public void setRange(Range range) {
|
||||
byte value = 0;
|
||||
|
||||
/**
|
||||
* Get the acceleration of one axis in Gs.
|
||||
*
|
||||
* @param axis The axis to read from.
|
||||
* @return Acceleration of the ADXL345 in Gs.
|
||||
*/
|
||||
public double getAcceleration(Axes axis) {
|
||||
byte[] rawAccel = new byte[2];
|
||||
m_i2c.read(kDataRegister + axis.value, rawAccel.length, rawAccel);
|
||||
switch(range) {
|
||||
case k2G:
|
||||
value = 0;
|
||||
break;
|
||||
case k4G:
|
||||
value = 1;
|
||||
break;
|
||||
case k8G:
|
||||
value = 2;
|
||||
break;
|
||||
case k16G:
|
||||
value = 3;
|
||||
break;
|
||||
}
|
||||
|
||||
// Sensor is little endian... swap bytes
|
||||
return accelFromBytes(rawAccel[0], rawAccel[1]);
|
||||
}
|
||||
// Specify the data format to read
|
||||
m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | value);
|
||||
}
|
||||
|
||||
private double accelFromBytes(byte first, byte second) {
|
||||
short tempLow = (short) (first & 0xff);
|
||||
short tempHigh = (short) ((second << 8) & 0xff00);
|
||||
return (tempLow | tempHigh) * kGsPerLSB;
|
||||
}
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getX() {
|
||||
return getAcceleration(Axes.kX);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the acceleration of all axes in Gs.
|
||||
*
|
||||
* @return Acceleration measured on all axes of the ADXL345 in Gs.
|
||||
*/
|
||||
public AllAxes getAccelerations() {
|
||||
AllAxes data = new AllAxes();
|
||||
byte[] rawData = new byte[6];
|
||||
m_i2c.read(kDataRegister, rawData.length, rawData);
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getY() {
|
||||
return getAcceleration(Axes.kY);
|
||||
}
|
||||
|
||||
// Sensor is little endian... swap bytes
|
||||
data.XAxis = accelFromBytes(rawData[0], rawData[1]);
|
||||
data.YAxis = accelFromBytes(rawData[2], rawData[3]);
|
||||
data.ZAxis = accelFromBytes(rawData[4], rawData[5]);
|
||||
return data;
|
||||
}
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getZ() {
|
||||
return getAcceleration(Axes.kZ);
|
||||
}
|
||||
|
||||
// TODO: Support LiveWindow
|
||||
/**
|
||||
* Get the acceleration of one axis in Gs.
|
||||
*
|
||||
* @param axis The axis to read from.
|
||||
* @return Acceleration of the ADXL345 in Gs.
|
||||
*/
|
||||
public double getAcceleration(Axes axis) {
|
||||
byte[] rawAccel = new byte[2];
|
||||
m_i2c.read(kDataRegister + axis.value, rawAccel.length, rawAccel);
|
||||
|
||||
// Sensor is little endian... swap bytes
|
||||
return accelFromBytes(rawAccel[0], rawAccel[1]);
|
||||
}
|
||||
|
||||
private double accelFromBytes(byte first, byte second) {
|
||||
short tempLow = (short) (first & 0xff);
|
||||
short tempHigh = (short) ((second << 8) & 0xff00);
|
||||
return (tempLow | tempHigh) * kGsPerLSB;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the acceleration of all axes in Gs.
|
||||
*
|
||||
* @return Acceleration measured on all axes of the ADXL345 in Gs.
|
||||
*/
|
||||
public AllAxes getAccelerations() {
|
||||
AllAxes data = new AllAxes();
|
||||
byte[] rawData = new byte[6];
|
||||
m_i2c.read(kDataRegister, rawData.length, rawData);
|
||||
|
||||
// Sensor is little endian... swap bytes
|
||||
data.XAxis = accelFromBytes(rawData[0], rawData[1]);
|
||||
data.YAxis = accelFromBytes(rawData[2], rawData[3]);
|
||||
data.ZAxis = accelFromBytes(rawData[4], rawData[5]);
|
||||
return data;
|
||||
}
|
||||
|
||||
// TODO: Support LiveWindow
|
||||
}
|
||||
|
||||
@@ -5,143 +5,167 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
* @author mwills
|
||||
*/
|
||||
public class ADXL345_SPI extends SensorBase {
|
||||
private static final int kPowerCtlRegister = 0x2D;
|
||||
private static final int kDataFormatRegister = 0x31;
|
||||
private static final int kDataRegister = 0x32;
|
||||
private static final double kGsPerLSB = 0.00390625;
|
||||
|
||||
private static final int kAddress_Read = 0x80;
|
||||
private static final int kAddress_MultiByte = 0x40;
|
||||
|
||||
private static final int kPowerCtl_Link=0x20;
|
||||
private static final int kPowerCtl_AutoSleep=0x10;
|
||||
private static final int kPowerCtl_Measure=0x08;
|
||||
private static final int kPowerCtl_Sleep=0x04;
|
||||
|
||||
private static final int kDataFormat_SelfTest=0x80;
|
||||
private static final int kDataFormat_SPI=0x40;
|
||||
private static final int kDataFormat_IntInvert=0x20;
|
||||
private static final int kDataFormat_FullRes=0x08;
|
||||
private static final int kDataFormat_Justify=0x04;
|
||||
|
||||
|
||||
public static class DataFormat_Range {
|
||||
public class ADXL345_SPI extends SensorBase implements Accelerometer {
|
||||
private static final int kPowerCtlRegister = 0x2D;
|
||||
private static final int kDataFormatRegister = 0x31;
|
||||
private static final int kDataRegister = 0x32;
|
||||
private static final double kGsPerLSB = 0.00390625;
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte k2G_val = 0x00;
|
||||
static final byte k4G_val = 0x01;
|
||||
static final byte k8G_val = 0x02;
|
||||
static final byte k16G_val = 0x03;
|
||||
public static final ADXL345_SPI.DataFormat_Range k2G = new ADXL345_SPI.DataFormat_Range(k2G_val);
|
||||
public static final ADXL345_SPI.DataFormat_Range k4G = new ADXL345_SPI.DataFormat_Range(k4G_val);
|
||||
public static final ADXL345_SPI.DataFormat_Range k8G = new ADXL345_SPI.DataFormat_Range(k8G_val);
|
||||
public static final ADXL345_SPI.DataFormat_Range k16G = new ADXL345_SPI.DataFormat_Range(k16G_val);
|
||||
private static final int kAddress_Read = 0x80;
|
||||
private static final int kAddress_MultiByte = 0x40;
|
||||
|
||||
private DataFormat_Range(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
private static final int kPowerCtl_Link=0x20;
|
||||
private static final int kPowerCtl_AutoSleep=0x10;
|
||||
private static final int kPowerCtl_Measure=0x08;
|
||||
private static final int kPowerCtl_Sleep=0x04;
|
||||
|
||||
public static class Axes {
|
||||
private static final int kDataFormat_SelfTest=0x80;
|
||||
private static final int kDataFormat_SPI=0x40;
|
||||
private static final int kDataFormat_IntInvert=0x20;
|
||||
private static final int kDataFormat_FullRes=0x08;
|
||||
private static final int kDataFormat_Justify=0x04;
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte kX_val = 0x00;
|
||||
static final byte kY_val = 0x02;
|
||||
static final byte kZ_val = 0x04;
|
||||
public static final ADXL345_SPI.Axes kX = new ADXL345_SPI.Axes(kX_val);
|
||||
public static final ADXL345_SPI.Axes kY = new ADXL345_SPI.Axes(kY_val);
|
||||
public static final ADXL345_SPI.Axes kZ = new ADXL345_SPI.Axes(kZ_val);
|
||||
public static class Axes {
|
||||
|
||||
private Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final byte value;
|
||||
static final byte kX_val = 0x00;
|
||||
static final byte kY_val = 0x02;
|
||||
static final byte kZ_val = 0x04;
|
||||
public static final ADXL345_SPI.Axes kX = new ADXL345_SPI.Axes(kX_val);
|
||||
public static final ADXL345_SPI.Axes kY = new ADXL345_SPI.Axes(kY_val);
|
||||
public static final ADXL345_SPI.Axes kZ = new ADXL345_SPI.Axes(kZ_val);
|
||||
|
||||
public static class AllAxes {
|
||||
private Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
public double XAxis;
|
||||
public double YAxis;
|
||||
public double ZAxis;
|
||||
}
|
||||
|
||||
private SPI m_spi;
|
||||
|
||||
/**
|
||||
* Constructor. Use this when the device is the first/only device on the bus
|
||||
*
|
||||
* @param clk The clock channel
|
||||
* @param mosi The mosi (output) channel
|
||||
* @param miso The miso (input) channel
|
||||
* @param cs The chip select channel
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
public ADXL345_SPI(SPI.Port port, ADXL345_SPI.DataFormat_Range range) {
|
||||
m_spi = new SPI(port);
|
||||
init(range);
|
||||
}
|
||||
|
||||
public void free(){
|
||||
m_spi.free();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set SPI bus parameters, bring device out of sleep and set format
|
||||
*
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
private void init(ADXL345_SPI.DataFormat_Range range){
|
||||
public static class AllAxes {
|
||||
|
||||
public double XAxis;
|
||||
public double YAxis;
|
||||
public double ZAxis;
|
||||
}
|
||||
|
||||
private SPI m_spi;
|
||||
|
||||
/**
|
||||
* Constructor. Use this when the device is the first/only device on the bus
|
||||
*
|
||||
* @param clk The clock channel
|
||||
* @param mosi The mosi (output) channel
|
||||
* @param miso The miso (input) channel
|
||||
* @param cs The chip select channel
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
public ADXL345_SPI(SPI.Port port, Range range) {
|
||||
m_spi = new SPI(port);
|
||||
init(range);
|
||||
}
|
||||
|
||||
public void free(){
|
||||
m_spi.free();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set SPI bus parameters, bring device out of sleep and set format
|
||||
*
|
||||
* @param range The range (+ or -) that the accelerometer will measure.
|
||||
*/
|
||||
private void init(Range range){
|
||||
m_spi.setClockRate(500000);
|
||||
m_spi.setMSBFirst();
|
||||
m_spi.setMSBFirst();
|
||||
m_spi.setSampleDataOnFalling();
|
||||
m_spi.setClockActiveLow();
|
||||
m_spi.setChipSelectActiveHigh();
|
||||
|
||||
// Turn on the measurements
|
||||
// Turn on the measurements
|
||||
byte[] commands = new byte[2];
|
||||
commands[0] = kPowerCtlRegister;
|
||||
commands[1] = kPowerCtl_Measure;
|
||||
m_spi.write(commands, 2);
|
||||
// Specify the data format to read
|
||||
commands[0] = kDataFormatRegister;
|
||||
commands[1] = (byte)(kDataFormat_FullRes | range.value);
|
||||
m_spi.write(commands, 2);
|
||||
}
|
||||
m_spi.write(commands, 2);
|
||||
|
||||
/**
|
||||
* Get the acceleration of one axis in Gs.
|
||||
*
|
||||
* @param axis The axis to read from.
|
||||
* @return Acceleration of the ADXL345 in Gs.
|
||||
*/
|
||||
public double getAcceleration(ADXL345_SPI.Axes axis) {
|
||||
setRange(range);
|
||||
}
|
||||
|
||||
/** {inheritdoc} */
|
||||
@Override
|
||||
public void setRange(Range range) {
|
||||
byte value = 0;
|
||||
|
||||
switch(range) {
|
||||
case k2G:
|
||||
value = 0;
|
||||
break;
|
||||
case k4G:
|
||||
value = 1;
|
||||
break;
|
||||
case k8G:
|
||||
value = 2;
|
||||
break;
|
||||
case k16G:
|
||||
value = 3;
|
||||
break;
|
||||
}
|
||||
|
||||
// Specify the data format to read
|
||||
byte[] commands = new byte[]{
|
||||
kDataFormatRegister,
|
||||
(byte)(kDataFormat_FullRes | value)
|
||||
};
|
||||
m_spi.write(commands, commands.length);
|
||||
}
|
||||
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getX() {
|
||||
return getAcceleration(Axes.kX);
|
||||
}
|
||||
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getY() {
|
||||
return getAcceleration(Axes.kY);
|
||||
}
|
||||
|
||||
/** {@inheritdoc} */
|
||||
@Override
|
||||
public double getZ() {
|
||||
return getAcceleration(Axes.kZ);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the acceleration of one axis in Gs.
|
||||
*
|
||||
* @param axis The axis to read from.
|
||||
* @return Acceleration of the ADXL345 in Gs.
|
||||
*/
|
||||
public double getAcceleration(ADXL345_SPI.Axes axis) {
|
||||
byte[] transferBuffer = new byte[3];
|
||||
transferBuffer[0] = (byte)((kAddress_Read | kAddress_MultiByte | kDataRegister) + axis.value);
|
||||
m_spi.transaction(transferBuffer, transferBuffer, 3);
|
||||
m_spi.transaction(transferBuffer, transferBuffer, 3);
|
||||
//Sensor is little endian... swap bytes
|
||||
int rawAccel = transferBuffer[2] << 8 | transferBuffer[1];
|
||||
return rawAccel * kGsPerLSB;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the acceleration of all axes in Gs.
|
||||
*
|
||||
* @return Acceleration measured on all axes of the ADXL345 in Gs.
|
||||
*/
|
||||
public ADXL345_SPI.AllAxes getAccelerations() {
|
||||
ADXL345_SPI.AllAxes data = new ADXL345_SPI.AllAxes();
|
||||
/**
|
||||
* Get the acceleration of all axes in Gs.
|
||||
*
|
||||
* @return Acceleration measured on all axes of the ADXL345 in Gs.
|
||||
*/
|
||||
public ADXL345_SPI.AllAxes getAccelerations() {
|
||||
ADXL345_SPI.AllAxes data = new ADXL345_SPI.AllAxes();
|
||||
byte dataBuffer[] = new byte[7];
|
||||
int[] rawData = new int[3];
|
||||
if (m_spi != null)
|
||||
@@ -161,5 +185,5 @@ public class ADXL345_SPI extends SensorBase {
|
||||
data.ZAxis = rawData[2] * kGsPerLSB;
|
||||
}
|
||||
return data;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -16,12 +16,12 @@ import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
|
||||
/**
|
||||
* Handle operation of the accelerometer.
|
||||
* Handle operation of an analog accelerometer.
|
||||
* The accelerometer reads acceleration directly through the sensor. Many sensors have
|
||||
* multiple axis and can be treated as multiple devices. Each is calibrated by finding
|
||||
* the center value over a period of time.
|
||||
*/
|
||||
public class Accelerometer extends SensorBase implements PIDSource, ISensor, LiveWindowSendable {
|
||||
public class AnalogAccelerometer extends SensorBase implements PIDSource, ISensor, LiveWindowSendable {
|
||||
|
||||
private AnalogInput m_analogChannel;
|
||||
private double m_voltsPerG = 1.0;
|
||||
@@ -42,7 +42,7 @@ public class Accelerometer extends SensorBase implements PIDSource, ISensor, Liv
|
||||
* The constructor allocates desired analog channel.
|
||||
* @param channel the port that the accelerometer is on
|
||||
*/
|
||||
public Accelerometer(final int channel) {
|
||||
public AnalogAccelerometer(final int channel) {
|
||||
m_allocatedChannel = true;
|
||||
m_analogChannel = new AnalogInput(channel);
|
||||
initAccelerometer();
|
||||
@@ -55,7 +55,7 @@ public class Accelerometer extends SensorBase implements PIDSource, ISensor, Liv
|
||||
* the Accelerometer class.
|
||||
* @param channel an already initialized analog channel
|
||||
*/
|
||||
public Accelerometer(AnalogInput channel) {
|
||||
public AnalogAccelerometer(AnalogInput channel) {
|
||||
m_allocatedChannel = false;
|
||||
if (channel == null)
|
||||
throw new NullPointerException("Analog Channel given was null");
|
||||
@@ -4,6 +4,7 @@
|
||||
/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
import edu.wpi.first.wpilibj.hal.AccelerometerJNI;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
@@ -17,15 +18,28 @@ import edu.wpi.first.wpilibj.tables.ITable;
|
||||
*
|
||||
* This class allows access to the RoboRIO's internal accelerometer.
|
||||
*/
|
||||
public class BuiltInAccelerometer implements ISensor, LiveWindowSendable
|
||||
public class BuiltInAccelerometer implements Accelerometer, ISensor, LiveWindowSendable
|
||||
{
|
||||
public enum Range { k2G, k4G, k8G }
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
* @param range The range the accelerometer will measure
|
||||
*/
|
||||
public BuiltInAccelerometer(Range range) {
|
||||
setRange(range);
|
||||
UsageReporting.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
* The accelerometer will measure +/-8 g-forces
|
||||
*/
|
||||
public BuiltInAccelerometer() {
|
||||
this(Range.k8G);
|
||||
}
|
||||
|
||||
/** {inheritdoc} */
|
||||
@Override
|
||||
public void setRange(Range range) {
|
||||
AccelerometerJNI.setAccelerometerActive(false);
|
||||
|
||||
switch(range) {
|
||||
@@ -38,24 +52,17 @@ public class BuiltInAccelerometer implements ISensor, LiveWindowSendable
|
||||
case k8G:
|
||||
AccelerometerJNI.setAccelerometerRange(2);
|
||||
break;
|
||||
case k16G:
|
||||
throw new RuntimeException("16G range not supported (use k2G, k4G, or k8G)");
|
||||
}
|
||||
|
||||
AccelerometerJNI.setAccelerometerActive(true);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
* The accelerometer will measure +/-8 g-forces
|
||||
*/
|
||||
public BuiltInAccelerometer() {
|
||||
this(Range.k8G);
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the X axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getX() {
|
||||
return AccelerometerJNI.getAccelerometerX();
|
||||
}
|
||||
@@ -63,6 +70,7 @@ public class BuiltInAccelerometer implements ISensor, LiveWindowSendable
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the Y axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getY() {
|
||||
return AccelerometerJNI.getAccelerometerY();
|
||||
}
|
||||
@@ -70,6 +78,7 @@ public class BuiltInAccelerometer implements ISensor, LiveWindowSendable
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the Z axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getZ() {
|
||||
return AccelerometerJNI.getAccelerometerZ();
|
||||
}
|
||||
|
||||
@@ -0,0 +1,48 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2014. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.interfaces;
|
||||
|
||||
/**
|
||||
* Interface for 3-axis accelerometers
|
||||
*/
|
||||
public interface Accelerometer {
|
||||
public enum Range
|
||||
{
|
||||
k2G,
|
||||
k4G,
|
||||
k8G,
|
||||
k16G
|
||||
}
|
||||
|
||||
/**
|
||||
* Common interface for setting the measuring range of an accelerometer.
|
||||
*
|
||||
* @param range The maximum acceleration, positive or negative, that the
|
||||
* accelerometer will measure. Not all accelerometers support all ranges.
|
||||
*/
|
||||
public void setRange(Range range);
|
||||
|
||||
/**
|
||||
* Common interface for getting the x axis acceleration
|
||||
*
|
||||
* @return The acceleration along the x axis in g-forces
|
||||
*/
|
||||
public double getX();
|
||||
|
||||
/**
|
||||
* Common interface for getting the y axis acceleration
|
||||
*
|
||||
* @return The acceleration along the y axis in g-forces
|
||||
*/
|
||||
public double getY();
|
||||
|
||||
/**
|
||||
* Common interface for getting the z axis acceleration
|
||||
*
|
||||
* @return The acceleration along the z axis in g-forces
|
||||
*/
|
||||
public double getZ();
|
||||
}
|
||||
Reference in New Issue
Block a user