mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
Restructure WPILibJ to share code.
wpilibJavaDevices now contains RoboRIO specific code and wpilibJava has shared high level information. The restructuring was mostly just copy and paste. The three big exceptions are Timer, RobotState and HLUsageReporting. Those require some dependencies injection since that appears to be the cleanest way to share the code. Change-Id: Ie7011e32bc95953a87801a9905b3bfec7f8de285
This commit is contained in:
@@ -0,0 +1,150 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
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 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;
|
||||
|
||||
public static class Axes {
|
||||
|
||||
/**
|
||||
* 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 Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
public static class AllAxes {
|
||||
|
||||
public double XAxis;
|
||||
public double YAxis;
|
||||
public double ZAxis;
|
||||
}
|
||||
private I2C m_i2c;
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
// Turn on the measurements
|
||||
m_i2c.write(kPowerCtlRegister, kPowerCtl_Measure);
|
||||
|
||||
setRange(range);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
|
||||
}
|
||||
|
||||
/** {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
|
||||
m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | value);
|
||||
}
|
||||
|
||||
/** {@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(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
|
||||
}
|
||||
@@ -0,0 +1,189 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
* @author mwills
|
||||
*/
|
||||
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;
|
||||
|
||||
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 Axes {
|
||||
|
||||
/**
|
||||
* 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);
|
||||
|
||||
private Axes(byte value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
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.setSampleDataOnFalling();
|
||||
m_spi.setClockActiveLow();
|
||||
m_spi.setChipSelectActiveHigh();
|
||||
|
||||
// Turn on the measurements
|
||||
byte[] commands = new byte[2];
|
||||
commands[0] = kPowerCtlRegister;
|
||||
commands[1] = kPowerCtl_Measure;
|
||||
m_spi.write(commands, 2);
|
||||
|
||||
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);
|
||||
//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();
|
||||
byte dataBuffer[] = new byte[7];
|
||||
int[] rawData = new int[3];
|
||||
if (m_spi != null)
|
||||
{
|
||||
// Select the data address.
|
||||
dataBuffer[0] = (byte)(kAddress_Read | kAddress_MultiByte | kDataRegister);
|
||||
m_spi.transaction(dataBuffer, dataBuffer, 7);
|
||||
|
||||
for (int i=0; i<3; i++)
|
||||
{
|
||||
//Sensor is little endian... swap bytes
|
||||
rawData[i] = dataBuffer[i*2+2] << 8 | dataBuffer[i*2+1];
|
||||
}
|
||||
|
||||
data.XAxis = rawData[0] * kGsPerLSB;
|
||||
data.YAxis = rawData[1] * kGsPerLSB;
|
||||
data.ZAxis = rawData[2] * kGsPerLSB;
|
||||
}
|
||||
return data;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,24 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
/**
|
||||
* Structure for holding the values stored in an accumulator
|
||||
* @author brad
|
||||
*/
|
||||
public class AccumulatorResult {
|
||||
|
||||
/**
|
||||
* The total value accumulated
|
||||
*/
|
||||
public long value;
|
||||
/**
|
||||
* The number of sample vaule was accumulated over
|
||||
*/
|
||||
public long count;
|
||||
}
|
||||
@@ -0,0 +1,162 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
|
||||
/**
|
||||
* 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 AnalogAccelerometer extends SensorBase implements PIDSource, ISensor, LiveWindowSendable {
|
||||
|
||||
private AnalogInput m_analogChannel;
|
||||
private double m_voltsPerG = 1.0;
|
||||
private double m_zeroGVoltage = 2.5;
|
||||
private boolean m_allocatedChannel;
|
||||
|
||||
/**
|
||||
* Common initialization
|
||||
*/
|
||||
private void initAccelerometer() {
|
||||
UsageReporting.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel());
|
||||
LiveWindow.addSensor("Accelerometer", m_analogChannel.getChannel(), this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new instance of an accelerometer.
|
||||
*
|
||||
* The constructor allocates desired analog channel.
|
||||
* @param channel the port that the accelerometer is on
|
||||
*/
|
||||
public AnalogAccelerometer(final int channel) {
|
||||
m_allocatedChannel = true;
|
||||
m_analogChannel = new AnalogInput(channel);
|
||||
initAccelerometer();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new instance of Accelerometer from an existing AnalogChannel.
|
||||
* Make a new instance of accelerometer given an AnalogChannel. This is particularly
|
||||
* useful if the port is going to be read as an analog channel as well as through
|
||||
* the Accelerometer class.
|
||||
* @param channel an already initialized analog channel
|
||||
*/
|
||||
public AnalogAccelerometer(AnalogInput channel) {
|
||||
m_allocatedChannel = false;
|
||||
if (channel == null)
|
||||
throw new NullPointerException("Analog Channel given was null");
|
||||
m_analogChannel = channel;
|
||||
initAccelerometer();
|
||||
}
|
||||
|
||||
/**
|
||||
* Delete the analog components used for the accelerometer.
|
||||
*/
|
||||
public void free() {
|
||||
if (m_analogChannel != null && m_allocatedChannel) {
|
||||
m_analogChannel.free();
|
||||
}
|
||||
m_analogChannel = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the acceleration in Gs.
|
||||
*
|
||||
* The acceleration is returned units of Gs.
|
||||
*
|
||||
* @return The current acceleration of the sensor in Gs.
|
||||
*/
|
||||
public double getAcceleration() {
|
||||
return (m_analogChannel.getAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the accelerometer sensitivity.
|
||||
*
|
||||
* This sets the sensitivity of the accelerometer used for calculating the acceleration.
|
||||
* The sensitivity varys by accelerometer model. There are constants defined for various models.
|
||||
*
|
||||
* @param sensitivity The sensitivity of accelerometer in Volts per G.
|
||||
*/
|
||||
public void setSensitivity(double sensitivity) {
|
||||
m_voltsPerG = sensitivity;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the voltage that corresponds to 0 G.
|
||||
*
|
||||
* The zero G voltage varys by accelerometer model. There are constants defined for various models.
|
||||
*
|
||||
* @param zero The zero G voltage.
|
||||
*/
|
||||
public void setZero(double zero) {
|
||||
m_zeroGVoltage = zero;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Acceleration for the PID Source parent.
|
||||
*
|
||||
* @return The current acceleration in Gs.
|
||||
*/
|
||||
public double pidGet() {
|
||||
return getAcceleration();
|
||||
}
|
||||
|
||||
public String getSmartDashboardType() {
|
||||
return "Accelerometer";
|
||||
}
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAcceleration());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when entering the LiveWindow.
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when exiting the LiveWindow.
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {}
|
||||
}
|
||||
@@ -0,0 +1,517 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.LongBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
//import com.sun.jna.Pointer;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Analog channel class.
|
||||
*
|
||||
* Each analog channel is read from hardware as a 12-bit number representing
|
||||
* -10V to 10V.
|
||||
*
|
||||
* Connected to each analog channel is an averaging and oversampling engine.
|
||||
* This engine accumulates the specified ( by setAverageBits() and
|
||||
* setOversampleBits() ) number of samples before returning a new value. This is
|
||||
* not a sliding window average. The only difference between the oversampled
|
||||
* samples and the averaged samples is that the oversampled samples are simply
|
||||
* accumulated effectively increasing the resolution, while the averaged samples
|
||||
* are divided by the number of samples to retain the resolution, but get more
|
||||
* stable values.
|
||||
*/
|
||||
public class AnalogInput extends SensorBase implements PIDSource,
|
||||
LiveWindowSendable {
|
||||
|
||||
private static final int kAccumulatorSlot = 1;
|
||||
private static Resource channels = new Resource(kAnalogInputChannels);
|
||||
private ByteBuffer m_port;
|
||||
private int m_channel;
|
||||
private static final int[] kAccumulatorChannels = { 0, 1 };
|
||||
private long m_accumulatorOffset;
|
||||
|
||||
/**
|
||||
* Construct an analog channel.
|
||||
*
|
||||
* @param channel
|
||||
* The channel number to represent.
|
||||
*/
|
||||
public AnalogInput(final int channel) {
|
||||
m_channel = channel;
|
||||
|
||||
if (AnalogJNI.checkAnalogInputChannel(channel) == 0) {
|
||||
throw new AllocationException("Analog input channel " + m_channel
|
||||
+ " cannot be allocated. Channel is not present.");
|
||||
}
|
||||
try {
|
||||
channels.allocate(channel);
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException("Analog input channel " + m_channel
|
||||
+ " is already allocated");
|
||||
}
|
||||
|
||||
ByteBuffer port_pointer = AnalogJNI.getPort((byte) channel);
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_port = AnalogJNI.initializeAnalogInputPort(port_pointer, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
LiveWindow.addSensor("AnalogInput", channel, this);
|
||||
UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Channel destructor.
|
||||
*/
|
||||
public void free() {
|
||||
channels.free(m_channel);
|
||||
m_channel = 0;
|
||||
m_accumulatorOffset = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a sample straight from this channel. The sample is a 12-bit value
|
||||
* representing the 0V to 10V range of the A/D converter. The units are in
|
||||
* A/D converter codes. Use GetVoltage() to get the analog value in
|
||||
* calibrated units.
|
||||
*
|
||||
* @return A sample straight from this channel.
|
||||
*/
|
||||
public int getValue() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = AnalogJNI.getAnalogValue(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a sample from the output of the oversample and average engine for
|
||||
* this channel. The sample is 12-bit + the value configured in
|
||||
* SetOversampleBits(). The value configured in setAverageBits() will cause
|
||||
* this value to be averaged 2**bits number of samples. This is not a
|
||||
* sliding window. The sample will not change until 2**(OversamplBits +
|
||||
* AverageBits) samples have been acquired from this channel. Use
|
||||
* getAverageVoltage() to get the analog value in calibrated units.
|
||||
*
|
||||
* @return A sample from the oversample and average engine for this channel.
|
||||
*/
|
||||
public int getAverageValue() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = AnalogJNI.getAnalogAverageValue(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a scaled sample straight from this channel. The value is scaled to
|
||||
* units of Volts using the calibrated scaling data from getLSBWeight() and
|
||||
* getOffset().
|
||||
*
|
||||
* @return A scaled sample straight from this channel.
|
||||
*/
|
||||
public double getVoltage() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
double value = AnalogJNI.getAnalogVoltage(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a scaled sample from the output of the oversample and average engine
|
||||
* for this channel. The value is scaled to units of Volts using the
|
||||
* calibrated scaling data from getLSBWeight() and getOffset(). Using
|
||||
* oversampling will cause this value to be higher resolution, but it will
|
||||
* update more slowly. Using averaging will cause this value to be more
|
||||
* stable, but it will update more slowly.
|
||||
*
|
||||
* @return A scaled sample from the output of the oversample and average
|
||||
* engine for this channel.
|
||||
*/
|
||||
public double getAverageVoltage() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
double value = AnalogJNI.getAnalogAverageVoltage(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the factory scaling least significant bit weight constant. The least
|
||||
* significant bit weight constant for the channel that was calibrated in
|
||||
* manufacturing and stored in an eeprom.
|
||||
*
|
||||
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
|
||||
*
|
||||
* @return Least significant bit weight.
|
||||
*/
|
||||
public long getLSBWeight() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
long value = AnalogJNI.getAnalogLSBWeight(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the factory scaling offset constant. The offset constant for the
|
||||
* channel that was calibrated in manufacturing and stored in an eeprom.
|
||||
*
|
||||
* Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
|
||||
*
|
||||
* @return Offset constant.
|
||||
*/
|
||||
public int getOffset() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = AnalogJNI.getAnalogOffset(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the channel number.
|
||||
*
|
||||
* @return The channel number.
|
||||
*/
|
||||
public int getChannel() {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the number of averaging bits. This sets the number of averaging bits.
|
||||
* The actual number of averaged samples is 2**bits. The averaging is done
|
||||
* automatically in the FPGA.
|
||||
*
|
||||
* @param bits
|
||||
* The number of averaging bits.
|
||||
*/
|
||||
public void setAverageBits(final int bits) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.setAnalogAverageBits(m_port, bits, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of averaging bits. This gets the number of averaging bits
|
||||
* from the FPGA. The actual number of averaged samples is 2**bits. The
|
||||
* averaging is done automatically in the FPGA.
|
||||
*
|
||||
* @return The number of averaging bits.
|
||||
*/
|
||||
public int getAverageBits() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = AnalogJNI.getAnalogAverageBits(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the number of oversample bits. This sets the number of oversample
|
||||
* bits. The actual number of oversampled values is 2**bits. The
|
||||
* oversampling is done automatically in the FPGA.
|
||||
*
|
||||
* @param bits
|
||||
* The number of oversample bits.
|
||||
*/
|
||||
public void setOversampleBits(final int bits) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.setAnalogOversampleBits(m_port, bits, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of oversample bits. This gets the number of oversample
|
||||
* bits from the FPGA. The actual number of oversampled values is 2**bits.
|
||||
* The oversampling is done automatically in the FPGA.
|
||||
*
|
||||
* @return The number of oversample bits.
|
||||
*/
|
||||
public int getOversampleBits() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = AnalogJNI.getAnalogOversampleBits(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the accumulator.
|
||||
*/
|
||||
public void initAccumulator() {
|
||||
if (!isAccumulatorChannel()) {
|
||||
throw new AllocationException(
|
||||
"Accumulators are only available on slot "
|
||||
+ kAccumulatorSlot + " on channels "
|
||||
+ kAccumulatorChannels[0] + ","
|
||||
+ kAccumulatorChannels[1]);
|
||||
}
|
||||
m_accumulatorOffset = 0;
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.initAccumulator(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set an inital value for the accumulator.
|
||||
*
|
||||
* This will be added to all values returned to the user.
|
||||
*
|
||||
* @param initialValue
|
||||
* The value that the accumulator should start from when reset.
|
||||
*/
|
||||
public void setAccumulatorInitialValue(long initialValue) {
|
||||
m_accumulatorOffset = initialValue;
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the accumulator to the initial value.
|
||||
*/
|
||||
public void resetAccumulator() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.resetAccumulator(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the center value of the accumulator.
|
||||
*
|
||||
* The center value is subtracted from each A/D value before it is added to
|
||||
* the accumulator. This is used for the center value of devices like gyros
|
||||
* and accelerometers to make integration work and to take the device offset
|
||||
* into account when integrating.
|
||||
*
|
||||
* This center value is based on the output of the oversampled and averaged
|
||||
* source from channel 1. Because of this, any non-zero oversample bits will
|
||||
* affect the size of the value for this field.
|
||||
*/
|
||||
public void setAccumulatorCenter(int center) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.setAccumulatorCenter(m_port, center, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the accumulator's deadband.
|
||||
*/
|
||||
public void setAccumulatorDeadband(int deadband) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.setAccumulatorDeadband(m_port, deadband, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the accumulated value.
|
||||
*
|
||||
* Read the value that has been accumulating on channel 1. The accumulator
|
||||
* is attached after the oversample and average engine.
|
||||
*
|
||||
* @return The 64-bit value accumulated since the last Reset().
|
||||
*/
|
||||
public long getAccumulatorValue() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
long value = AnalogJNI.getAccumulatorValue(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value + m_accumulatorOffset;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the number of accumulated values.
|
||||
*
|
||||
* Read the count of the accumulated values since the accumulator was last
|
||||
* Reset().
|
||||
*
|
||||
* @return The number of times samples from the channel were accumulated.
|
||||
*/
|
||||
public long getAccumulatorCount() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
long value = AnalogJNI.getAccumulatorCount(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the accumulated value and the number of accumulated values
|
||||
* atomically.
|
||||
*
|
||||
* This function reads the value and count from the FPGA atomically. This
|
||||
* can be used for averaging.
|
||||
*
|
||||
* @param result
|
||||
* AccumulatorResult object to store the results in.
|
||||
*/
|
||||
public void getAccumulatorOutput(AccumulatorResult result) {
|
||||
if (result == null) {
|
||||
throw new IllegalArgumentException("Null parameter `result'");
|
||||
}
|
||||
if (!isAccumulatorChannel()) {
|
||||
throw new IllegalArgumentException("Channel " + m_channel
|
||||
+ " is not an accumulator channel.");
|
||||
}
|
||||
ByteBuffer value = ByteBuffer.allocateDirect(8);
|
||||
// set the byte order
|
||||
value.order(ByteOrder.LITTLE_ENDIAN);
|
||||
ByteBuffer count = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
count.order(ByteOrder.LITTLE_ENDIAN);
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
AnalogJNI.getAccumulatorOutput(m_port, value.asLongBuffer(), count.asIntBuffer(), status.asIntBuffer());
|
||||
result.value = value.asLongBuffer().get(0) + m_accumulatorOffset;
|
||||
result.count = count.asIntBuffer().get(0);
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Is the channel attached to an accumulator.
|
||||
*
|
||||
* @return The analog channel is attached to an accumulator.
|
||||
*/
|
||||
public boolean isAccumulatorChannel() {
|
||||
for (int i = 0; i < kAccumulatorChannels.length; i++) {
|
||||
if (m_channel == kAccumulatorChannels[i]) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the sample rate.
|
||||
*
|
||||
* This is a global setting for all channels.
|
||||
*
|
||||
* @param samplesPerSecond The number of samples per second.
|
||||
*/
|
||||
public static void setGlobalSampleRate(final double samplesPerSecond) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
AnalogJNI.setAnalogSampleRate((float)samplesPerSecond, status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current sample rate.
|
||||
*
|
||||
* This assumes one entry in the scan list. This is a global setting for
|
||||
* all channels.
|
||||
*
|
||||
* @return Sample rate.
|
||||
*/
|
||||
public static double getGlobalSampleRate() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double value = AnalogJNI.getAnalogSampleRate(status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the average value for use with PIDController
|
||||
*
|
||||
* @return the average value
|
||||
*/
|
||||
public double pidGet() {
|
||||
return getAverageValue();
|
||||
}
|
||||
|
||||
/**
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Analog Input";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAverageVoltage());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when entering the
|
||||
* LiveWindow. {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when exiting the
|
||||
* LiveWindow. {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,140 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.LongBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
//import com.sun.jna.Pointer;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Analog output class.
|
||||
*/
|
||||
public class AnalogOutput extends SensorBase implements LiveWindowSendable {
|
||||
private static Resource channels = new Resource(kAnalogOutputChannels);
|
||||
private ByteBuffer m_port;
|
||||
private int m_channel;
|
||||
|
||||
/**
|
||||
* Construct an analog output on a specified MXP channel.
|
||||
*
|
||||
* @param channel
|
||||
* The channel number to represent.
|
||||
*/
|
||||
public AnalogOutput(final int channel) {
|
||||
m_channel = channel;
|
||||
|
||||
if (AnalogJNI.checkAnalogOutputChannel(channel) == 0) {
|
||||
throw new AllocationException("Analog output channel " + m_channel
|
||||
+ " cannot be allocated. Channel is not present.");
|
||||
}
|
||||
try {
|
||||
channels.allocate(channel);
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException("Analog output channel " + m_channel
|
||||
+ " is already allocated");
|
||||
}
|
||||
|
||||
ByteBuffer port_pointer = AnalogJNI.getPort((byte)channel);
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_port = AnalogJNI.initializeAnalogOutputPort(port_pointer, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
LiveWindow.addSensor("AnalogOutput", channel, this);
|
||||
UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel, 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Channel destructor.
|
||||
*/
|
||||
public void free() {
|
||||
channels.free(m_channel);
|
||||
m_channel = 0;
|
||||
}
|
||||
|
||||
public void setVoltage(double voltage) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
AnalogJNI.setAnalogOutput(m_port, voltage, status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
public double getVoltage() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double voltage = AnalogJNI.getAnalogOutput(m_port, status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return voltage;
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Analog Output";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getVoltage());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when entering the
|
||||
* LiveWindow. {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when exiting the
|
||||
* LiveWindow. {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,198 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
import edu.wpi.first.wpilibj.interfaces.Potentiometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Class for reading analog potentiometers. Analog potentiometers read
|
||||
* in an analog voltage that corresponds to a position. Usually the
|
||||
* position is either degrees or meters. However, if no conversion is
|
||||
* given it remains volts.
|
||||
*
|
||||
* @author Alex Henning
|
||||
*/
|
||||
public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable {
|
||||
private double m_scale, m_offset;
|
||||
private AnalogInput m_analog_input;
|
||||
private boolean m_init_analog_input;
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
* @param input The {@link AnalogInput} this potentiometer is plugged into.
|
||||
* @param scale The scaling to multiply the voltage by to get a meaningful unit.
|
||||
* @param offset The offset to add to the scaled value for controlling the zero value
|
||||
*/
|
||||
private void initPot(final AnalogInput input, double scale, double offset) {
|
||||
this.m_scale = scale;
|
||||
this.m_offset = offset;
|
||||
m_analog_input = input;
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* Use the scaling and offset values so that the output produces
|
||||
* meaningful values. I.E: you have a 270 degree potentiometer and
|
||||
* you want the output to be degrees with the halfway point as 0
|
||||
* degrees. The scale value is 270.0(degrees)/5.0(volts) and the
|
||||
* offset is -135.0 since the halfway point after scaling is 135
|
||||
* degrees.
|
||||
*
|
||||
* @param channel The analog channel this potentiometer is plugged into.
|
||||
* @param scale The scaling to multiply the voltage by to get a meaningful unit.
|
||||
* @param offset The offset to add to the scaled value for controlling the zero value
|
||||
*/
|
||||
public AnalogPotentiometer(final int channel, double scale, double offset) {
|
||||
AnalogInput input = new AnalogInput(channel);
|
||||
m_init_analog_input = true;
|
||||
initPot(input, scale, offset);
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* Use the scaling and offset values so that the output produces
|
||||
* meaningful values. I.E: you have a 270 degree potentiometer and
|
||||
* you want the output to be degrees with the halfway point as 0
|
||||
* degrees. The scale value is 270.0(degrees)/5.0(volts) and the
|
||||
* offset is -135.0 since the halfway point after scaling is 135
|
||||
* degrees.
|
||||
*
|
||||
* @param input The {@link AnalogInput} this potentiometer is plugged into.
|
||||
* @param scale The scaling to multiply the voltage by to get a meaningful unit.
|
||||
* @param offset The offset to add to the scaled value for controlling the zero value
|
||||
*/
|
||||
public AnalogPotentiometer(final AnalogInput input, double scale, double offset) {
|
||||
m_init_analog_input = false;
|
||||
initPot(input, scale, offset);
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* Use the scaling and offset values so that the output produces
|
||||
* meaningful values. I.E: you have a 270 degree potentiometer and
|
||||
* you want the output to be degrees with the halfway point as 0
|
||||
* degrees. The scale value is 270.0(degrees)/5.0(volts) and the
|
||||
* offset is -135.0 since the halfway point after scaling is 135
|
||||
* degrees.
|
||||
*
|
||||
* @param channel The analog channel this potentiometer is plugged into.
|
||||
* @param scale The scaling to multiply the voltage by to get a meaningful unit.
|
||||
*/
|
||||
public AnalogPotentiometer(final int channel, double scale) {
|
||||
this(channel, scale, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* Use the scaling and offset values so that the output produces
|
||||
* meaningful values. I.E: you have a 270 degree potentiometer and
|
||||
* you want the output to be degrees with the halfway point as 0
|
||||
* degrees. The scale value is 270.0(degrees)/5.0(volts) and the
|
||||
* offset is -135.0 since the halfway point after scaling is 135
|
||||
* degrees.
|
||||
*
|
||||
* @param input The {@link AnalogInput} this potentiometer is plugged into.
|
||||
* @param scale The scaling to multiply the voltage by to get a meaningful unit.
|
||||
*/
|
||||
public AnalogPotentiometer(final AnalogInput input, double scale) {
|
||||
this(input, scale, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* @param channel The analog channel this potentiometer is plugged into.
|
||||
*/
|
||||
public AnalogPotentiometer(final int channel) {
|
||||
this(channel, 1, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* AnalogPotentiometer constructor.
|
||||
*
|
||||
* @param input The {@link AnalogInput} this potentiometer is plugged into.
|
||||
*/
|
||||
public AnalogPotentiometer(final AnalogInput input) {
|
||||
this(input, 1, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current reading of the potentiomere.
|
||||
*
|
||||
* @return The current position of the potentiometer.
|
||||
*/
|
||||
public double get() {
|
||||
return m_analog_input.getVoltage() * m_scale + m_offset;
|
||||
}
|
||||
|
||||
/**
|
||||
* Implement the PIDSource interface.
|
||||
*
|
||||
* @return The current reading.
|
||||
*/
|
||||
public double pidGet() {
|
||||
return get();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType(){
|
||||
return "Analog Input";
|
||||
}
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable(){
|
||||
return m_table;
|
||||
}
|
||||
|
||||
public void free(){
|
||||
if(m_init_analog_input){
|
||||
m_analog_input.free();
|
||||
m_analog_input = null;
|
||||
m_init_analog_input = false;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when entering the LiveWindow.
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {}
|
||||
|
||||
/**
|
||||
* Analog Channels don't have to do anything special when exiting the LiveWindow.
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {}
|
||||
}
|
||||
@@ -0,0 +1,224 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
//import com.sun.jna.Pointer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
* Class for creating and configuring Analog Triggers
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class AnalogTrigger implements IInputOutput {
|
||||
|
||||
/**
|
||||
* Exceptions dealing with improper operation of the Analog trigger
|
||||
*/
|
||||
public class AnalogTriggerException extends RuntimeException {
|
||||
|
||||
/**
|
||||
* Create a new exception with the given message
|
||||
*
|
||||
* @param message
|
||||
* the message to pass with the exception
|
||||
*/
|
||||
public AnalogTriggerException(String message) {
|
||||
super(message);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Where the analog trigger is attached
|
||||
*/
|
||||
protected ByteBuffer m_port;
|
||||
protected int m_index;
|
||||
|
||||
/**
|
||||
* Initialize an analog trigger from a channel.
|
||||
*
|
||||
* @param channel
|
||||
* the port to use for the analog trigger
|
||||
*/
|
||||
protected void initTrigger(final int channel) {
|
||||
ByteBuffer port_pointer = AnalogJNI.getPort((byte) channel);
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
IntBuffer index = IntBuffer.allocate(1);
|
||||
// XXX: Uncomment when analog has been fixed
|
||||
// m_port = HALLibrary
|
||||
// .initializeAnalogTrigger(port_pointer, index, status);
|
||||
//HALUtil.checkStatus(status);
|
||||
//m_index = index.get(0);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_AnalogTrigger, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for an analog trigger given a channel number.
|
||||
*
|
||||
* @param channel
|
||||
* the port to use for the analog trigger
|
||||
*/
|
||||
public AnalogTrigger(final int channel) {
|
||||
initTrigger(channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Construct an analog trigger given an analog channel. This should be used
|
||||
* in the case of sharing an analog channel between the trigger and an
|
||||
* analog input object.
|
||||
*
|
||||
* @param channel
|
||||
* the AnalogInput to use for the analog trigger
|
||||
*/
|
||||
public AnalogTrigger(AnalogInput channel) {
|
||||
initTrigger(channel.getChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the resources used by this object
|
||||
*/
|
||||
public void free() {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
AnalogJNI.cleanAnalogTrigger(m_port, status);
|
||||
HALUtil.checkStatus(status);
|
||||
m_port = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the upper and lower limits of the analog trigger. The limits are
|
||||
* given in ADC codes. If oversampling is used, the units must be scaled
|
||||
* appropriately.
|
||||
*
|
||||
* @param lower
|
||||
* the lower raw limit
|
||||
* @param upper
|
||||
* the upper raw limit
|
||||
*/
|
||||
public void setLimitsRaw(final int lower, final int upper) {
|
||||
if (lower > upper) {
|
||||
throw new BoundaryException("Lower bound is greater than upper");
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
AnalogJNI.setAnalogTriggerLimitsRaw(m_port, lower, upper, status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the upper and lower limits of the analog trigger. The limits are
|
||||
* given as floating point voltage values.
|
||||
*
|
||||
* @param lower
|
||||
* the lower voltage limit
|
||||
* @param upper
|
||||
* the upper voltage limit
|
||||
*/
|
||||
public void setLimitsVoltage(double lower, double upper) {
|
||||
if (lower > upper) {
|
||||
throw new BoundaryException(
|
||||
"Lower bound is greater than upper bound");
|
||||
}
|
||||
// TODO: This depends on the averaged setting. Only raw values will work
|
||||
// as is.
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
AnalogJNI.setAnalogTriggerLimitsVoltage(m_port, (float) lower,
|
||||
(float) upper, status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the analog trigger to use the averaged vs. raw values. If the
|
||||
* value is true, then the averaged value is selected for the analog
|
||||
* trigger, otherwise the immediate value is used.
|
||||
*
|
||||
* @param useAveragedValue
|
||||
* true to use an averaged value, false otherwise
|
||||
*/
|
||||
public void setAveraged(boolean useAveragedValue) {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
AnalogJNI.setAnalogTriggerAveraged(m_port,
|
||||
(byte) (useAveragedValue ? 1 : 0), status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the analog trigger to use a filtered value. The analog trigger
|
||||
* will operate with a 3 point average rejection filter. This is designed to
|
||||
* help with 360 degree pot applications for the period where the pot
|
||||
* crosses through zero.
|
||||
*
|
||||
* @param useFilteredValue
|
||||
* true to use a filterd value, false otherwise
|
||||
*/
|
||||
public void setFiltered(boolean useFilteredValue) {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
AnalogJNI.setAnalogTriggerFiltered(m_port,
|
||||
(byte) (useFilteredValue ? 1 : 0), status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the index of the analog trigger. This is the FPGA index of this
|
||||
* analog trigger instance.
|
||||
*
|
||||
* @return The index of the analog trigger.
|
||||
*/
|
||||
public int getIndex() {
|
||||
return m_index;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the InWindow output of the analog trigger. True if the analog
|
||||
* input is between the upper and lower limits.
|
||||
*
|
||||
* @return The InWindow output of the analog trigger.
|
||||
*/
|
||||
public boolean getInWindow() {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
byte value = AnalogJNI.getAnalogTriggerInWindow(m_port, status);
|
||||
HALUtil.checkStatus(status);
|
||||
return value != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the TriggerState output of the analog trigger. True if above upper
|
||||
* limit. False if below lower limit. If in Hysteresis, maintain previous
|
||||
* state.
|
||||
*
|
||||
* @return The TriggerState output of the analog trigger.
|
||||
*/
|
||||
public boolean getTriggerState() {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
byte value = AnalogJNI.getAnalogTriggerTriggerState(m_port, status);
|
||||
HALUtil.checkStatus(status);
|
||||
return value != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an AnalogTriggerOutput object. Gets an output object that can be
|
||||
* used for routing. Caller is responsible for deleting the
|
||||
* AnalogTriggerOutput object.
|
||||
*
|
||||
* @param type
|
||||
* An enum of the type of output object to create.
|
||||
* @return A pointer to a new AnalogTriggerOutput object.
|
||||
*/
|
||||
AnalogTriggerOutput createOutput(int type) {
|
||||
return new AnalogTriggerOutput(this, type);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,141 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Class to represent a specific output from an analog trigger. This class is
|
||||
* used to get the current output value and also as a DigitalSource to provide
|
||||
* routing of an output to digital subsystems on the FPGA such as Counter,
|
||||
* Encoder, and Interrupt.
|
||||
*
|
||||
* The TriggerState output indicates the primary output value of the trigger. If
|
||||
* the analog signal is less than the lower limit, the output is false. If the
|
||||
* analog value is greater than the upper limit, then the output is true. If the
|
||||
* analog value is in between, then the trigger output state maintains its most
|
||||
* recent value.
|
||||
*
|
||||
* The InWindow output indicates whether or not the analog signal is inside the
|
||||
* range defined by the limits.
|
||||
*
|
||||
* The RisingPulse and FallingPulse outputs detect an instantaneous transition
|
||||
* from above the upper limit to below the lower limit, and vise versa. These
|
||||
* pulses represent a rollover condition of a sensor and can be routed to an up
|
||||
* / down couter or to interrupts. Because the outputs generate a pulse, they
|
||||
* cannot be read directly. To help ensure that a rollover condition is not
|
||||
* missed, there is an average rejection filter available that operates on the
|
||||
* upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples.
|
||||
* This will reject a sample that is (due to averaging or sampling) errantly
|
||||
* between the two limits. This filter will fail if more than one sample in a
|
||||
* row is errantly in between the two limits. You may see this problem if
|
||||
* attempting to use this feature with a mechanical rollover sensor, such as a
|
||||
* 360 degree no-stop potentiometer without signal conditioning, because the
|
||||
* rollover transition is not sharp / clean enough. Using the averaging engine
|
||||
* may help with this, but rotational speeds of the sensor will then be limited.
|
||||
*/
|
||||
public class AnalogTriggerOutput extends DigitalSource implements IInputOutput {
|
||||
|
||||
/**
|
||||
* Exceptions dealing with improper operation of the Analog trigger output
|
||||
*/
|
||||
public class AnalogTriggerOutputException extends RuntimeException {
|
||||
|
||||
/**
|
||||
* Create a new exception with the given message
|
||||
*
|
||||
* @param message
|
||||
* the message to pass with the exception
|
||||
*/
|
||||
public AnalogTriggerOutputException(String message) {
|
||||
super(message);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
private AnalogTrigger m_trigger;
|
||||
private int m_outputType; // define in HALLibrary.AnalogTriggerType
|
||||
|
||||
/**
|
||||
* Create an object that represents one of the four outputs from an analog
|
||||
* trigger.
|
||||
*
|
||||
* Because this class derives from DigitalSource, it can be passed into
|
||||
* routing functions for Counter, Encoder, etc.
|
||||
*
|
||||
* @param trigger
|
||||
* The trigger for which this is an output.
|
||||
* @param outputType
|
||||
* An enum that specifies the output on the trigger to represent.
|
||||
*/
|
||||
public AnalogTriggerOutput(AnalogTrigger trigger, final int outputType) {
|
||||
if (trigger == null)
|
||||
throw new NullPointerException("Analog Trigger given was null");
|
||||
m_trigger = trigger;
|
||||
m_outputType = outputType;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_AnalogTriggerOutput,
|
||||
trigger.getIndex(), outputType);
|
||||
}
|
||||
|
||||
public void free() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the state of the analog trigger output.
|
||||
*
|
||||
* @return The state of the analog trigger output.
|
||||
*/
|
||||
public boolean get() {
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
byte value = AnalogJNI.getAnalogTriggerOutput(m_trigger.m_port,
|
||||
m_outputType, status);
|
||||
HALUtil.checkStatus(status);
|
||||
return value != 0;
|
||||
}
|
||||
|
||||
public int getChannelForRouting() {
|
||||
return (m_trigger.m_index << 2) + m_outputType;
|
||||
}
|
||||
|
||||
public int getModuleForRouting() {
|
||||
return m_trigger.m_index >> 2;
|
||||
}
|
||||
|
||||
public boolean getAnalogTriggerForRouting() {
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Request interrupts asynchronously on this digital input.
|
||||
*
|
||||
* @param handler
|
||||
* the interrupt service routine
|
||||
* @param param
|
||||
* a parameter for the ISR
|
||||
*/
|
||||
// public void requestInterrupts(/*tInterruptHandler*/Object handler, Object
|
||||
// param) {
|
||||
// TODO: add interrupt support
|
||||
// TODO: throw exception
|
||||
// }
|
||||
|
||||
/**
|
||||
* Request interrupts synchronously on this digital input.
|
||||
*/
|
||||
// public void requestInterrupts() {
|
||||
// TODO: throw exception
|
||||
// }
|
||||
}
|
||||
@@ -0,0 +1,114 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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;
|
||||
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;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Built-in accelerometer.
|
||||
*
|
||||
* This class allows access to the RoboRIO's internal accelerometer.
|
||||
*/
|
||||
public class BuiltInAccelerometer implements Accelerometer, ISensor, LiveWindowSendable
|
||||
{
|
||||
/**
|
||||
* 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) {
|
||||
case k2G:
|
||||
AccelerometerJNI.setAccelerometerRange(0);
|
||||
break;
|
||||
case k4G:
|
||||
AccelerometerJNI.setAccelerometerRange(1);
|
||||
break;
|
||||
case k8G:
|
||||
AccelerometerJNI.setAccelerometerRange(2);
|
||||
break;
|
||||
case k16G:
|
||||
throw new RuntimeException("16G range not supported (use k2G, k4G, or k8G)");
|
||||
}
|
||||
|
||||
AccelerometerJNI.setAccelerometerActive(true);
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the X axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getX() {
|
||||
return AccelerometerJNI.getAccelerometerX();
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the Y axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getY() {
|
||||
return AccelerometerJNI.getAccelerometerY();
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The acceleration of the RoboRIO along the Z axis in g-forces
|
||||
*/
|
||||
@Override
|
||||
public double getZ() {
|
||||
return AccelerometerJNI.getAccelerometerZ();
|
||||
}
|
||||
|
||||
public String getSmartDashboardType(){
|
||||
return "Accelerometer";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/** {@inheritDoc} */
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/** {@inheritDoc} */
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("X", getX());
|
||||
m_table.putNumber("Y", getY());
|
||||
m_table.putNumber("Z", getZ());
|
||||
}
|
||||
}
|
||||
|
||||
/** {@inheritDoc} */
|
||||
public ITable getTable(){
|
||||
return m_table;
|
||||
}
|
||||
|
||||
public void startLiveWindowMode() {}
|
||||
public void stopLiveWindowMode() {}
|
||||
};
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,119 @@
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.SensorBase;
|
||||
import edu.wpi.first.wpilibj.hal.CompressorJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IDevice;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
public class Compressor extends SensorBase implements IDevice, LiveWindowSendable {
|
||||
private ByteBuffer m_pcm;
|
||||
|
||||
public Compressor(int pcmId) {
|
||||
initCompressor(pcmId);
|
||||
}
|
||||
|
||||
public Compressor() {
|
||||
initCompressor(getDefaultSolenoidModule());
|
||||
}
|
||||
|
||||
private void initCompressor(int module) {
|
||||
m_table = null;
|
||||
|
||||
m_pcm = CompressorJNI.initializeCompressor((byte)module);
|
||||
}
|
||||
|
||||
public void start() {
|
||||
setClosedLoopControl(true);
|
||||
}
|
||||
|
||||
public void stop() {
|
||||
setClosedLoopControl(false);
|
||||
}
|
||||
|
||||
public boolean enabled() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
boolean on = CompressorJNI.getCompressor(m_pcm, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return on;
|
||||
}
|
||||
|
||||
public boolean getPressureSwitchValue() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
boolean on = CompressorJNI.getPressureSwitch(m_pcm, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return on;
|
||||
}
|
||||
|
||||
public float getCompressorCurrent() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
float current = CompressorJNI.getCompressorCurrent(m_pcm, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return current;
|
||||
}
|
||||
|
||||
public void setClosedLoopControl(boolean on) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
CompressorJNI.setClosedLoopControl(m_pcm, on, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
public boolean getClosedLoopControl() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
boolean on = CompressorJNI.getClosedLoopControl(m_pcm, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return on;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getSmartDashboardType() {
|
||||
return "Compressor";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Enabled", enabled());
|
||||
m_table.putBoolean("Pressure Switch", getPressureSwitchValue());
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,717 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.CounterJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
* Class for counting the number of ticks on a digital input channel. This is a
|
||||
* general purpose class for counting repetitive events. It can return the
|
||||
* number of counts, the period of the most recent cycle, and detect when the
|
||||
* signal being counted has stopped by supplying a maximum cycle time.
|
||||
*/
|
||||
public class Counter extends SensorBase implements CounterBase,
|
||||
LiveWindowSendable, PIDSource {
|
||||
|
||||
/**
|
||||
* Mode determines how and what the counter counts
|
||||
*/
|
||||
public static class Mode {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kTwoPulse_val = 0;
|
||||
static final int kSemiperiod_val = 1;
|
||||
static final int kPulseLength_val = 2;
|
||||
static final int kExternalDirection_val = 3;
|
||||
/**
|
||||
* mode: two pulse
|
||||
*/
|
||||
public static final Mode kTwoPulse = new Mode(kTwoPulse_val);
|
||||
/**
|
||||
* mode: semi period
|
||||
*/
|
||||
public static final Mode kSemiperiod = new Mode(kSemiperiod_val);
|
||||
/**
|
||||
* mode: pulse length
|
||||
*/
|
||||
public static final Mode kPulseLength = new Mode(kPulseLength_val);
|
||||
/**
|
||||
* mode: external direction
|
||||
*/
|
||||
public static final Mode kExternalDirection = new Mode(
|
||||
kExternalDirection_val);
|
||||
|
||||
private Mode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
private DigitalSource m_upSource; // /< What makes the counter count up.
|
||||
private DigitalSource m_downSource; // /< What makes the counter count down.
|
||||
private boolean m_allocatedUpSource;
|
||||
private boolean m_allocatedDownSource;
|
||||
private ByteBuffer m_counter; // /< The FPGA counter object.
|
||||
private int m_index; // /< The index of this counter.
|
||||
private PIDSourceParameter m_pidSource;
|
||||
private double m_distancePerPulse; // distance of travel for each tick
|
||||
|
||||
private void initCounter(final Mode mode) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_counter = CounterJNI.initializeCounter(mode.value, index.asIntBuffer(), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
m_index = index.asIntBuffer().get(0);
|
||||
|
||||
m_allocatedUpSource = false;
|
||||
m_allocatedDownSource = false;
|
||||
m_upSource = null;
|
||||
m_downSource = null;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Counter, m_index,
|
||||
mode.value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a counter where no sources are selected. Then they
|
||||
* all must be selected by calling functions to specify the upsource and the
|
||||
* downsource independently.
|
||||
*/
|
||||
public Counter() {
|
||||
initCounter(Mode.kTwoPulse);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a counter from a Digital Input. This is used if an
|
||||
* existing digital input is to be shared by multiple other objects such as
|
||||
* encoders.
|
||||
*
|
||||
* @param source
|
||||
* the digital source to count
|
||||
*/
|
||||
public Counter(DigitalSource source) {
|
||||
if (source == null)
|
||||
throw new NullPointerException("Source given was null");
|
||||
initCounter(Mode.kTwoPulse);
|
||||
setUpSource(source);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an up-Counter instance
|
||||
* given a channel.
|
||||
*
|
||||
* @param channel
|
||||
* the digital input channel to count
|
||||
*/
|
||||
public Counter(int channel) {
|
||||
initCounter(Mode.kTwoPulse);
|
||||
setUpSource(channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an instance of a simple
|
||||
* up-Counter given an analog trigger. Use the trigger state output from the
|
||||
* analog trigger.
|
||||
*
|
||||
* @param encodingType
|
||||
* which edges to count
|
||||
* @param upSource
|
||||
* first source to count
|
||||
* @param downSource
|
||||
* second source for direction
|
||||
* @param inverted
|
||||
* true to invert the count
|
||||
*/
|
||||
public Counter(EncodingType encodingType, DigitalSource upSource,
|
||||
DigitalSource downSource, boolean inverted) {
|
||||
initCounter(Mode.kExternalDirection);
|
||||
if (encodingType != EncodingType.k1X
|
||||
&& encodingType != EncodingType.k2X) {
|
||||
throw new RuntimeException(
|
||||
"Counters only support 1X and 2X quadreature decoding!");
|
||||
}
|
||||
if (upSource == null)
|
||||
throw new NullPointerException("Up Source given was null");
|
||||
setUpSource(upSource);
|
||||
if (downSource == null)
|
||||
throw new NullPointerException("Down Source given was null");
|
||||
setDownSource(downSource);
|
||||
|
||||
if (encodingType == null)
|
||||
throw new NullPointerException("Encoding type given was null");
|
||||
|
||||
if (encodingType == EncodingType.k1X) {
|
||||
setUpSourceEdge(true, false);
|
||||
} else {
|
||||
setUpSourceEdge(true, true);
|
||||
}
|
||||
|
||||
setDownSourceEdge(inverted, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Counter object. Create an instance of a simple
|
||||
* up-Counter given an analog trigger. Use the trigger state output from the
|
||||
* analog trigger.
|
||||
*
|
||||
* @param trigger
|
||||
* the analog trigger to count
|
||||
*/
|
||||
public Counter(AnalogTrigger trigger) {
|
||||
initCounter(Mode.kTwoPulse);
|
||||
setUpSource(trigger.createOutput(AnalogJNI.AnalogTriggerType.kState));
|
||||
}
|
||||
|
||||
public void free() {
|
||||
setUpdateWhenEmpty(true);
|
||||
|
||||
clearUpSource();
|
||||
clearDownSource();
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.freeCounter(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
m_upSource = null;
|
||||
m_downSource = null;
|
||||
m_counter = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the upsource for the counter as a digital input channel.
|
||||
*
|
||||
* @param channel
|
||||
* the digital port to count
|
||||
*/
|
||||
public void setUpSource(int channel) {
|
||||
setUpSource(new DigitalInput(channel));
|
||||
m_allocatedUpSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count up. Set the up
|
||||
* counting DigitalSource.
|
||||
*
|
||||
* @param source
|
||||
* the digital source to count
|
||||
*/
|
||||
public void setUpSource(DigitalSource source) {
|
||||
if (m_upSource != null && m_allocatedUpSource) {
|
||||
m_upSource.free();
|
||||
m_allocatedUpSource = false;
|
||||
}
|
||||
m_upSource = source;
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterUpSourceWithModule(m_counter,
|
||||
(byte) source.getModuleForRouting(),
|
||||
source.getChannelForRouting(),
|
||||
(byte) (source.getAnalogTriggerForRouting() ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the up counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger
|
||||
* The analog trigger object that is used for the Up Source
|
||||
* @param triggerType
|
||||
* The analog trigger output that will trigger the counter.
|
||||
*/
|
||||
public void setUpSource(AnalogTrigger analogTrigger, int triggerType) {
|
||||
analogTrigger.createOutput(triggerType);
|
||||
m_allocatedUpSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on an up counting source. Set the up source to
|
||||
* either detect rising edges or falling edges.
|
||||
*
|
||||
* @param risingEdge
|
||||
* true to count rising edge
|
||||
* @param fallingEdge
|
||||
* true to count falling edge
|
||||
*/
|
||||
public void setUpSourceEdge(boolean risingEdge, boolean fallingEdge) {
|
||||
if (m_upSource == null)
|
||||
throw new RuntimeException(
|
||||
"Up Source must be set before setting the edge!");
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterUpSourceEdge(m_counter,
|
||||
(byte) (risingEdge ? 1 : 0), (byte) (fallingEdge ? 1 : 0),
|
||||
status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable the up counting source to the counter.
|
||||
*/
|
||||
public void clearUpSource() {
|
||||
if (m_upSource != null && m_allocatedUpSource) {
|
||||
m_upSource.free();
|
||||
m_allocatedUpSource = false;
|
||||
}
|
||||
m_upSource = null;
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.clearCounterUpSource(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the down counting source to be a digital input channel.
|
||||
*
|
||||
* @param channel
|
||||
* the digital port to count
|
||||
*/
|
||||
public void setDownSource(int channel) {
|
||||
setDownSource(new DigitalInput(channel));
|
||||
m_allocatedDownSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the source object that causes the counter to count down. Set the down
|
||||
* counting DigitalSource.
|
||||
*
|
||||
* @param source
|
||||
* the digital source to count
|
||||
*/
|
||||
public void setDownSource(DigitalSource source) {
|
||||
if (m_downSource != null && m_allocatedDownSource) {
|
||||
m_downSource.free();
|
||||
m_allocatedDownSource = false;
|
||||
}
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterDownSourceWithModule(m_counter,
|
||||
(byte) source.getModuleForRouting(),
|
||||
source.getChannelForRouting(),
|
||||
(byte) (source.getAnalogTriggerForRouting() ? 1 : 0), status.asIntBuffer());
|
||||
if (status.asIntBuffer().get(0) == HALUtil.PARAMETER_OUT_OF_RANGE) {
|
||||
throw new IllegalArgumentException(
|
||||
"Counter only supports DownSource in TwoPulse and ExternalDirection modes.");
|
||||
}
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
m_downSource = source;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the down counting source to be an analog trigger.
|
||||
*
|
||||
* @param analogTrigger
|
||||
* The analog trigger object that is used for the Down Source
|
||||
* @param triggerType
|
||||
* The analog trigger output that will trigger the counter.
|
||||
*/
|
||||
public void setDownSource(AnalogTrigger analogTrigger, int triggerType) {
|
||||
setDownSource(analogTrigger.createOutput(triggerType));
|
||||
m_allocatedDownSource = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the edge sensitivity on a down counting source. Set the down source
|
||||
* to either detect rising edges or falling edges.
|
||||
*
|
||||
* @param risingEdge
|
||||
* true to count the rising edge
|
||||
* @param fallingEdge
|
||||
* true to count the falling edge
|
||||
*/
|
||||
public void setDownSourceEdge(boolean risingEdge, boolean fallingEdge) {
|
||||
if (m_downSource == null)
|
||||
throw new RuntimeException(
|
||||
" Down Source must be set before setting the edge!");
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterDownSourceEdge(m_counter, (byte) (risingEdge ? 1
|
||||
: 0), (byte) (fallingEdge ? 0 : 1), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable the down counting source to the counter.
|
||||
*/
|
||||
public void clearDownSource() {
|
||||
if (m_downSource != null && m_allocatedDownSource) {
|
||||
m_downSource.free();
|
||||
m_allocatedDownSource = false;
|
||||
}
|
||||
m_downSource = null;
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.clearCounterDownSource(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set standard up / down counting mode on this counter. Up and down counts
|
||||
* are sourced independently from two inputs.
|
||||
*/
|
||||
public void setUpDownCounterMode() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterUpDownMode(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set external direction mode on this counter. Counts are sourced on the Up
|
||||
* counter input. The Down counter input represents the direction to count.
|
||||
*/
|
||||
public void setExternalDirectionMode() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterExternalDirectionMode(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set Semi-period mode on this counter. Counts up on both rising and
|
||||
* falling edges.
|
||||
*
|
||||
* @param highSemiPeriod
|
||||
* true to count up on both rising and falling
|
||||
*/
|
||||
public void setSemiPeriodMode(boolean highSemiPeriod) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterSemiPeriodMode(m_counter,
|
||||
(byte) (highSemiPeriod ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the counter to count in up or down based on the length of the
|
||||
* input pulse. This mode is most useful for direction sensitive gear tooth
|
||||
* sensors.
|
||||
*
|
||||
* @param threshold
|
||||
* The pulse length beyond which the counter counts the opposite
|
||||
* direction. Units are seconds.
|
||||
*/
|
||||
public void setPulseLengthMode(double threshold) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterPulseLengthMode(m_counter, threshold,
|
||||
status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Start the Counter counting. This enables the counter and it starts
|
||||
* accumulating counts from the associated input channel. The counter value
|
||||
* is not reset on starting, and still has the previous value.
|
||||
*/
|
||||
public void start() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.startCounter(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current counter value. Read the value at this instant. It may
|
||||
* still be running, so it reflects the current value. Next time it is read,
|
||||
* it might have a different value.
|
||||
*/
|
||||
public int get() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = CounterJNI.getCounter(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current scaled counter value. Read the value at this instant,
|
||||
* scaled by the distance per pulse (defaults to 1).
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
public double getDistance() {
|
||||
return get() * m_distancePerPulse;
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the Counter to zero. Set the counter value to zero. This doesn't
|
||||
* effect the running state of the counter, just sets the current value to
|
||||
* zero.
|
||||
*/
|
||||
public void reset() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.resetCounter(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the Counter. Stops the counting but doesn't effect the current
|
||||
* value.
|
||||
*/
|
||||
public void stop() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.stopCounter(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the maximum period where the device is still considered "moving".
|
||||
* Sets the maximum period where the device is considered moving. This value
|
||||
* is used to determine the "stopped" state of the counter using the
|
||||
* GetStopped method.
|
||||
*
|
||||
* @param maxPeriod
|
||||
* The maximum period where the counted device is considered
|
||||
* moving in seconds.
|
||||
*/
|
||||
public void setMaxPeriod(double maxPeriod) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterMaxPeriod(m_counter, maxPeriod, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Select whether you want to continue updating the event timer output when
|
||||
* there are no samples captured. The output of the event timer has a buffer
|
||||
* of periods that are averaged and posted to a register on the FPGA. When
|
||||
* the timer detects that the event source has stopped (based on the
|
||||
* MaxPeriod) the buffer of samples to be averaged is emptied. If you enable
|
||||
* the update when empty, you will be notified of the stopped source and the
|
||||
* event time will report 0 samples. If you disable update when empty, the
|
||||
* most recent average will remain on the output until a new sample is
|
||||
* acquired. You will never see 0 samples output (except when there have
|
||||
* been no events since an FPGA reset) and you will likely not see the
|
||||
* stopped bit become true (since it is updated at the end of an average and
|
||||
* there are no samples to average).
|
||||
*
|
||||
* @param enabled
|
||||
* true to continue updating
|
||||
*/
|
||||
public void setUpdateWhenEmpty(boolean enabled) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterUpdateWhenEmpty(m_counter,
|
||||
(byte) (enabled ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the clock is stopped. Determine if the clocked input is
|
||||
* stopped based on the MaxPeriod value set using the SetMaxPeriod method.
|
||||
* If the clock exceeds the MaxPeriod, then the device (and counter) are
|
||||
* assumed to be stopped and it returns true.
|
||||
*
|
||||
* @return Returns true if the most recent counter period exceeds the
|
||||
* MaxPeriod value set by SetMaxPeriod.
|
||||
*/
|
||||
public boolean getStopped() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = CounterJNI.getCounterStopped(m_counter, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* The last direction the counter value changed.
|
||||
*
|
||||
* @return The last direction the counter value changed.
|
||||
*/
|
||||
public boolean getDirection() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = CounterJNI.getCounterDirection(m_counter, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Counter to return reversed sensing on the direction. This allows
|
||||
* counters to change the direction they are counting in the case of 1X and
|
||||
* 2X quadrature encoding only. Any other counter mode isn't supported.
|
||||
*
|
||||
* @param reverseDirection
|
||||
* true if the value counted should be negated.
|
||||
*/
|
||||
public void setReverseDirection(boolean reverseDirection) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterReverseDirection(m_counter,
|
||||
(byte) (reverseDirection ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Period of the most recent count. Returns the time interval of the
|
||||
* most recent count. This can be used for velocity calculations to
|
||||
* determine shaft speed.
|
||||
*
|
||||
* @returns The period of the last two pulses in units of seconds.
|
||||
*/
|
||||
public double getPeriod() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
double value = CounterJNI.getCounterPeriod(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current rate of the Counter. Read the current rate of the counter
|
||||
* accounting for the distance per pulse value. The default value for
|
||||
* distance per pulse (1) yields units of pulses per second.
|
||||
*
|
||||
* @return The rate in units/sec
|
||||
*/
|
||||
public double getRate() {
|
||||
return m_distancePerPulse / getPeriod();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
* @param samplesToAverage
|
||||
* The number of samples to average from 1 to 127.
|
||||
*/
|
||||
public void setSamplesToAverage(int samplesToAverage) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
CounterJNI.setCounterSamplesToAverage(m_counter, samplesToAverage,
|
||||
status.asIntBuffer());
|
||||
if (status.asIntBuffer().get(0) == HALUtil.PARAMETER_OUT_OF_RANGE) {
|
||||
throw new BoundaryException(BoundaryException.getMessage(
|
||||
samplesToAverage, 1, 127));
|
||||
}
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to
|
||||
* 127)
|
||||
*/
|
||||
public int getSamplesToAverage() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = CounterJNI.getCounterSamplesToAverage(m_counter, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the distance per pulse for this counter. This sets the multiplier
|
||||
* used to determine the distance driven based on the count value from the
|
||||
* encoder. Set this value based on the Pulses per Revolution and factor in
|
||||
* any gearing reductions. This distance can be in any units you like,
|
||||
* linear or angular.
|
||||
*
|
||||
* @param distancePerPulse
|
||||
* The scale factor that will be used to convert pulses to useful
|
||||
* units.
|
||||
*/
|
||||
public void setDistancePerPulse(double distancePerPulse) {
|
||||
m_distancePerPulse = distancePerPulse;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set which parameter of the encoder you are using as a process control
|
||||
* variable. The counter class supports the rate and distance parameters.
|
||||
*
|
||||
* @param pidSource
|
||||
* An enum to select the parameter.
|
||||
*/
|
||||
public void setPIDSourceParameter(PIDSourceParameter pidSource) {
|
||||
BoundaryException.assertWithinBounds(pidSource.value, 0, 1);
|
||||
m_pidSource = pidSource;
|
||||
}
|
||||
|
||||
public double pidGet() {
|
||||
switch (m_pidSource.value) {
|
||||
case PIDSourceParameter.kDistance_val:
|
||||
return getDistance();
|
||||
case PIDSourceParameter.kRate_val:
|
||||
return getRate();
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Counter";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,91 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
/**
|
||||
* Interface for counting the number of ticks on a digital input channel.
|
||||
* Encoders, Gear tooth sensors, and counters should all subclass this so it can be used to
|
||||
* build more advanced classes for control and driving.
|
||||
*/
|
||||
public interface CounterBase {
|
||||
|
||||
/**
|
||||
* The number of edges for the counterbase to increment or decrement on
|
||||
*/
|
||||
public static class EncodingType {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int k1X_val = 0;
|
||||
static final int k2X_val = 1;
|
||||
static final int k4X_val = 2;
|
||||
/**
|
||||
* Count only the rising edge
|
||||
*/
|
||||
public static final EncodingType k1X = new EncodingType(k1X_val);
|
||||
/**
|
||||
* Count both the rising and falling edge
|
||||
*/
|
||||
public static final EncodingType k2X = new EncodingType(k2X_val);
|
||||
/**
|
||||
* Count rising and falling on both channels
|
||||
*/
|
||||
public static final EncodingType k4X = new EncodingType(k4X_val);
|
||||
|
||||
private EncodingType(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Start the counter
|
||||
*/
|
||||
public void start();
|
||||
|
||||
/**
|
||||
* Get the count
|
||||
* @return the count
|
||||
*/
|
||||
int get();
|
||||
|
||||
/**
|
||||
* Reset the count to zero
|
||||
*/
|
||||
void reset();
|
||||
|
||||
/**
|
||||
* Stop counting
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Get the time between the last two edges counted
|
||||
* @return the time beteween the last two ticks in seconds
|
||||
*/
|
||||
double getPeriod();
|
||||
|
||||
/**
|
||||
* Set the maximum time between edges to be considered stalled
|
||||
* @param maxPeriod the maximum period in seconds
|
||||
*/
|
||||
void setMaxPeriod(double maxPeriod);
|
||||
|
||||
/**
|
||||
* Determine if the counter is not moving
|
||||
* @return true if the counter has not changed for the max period
|
||||
*/
|
||||
boolean getStopped();
|
||||
|
||||
/**
|
||||
* Determine which direction the counter is going
|
||||
* @return true for one direction, false for the other
|
||||
*/
|
||||
boolean getDirection();
|
||||
}
|
||||
@@ -0,0 +1,372 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.util.Stack;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Pack data into the "user data" field that gets sent to the dashboard laptop
|
||||
* via the driver station.
|
||||
*/
|
||||
public class Dashboard implements IDashboard, IInputOutput {
|
||||
|
||||
protected class MemAccess {
|
||||
|
||||
byte[] m_bytes;
|
||||
|
||||
protected MemAccess(byte[] bytes) {
|
||||
m_bytes = bytes;
|
||||
}
|
||||
|
||||
protected MemAccess(int length) {
|
||||
m_bytes = new byte[length];
|
||||
}
|
||||
|
||||
public void setByte(int index, byte value) {
|
||||
m_bytes[index] = value;
|
||||
}
|
||||
|
||||
public void setShort(int index, short value) {
|
||||
setByte(index++, (byte) (value >>> 8));
|
||||
setByte(index++, (byte) (value));
|
||||
}
|
||||
|
||||
public void setInt(int index, int value) {
|
||||
setByte(index++, (byte) (value >>> 24));
|
||||
setByte(index++, (byte) (value >>> 16));
|
||||
setByte(index++, (byte) (value >>> 8));
|
||||
setByte(index++, (byte) (value));
|
||||
}
|
||||
|
||||
public void setFloat(int index, float value) {
|
||||
setInt(index, Float.floatToIntBits(value));
|
||||
}
|
||||
|
||||
public void setDouble(int index, double value) {
|
||||
setInt(index, (int) (Double.doubleToLongBits(value) >>> 32));
|
||||
setInt(index + 4, (int) Double.doubleToLongBits(value));
|
||||
}
|
||||
|
||||
public void setString(int index, String value) {
|
||||
setBytes(index, value.getBytes(), 0, value.length());
|
||||
}
|
||||
|
||||
public void setBytes(int index, byte[] value, int offset, int number) {
|
||||
for (int i = 0; i < number; i++) {
|
||||
m_bytes[i + index] = value[i + offset];
|
||||
}
|
||||
}
|
||||
}
|
||||
private static final String kArray = "Array";
|
||||
private static final String kCluster = "Cluster";
|
||||
private static final Integer kByte = new Integer(0);
|
||||
private static final Integer kShort = new Integer(1);
|
||||
private static final Integer kInt = new Integer(2);
|
||||
private static final Integer kFloat = new Integer(3);
|
||||
private static final Integer kDouble = new Integer(4);
|
||||
private static final Integer kString = new Integer(5);
|
||||
private static final Integer kOther = new Integer(6);
|
||||
private static final Integer kBoolean = new Integer(7);
|
||||
private static final int kMaxDashboardDataSize = DriverStation.USER_STATUS_DATA_SIZE -
|
||||
4 * 3 - 1; // 13 bytes needed for 3 size parameters and the sequence number
|
||||
private static boolean m_reported = false;
|
||||
protected MemAccess m_userStatus;
|
||||
protected int m_userStatusSize = 0;
|
||||
private MemAccess m_localBuffer;
|
||||
private int m_packPtr;
|
||||
private Stack m_expectedArrayElementType = new Stack();
|
||||
private Stack m_arrayElementCount = new Stack();
|
||||
private Stack m_arraySizePtr = new Stack();
|
||||
private Stack m_complexTypeStack = new Stack();
|
||||
private final Object m_statusDataSemaphore;
|
||||
|
||||
/**
|
||||
* Dashboard constructor.
|
||||
*
|
||||
* This is only called once when the DriverStation constructor is called.
|
||||
* @param statusDataSemaphore the object to synchronize on
|
||||
*/
|
||||
protected Dashboard(Object statusDataSemaphore) {
|
||||
m_userStatus = new MemAccess(kMaxDashboardDataSize);
|
||||
m_localBuffer = new MemAccess(kMaxDashboardDataSize);
|
||||
m_packPtr = 0;
|
||||
m_statusDataSemaphore = statusDataSemaphore;
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a signed 8-bit int into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addByte(byte value) {
|
||||
if (!validateAdd(1)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setByte(m_packPtr, value);
|
||||
m_packPtr += 1;
|
||||
return addedElement(kByte);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a signed 16-bit int into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addShort(short value) {
|
||||
if (!validateAdd(2)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setShort(m_packPtr, value);
|
||||
m_packPtr += 2;
|
||||
return addedElement(kShort);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a signed 32-bit int into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addInt(int value) {
|
||||
if (!validateAdd(4)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setInt(m_packPtr, value);
|
||||
m_packPtr += 4;
|
||||
return addedElement(kInt);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a 32-bit floating point number into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addFloat(float value) {
|
||||
if (!validateAdd(4)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setFloat(m_packPtr, value);
|
||||
m_packPtr += 4;
|
||||
return addedElement(kFloat);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a 64-bit floating point number into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addDouble(double value) {
|
||||
if (!validateAdd(8)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setDouble(m_packPtr, value);
|
||||
m_packPtr += 8;
|
||||
return addedElement(kDouble);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a boolean into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addBoolean(boolean value) {
|
||||
if (!validateAdd(1)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setByte(m_packPtr, (byte) (value ? 1 : 0));
|
||||
m_packPtr += 1;
|
||||
return addedElement(kBoolean);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a NULL-terminated string of 8-bit characters into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addString(String value) {
|
||||
if (!validateAdd(value.length() + 4)) {
|
||||
return false;
|
||||
}
|
||||
m_localBuffer.setInt(m_packPtr, value.length());
|
||||
m_packPtr += 4;
|
||||
m_localBuffer.setString(m_packPtr, value);
|
||||
m_packPtr += value.length();
|
||||
return addedElement(kString);
|
||||
}
|
||||
|
||||
/**
|
||||
* Pack a string of 8-bit characters of specified length into the dashboard data structure.
|
||||
* @param value Data to be packed into the structure.
|
||||
* @param length The number of bytes in the string to pack.
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addString(String value, int length) {
|
||||
return addString(value.substring(0, length));
|
||||
}
|
||||
|
||||
/**
|
||||
* Start an array in the packed dashboard data structure.
|
||||
*
|
||||
* After calling addArray(), call the appropriate Add method for each element of the array.
|
||||
* Make sure you call the same add each time. An array must contain elements of the same type.
|
||||
* You can use clusters inside of arrays to make each element of the array contain a structure of values.
|
||||
* You can also nest arrays inside of other arrays.
|
||||
* Every call to addArray() must have a matching call to finalizeArray().
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addArray() {
|
||||
if (!validateAdd(4)) {
|
||||
return false;
|
||||
}
|
||||
m_complexTypeStack.push(kArray);
|
||||
m_arrayElementCount.push(new Integer(0));
|
||||
m_arraySizePtr.push(new Integer(m_packPtr));
|
||||
m_packPtr += 4;
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Indicate the end of an array packed into the dashboard data structure.
|
||||
*
|
||||
* After packing data into the array, call finalizeArray().
|
||||
* Every call to addArray() must have a matching call to finalizeArray().
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean finalizeArray() {
|
||||
if (m_complexTypeStack.peek() != kArray) {
|
||||
System.err.println("Attempted to finalize an array in the middle of a cluster or without starting the array");
|
||||
return false;
|
||||
}
|
||||
m_complexTypeStack.pop();
|
||||
m_localBuffer.setInt(((Integer) m_arraySizePtr.pop()).intValue(),
|
||||
((Integer) m_arrayElementCount.peek()).intValue());
|
||||
|
||||
|
||||
if (((Integer) m_arrayElementCount.peek()).intValue() != 0) {
|
||||
m_expectedArrayElementType.pop();
|
||||
}
|
||||
m_arrayElementCount.pop();
|
||||
return addedElement(kOther);
|
||||
}
|
||||
|
||||
/**
|
||||
* Start a cluster in the packed dashboard data structure.
|
||||
*
|
||||
* After calling addCluster(), call the appropriate Add method for each element of the cluster.
|
||||
* You can use clusters inside of arrays to make each element of the array contain a structure of values.
|
||||
* Every call to addCluster() must have a matching call to finalizeCluster().
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean addCluster() {
|
||||
m_complexTypeStack.push(kCluster);
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Indicate the end of a cluster packed into the dashboard data structure.
|
||||
*
|
||||
* After packing data into the cluster, call finalizeCluster().
|
||||
* Every call to addCluster() must have a matching call to finalizeCluster
|
||||
* @return True on success
|
||||
*/
|
||||
public boolean finalizeCluster() {
|
||||
if (m_complexTypeStack.peek() != kCluster) {
|
||||
System.err.println("Attempted to close a cluster on an open array or without starting the cluster");
|
||||
return false;
|
||||
}
|
||||
m_complexTypeStack.pop();
|
||||
return addedElement(kOther);
|
||||
}
|
||||
|
||||
/**
|
||||
* Indicate that the packing is complete and commit the buffer to the DriverStation.
|
||||
*
|
||||
* The packing of the dashboard packet is complete.
|
||||
* If you are not using the packed dashboard data, you can call commit() to commit the Printf() buffer and the error string buffer.
|
||||
* In effect, you are packing an empty structure.
|
||||
* Prepares a packet to go to the dashboard...
|
||||
* Pack the sequence number, Printf() buffer, the errors messages (not implemented yet), and packed dashboard data buffer.
|
||||
* @return The total size of the data packed into the userData field of the status packet.
|
||||
*/
|
||||
public synchronized int commit() {
|
||||
|
||||
if (!m_complexTypeStack.empty()) {
|
||||
System.err.println("didn't finish complex type");
|
||||
m_packPtr = 0;
|
||||
System.err.println("didn't finish complex type");
|
||||
return 0;
|
||||
}
|
||||
|
||||
if(!m_reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_Dashboard, 0);
|
||||
m_reported = true;
|
||||
}
|
||||
|
||||
synchronized (m_statusDataSemaphore) {
|
||||
// Sequence number
|
||||
DriverStation.getInstance().incrementUpdateNumber();
|
||||
|
||||
// Packed Dashboard Data
|
||||
m_userStatusSize = m_packPtr;
|
||||
m_userStatus.setBytes(0, m_localBuffer.m_bytes, 0, m_userStatusSize);
|
||||
m_packPtr = 0;
|
||||
|
||||
}
|
||||
return m_userStatusSize;
|
||||
}
|
||||
|
||||
/**
|
||||
* Validate that the data being packed will fit in the buffer.
|
||||
*/
|
||||
private boolean validateAdd(int size) {
|
||||
if (m_packPtr + size > kMaxDashboardDataSize) {
|
||||
m_packPtr = 0;
|
||||
System.err.println("Dashboard data is too long to send");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Check for consistent types when adding elements to an array and keep track of the number of elements in the array.
|
||||
*/
|
||||
private boolean addedElement(Integer type) {
|
||||
if (isArrayRoot()) {
|
||||
if (((Integer) m_arrayElementCount.peek()).intValue() == 0) {
|
||||
m_expectedArrayElementType.push(type);
|
||||
} else {
|
||||
if (type != m_expectedArrayElementType.peek()) {
|
||||
System.err.println("Attempted to add multiple datatypes to the same array");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
m_arrayElementCount.push(new Integer(((Integer) m_arrayElementCount.pop()).intValue() + 1));
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* If the top of the type stack an array?
|
||||
*/
|
||||
private boolean isArrayRoot() {
|
||||
return !m_complexTypeStack.empty() && m_complexTypeStack.peek() == kArray;
|
||||
}
|
||||
|
||||
public byte[] getBytes() {
|
||||
return m_userStatus.m_bytes;
|
||||
}
|
||||
|
||||
public int getBytesLength() {
|
||||
return m_userStatusSize;
|
||||
}
|
||||
|
||||
public void flush() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,204 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.InterruptJNI;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.InterruptJNI.InterruptHandlerFunction;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Class to read a digital input. This class will read digital inputs and return
|
||||
* the current value on the channel. Other devices such as encoders, gear tooth
|
||||
* sensors, etc. that are implemented elsewhere will automatically allocate
|
||||
* digital inputs and outputs as required. This class is only for devices like
|
||||
* switches etc. that aren't implemented anywhere else.
|
||||
*/
|
||||
public class DigitalInput extends DigitalSource implements IInputOutput,
|
||||
LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* Create an instance of a Digital Input class. Creates a digital input
|
||||
* given a channel.
|
||||
*
|
||||
* @param channel
|
||||
* the port for the digital input
|
||||
*/
|
||||
public DigitalInput(int channel) {
|
||||
initDigitalPort(channel, true);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_DigitalInput, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value from a digital input channel. Retrieve the value of a
|
||||
* single digital input channel from the FPGA.
|
||||
*
|
||||
* @return the stats of the digital input
|
||||
*/
|
||||
public boolean get() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = DIOJNI.getDIO(m_port, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the channel of the digital input
|
||||
*
|
||||
* @return The GPIO channel number that this object represents.
|
||||
*/
|
||||
public int getChannel() {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
public boolean getAnalogTriggerForRouting() {
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Request interrupts asynchronously on this digital input.
|
||||
*
|
||||
* @param handler
|
||||
* The address of the interrupt handler function of type
|
||||
* tInterruptHandler that will be called whenever there is an
|
||||
* interrupt on the digitial input port. Request interrupts in
|
||||
* synchronus mode where the user program interrupt handler will
|
||||
* be called when an interrupt occurs. The default is interrupt
|
||||
* on rising edges only.
|
||||
*/
|
||||
public void requestInterrupts(InterruptHandlerFunction handler) {
|
||||
// TODO: add interrupt support
|
||||
|
||||
try {
|
||||
m_interruptIndex = interrupts.allocate();
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException(
|
||||
"No interrupts are left to be allocated");
|
||||
}
|
||||
|
||||
allocateInterrupts(false);
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
InterruptJNI.requestInterrupts(m_interrupt, (byte) getModuleForRouting(),
|
||||
getChannelForRouting(),
|
||||
(byte) (getAnalogTriggerForRouting() ? 1 : 0), status.asIntBuffer());
|
||||
setUpSourceEdge(true, false);
|
||||
InterruptJNI.attachInterruptHandler(m_interrupt, handler, null, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Request interrupts synchronously on this digital input. Request
|
||||
* interrupts in synchronus mode where the user program will have to
|
||||
* explicitly wait for the interrupt to occur. The default is interrupt on
|
||||
* rising edges only.
|
||||
*/
|
||||
public void requestInterrupts() {
|
||||
try {
|
||||
m_interruptIndex = interrupts.allocate();
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException(
|
||||
"No interrupts are left to be allocated");
|
||||
}
|
||||
|
||||
allocateInterrupts(true);
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
InterruptJNI.requestInterrupts(m_interrupt, (byte) getModuleForRouting(),
|
||||
getChannelForRouting(),
|
||||
(byte) (getAnalogTriggerForRouting() ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
setUpSourceEdge(true, false);
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Set which edge to trigger interrupts on
|
||||
*
|
||||
* @param risingEdge
|
||||
* true to interrupt on rising edge
|
||||
* @param fallingEdge
|
||||
* true to interrupt on falling edge
|
||||
*/
|
||||
public void setUpSourceEdge(boolean risingEdge, boolean fallingEdge) {
|
||||
if (m_interrupt != null) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
InterruptJNI.setInterruptUpSourceEdge(m_interrupt,
|
||||
(byte) (risingEdge ? 1 : 0), (byte) (fallingEdge ? 1 : 0),
|
||||
status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
} else {
|
||||
throw new IllegalArgumentException(
|
||||
"You must call RequestInterrupts before setUpSourceEdge");
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Digital Input";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Value", get());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,266 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
//import com.sun.jna.Pointer;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.PWMJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Class to write digital outputs. This class will wrtie digital outputs. Other
|
||||
* devices that are implemented elsewhere will automatically allocate digital
|
||||
* inputs and outputs as required.
|
||||
*/
|
||||
public class DigitalOutput extends DigitalSource implements IInputOutput,
|
||||
LiveWindowSendable {
|
||||
|
||||
private ByteBuffer m_pwmGenerator;
|
||||
|
||||
/**
|
||||
* Create an instance of a digital output. Create an instance of a digital
|
||||
* output given a channel.
|
||||
*
|
||||
* @param channel
|
||||
* the port to use for the digital output
|
||||
*/
|
||||
public DigitalOutput(int channel) {
|
||||
initDigitalPort(channel, false);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_DigitalOutput, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the resources associated with a digital output.
|
||||
*/
|
||||
public void free() {
|
||||
// disable the pwm only if we have allocated it
|
||||
if (m_pwmGenerator != null) {
|
||||
disablePWM();
|
||||
}
|
||||
super.free();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the value of a digital output.
|
||||
*
|
||||
* @param value
|
||||
* true is on, off is false
|
||||
*/
|
||||
public void set(boolean value) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
DIOJNI.setDIO(m_port, (short) (value ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The GPIO channel number that this object represents.
|
||||
*/
|
||||
public int getChannel() {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Generate a single pulse. Write a pulse to the specified digital output
|
||||
* channel. There can only be a single pulse going at any time.
|
||||
*
|
||||
* @param channel
|
||||
* The channel to pulse.
|
||||
* @param pulseLength
|
||||
* The length of the pulse.
|
||||
*/
|
||||
public void pulse(final int channel, final float pulseLength) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
DIOJNI.pulse(m_port, pulseLength, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* @deprecated Generate a single pulse. Write a pulse to the specified
|
||||
* digital output channel. There can only be a single pulse
|
||||
* going at any time.
|
||||
*
|
||||
* @param channel
|
||||
* The channel to pulse.
|
||||
* @param pulseLength
|
||||
* The length of the pulse.
|
||||
*/
|
||||
public void pulse(final int channel, final int pulseLength) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
float convertedPulse = (float) (pulseLength / 1.0e9 * (DIOJNI.getLoopTiming(status.asIntBuffer()) * 25));
|
||||
System.err
|
||||
.println("You should use the float version of pulse for portability. This is deprecated");
|
||||
DIOJNI.pulse(m_port, convertedPulse, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the pulse is still going. Determine if a previously started
|
||||
* pulse is still going.
|
||||
*
|
||||
* @return true if pulsing
|
||||
*/
|
||||
public boolean isPulsing() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = DIOJNI.isPulsing(m_port, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the PWM frequency of the PWM output on a Digital Output line.
|
||||
*
|
||||
* The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is
|
||||
* logarithmic.
|
||||
*
|
||||
* There is only one PWM frequency for all channnels.
|
||||
*
|
||||
* @param rate The frequency to output all digital output PWM signals.
|
||||
*/
|
||||
public void setPWMRate(double rate) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
PWMJNI.setPWMRate(rate, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable a PWM Output on this line.
|
||||
*
|
||||
* Allocate one of the 4 DO PWM generator resources.
|
||||
*
|
||||
* Supply the initial duty-cycle to output so as to avoid a glitch when
|
||||
* first starting.
|
||||
*
|
||||
* The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
|
||||
* less) but is reduced the higher the frequency of the PWM signal is.
|
||||
*
|
||||
* @param initialDutyCycle
|
||||
* The duty-cycle to start generating. [0..1]
|
||||
*/
|
||||
public void enablePWM(double initialDutyCycle) {
|
||||
if (m_pwmGenerator == null)
|
||||
return;
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_pwmGenerator = PWMJNI.allocatePWM(status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
PWMJNI.setPWMDutyCycle(m_pwmGenerator, initialDutyCycle,
|
||||
status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
PWMJNI.setPWMOutputChannel(m_pwmGenerator, m_channel, status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Change this line from a PWM output back to a static Digital Output line.
|
||||
*
|
||||
* Free up one of the 4 DO PWM generator resources that were in use.
|
||||
*/
|
||||
public void disablePWM() {
|
||||
// Disable the output by routing to a dead bit.
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
PWMJNI.setPWMOutputChannel(m_pwmGenerator, kDigitalChannels, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
PWMJNI.freePWM(m_pwmGenerator, status.asIntBuffer());
|
||||
m_pwmGenerator = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Change the duty-cycle that is being generated on the line.
|
||||
*
|
||||
* The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
|
||||
* less) but is reduced the higher the frequency of the PWM signal is.
|
||||
*
|
||||
* @param dutyCycle
|
||||
* The duty-cycle to change to. [0..1]
|
||||
*/
|
||||
public void updateDutyCycle(double dutyCycle) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
PWMJNI.setPWMDutyCycle(m_pwmGenerator, dutyCycle, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Digital Output";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
// TODO: Put current value.
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value,
|
||||
boolean bln) {
|
||||
set(((Boolean) value).booleanValue());
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,93 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* DigitalSource Interface. The DigitalSource represents all the possible inputs
|
||||
* for a counter or a quadrature encoder. The source may be either a digital
|
||||
* input or an analog input. If the caller just provides a channel, then a
|
||||
* digital input will be constructed and freed when finished for the source. The
|
||||
* source can either be a digital input or analog trigger but not both.
|
||||
*/
|
||||
public abstract class DigitalSource extends InterruptableSensorBase {
|
||||
|
||||
protected static Resource channels = new Resource(kDigitalChannels);
|
||||
protected ByteBuffer m_port;
|
||||
protected int m_channel;
|
||||
|
||||
protected void initDigitalPort(int channel, boolean input) {
|
||||
|
||||
m_channel = channel;
|
||||
|
||||
checkDigitalChannel(m_channel); // XXX: Replace with
|
||||
// HALLibrary.checkDigitalChannel when
|
||||
// implemented
|
||||
|
||||
try {
|
||||
channels.allocate(m_channel);
|
||||
} catch (CheckedAllocationException ex) {
|
||||
throw new AllocationException("Digital input " + m_channel
|
||||
+ " is already allocated");
|
||||
}
|
||||
|
||||
ByteBuffer port_pointer = DIOJNI.getPort((byte) channel);
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_port = DIOJNI.initializeDigitalPort(port_pointer, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
DIOJNI.allocateDIO(m_port, (byte) (input ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
public void free() {
|
||||
channels.free(m_channel);
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
DIOJNI.freeDIO(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
m_channel = 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the channel routing number
|
||||
*
|
||||
* @return channel routing number
|
||||
*/
|
||||
public int getChannelForRouting() {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the module routing number
|
||||
*
|
||||
* @return 0
|
||||
*/
|
||||
public int getModuleForRouting() {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Is this an analog trigger
|
||||
*
|
||||
* @return true if this is an analog trigger
|
||||
*/
|
||||
public boolean getAnalogTriggerForRouting() {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,209 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* DoubleSolenoid class for running 2 channels of high voltage Digital Output
|
||||
* (9472 module).
|
||||
*
|
||||
* The DoubleSolenoid class is typically used for pneumatics solenoids that
|
||||
* have two positions controlled by two separate channels.
|
||||
*/
|
||||
public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* Possible values for a DoubleSolenoid
|
||||
*/
|
||||
public static class Value {
|
||||
|
||||
public final int value;
|
||||
public static final int kOff_val = 0;
|
||||
public static final int kForward_val = 1;
|
||||
public static final int kReverse_val = 2;
|
||||
public static final Value kOff = new Value(kOff_val);
|
||||
public static final Value kForward = new Value(kForward_val);
|
||||
public static final Value kReverse = new Value(kReverse_val);
|
||||
|
||||
private Value(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
private int m_forwardChannel; ///< The forward channel on the module to control.
|
||||
private int m_reverseChannel; ///< The reverse channel on the module to control.
|
||||
private byte m_forwardMask; ///< The mask for the forward channel.
|
||||
private byte m_reverseMask; ///< The mask for the reverse channel.
|
||||
|
||||
/**
|
||||
* Common function to implement constructor behavior.
|
||||
*/
|
||||
private synchronized void initSolenoid() {
|
||||
// checkSolenoidModule(m_moduleNumber);
|
||||
// checkSolenoidChannel(m_forwardChannel);
|
||||
// checkSolenoidChannel(m_reverseChannel);
|
||||
//
|
||||
// try {
|
||||
// m_allocated.allocate((m_moduleNumber - 1) * kSolenoidChannels + m_forwardChannel - 1);
|
||||
// } catch (CheckedAllocationException e) {
|
||||
// throw new AllocationException(
|
||||
// "Solenoid channel " + m_forwardChannel + " on module " + m_moduleNumber + " is already allocated");
|
||||
// }
|
||||
// try {
|
||||
// m_allocated.allocate((m_moduleNumber - 1) * kSolenoidChannels + m_reverseChannel - 1);
|
||||
// } catch (CheckedAllocationException e) {
|
||||
// throw new AllocationException(
|
||||
// "Solenoid channel " + m_reverseChannel + " on module " + m_moduleNumber + " is already allocated");
|
||||
// }
|
||||
// m_forwardMask = (byte) (1 << (m_forwardChannel - 1));
|
||||
// m_reverseMask = (byte) (1 << (m_reverseChannel - 1));
|
||||
//
|
||||
// UsageReporting.report(tResourceType.kResourceType_Solenoid, m_forwardChannel, m_moduleNumber-1);
|
||||
// UsageReporting.report(tResourceType.kResourceType_Solenoid, m_reverseChannel, m_moduleNumber-1);
|
||||
// LiveWindow.addActuator("DoubleSolenoid", m_moduleNumber, m_forwardChannel, this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param forwardChannel The forward channel on the module to control.
|
||||
* @param reverseChannel The reverse channel on the module to control.
|
||||
*/
|
||||
public DoubleSolenoid(final int forwardChannel, final int reverseChannel) {
|
||||
super(getDefaultSolenoidModule());
|
||||
m_forwardChannel = forwardChannel;
|
||||
m_reverseChannel = reverseChannel;
|
||||
initSolenoid();
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param moduleNumber The module number of the solenoid module to use.
|
||||
* @param forwardChannel The forward channel on the module to control.
|
||||
* @param reverseChannel The reverse channel on the module to control.
|
||||
*/
|
||||
public DoubleSolenoid(final int moduleNumber, final int forwardChannel, final int reverseChannel) {
|
||||
super(moduleNumber);
|
||||
m_forwardChannel = forwardChannel;
|
||||
m_reverseChannel = reverseChannel;
|
||||
initSolenoid();
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
public synchronized void free() {
|
||||
// m_allocated.free((m_moduleNumber - 1) * kSolenoidChannels + m_forwardChannel - 1);
|
||||
// m_allocated.free((m_moduleNumber - 1) * kSolenoidChannels + m_reverseChannel - 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the value of a solenoid.
|
||||
*
|
||||
* @param value Move the solenoid to forward, reverse, or don't move it.
|
||||
*/
|
||||
public void set(final Value value) {
|
||||
byte rawValue = 0;
|
||||
|
||||
switch (value.value) {
|
||||
case Value.kOff_val:
|
||||
rawValue = 0x00;
|
||||
break;
|
||||
case Value.kForward_val:
|
||||
rawValue = m_forwardMask;
|
||||
break;
|
||||
case Value.kReverse_val:
|
||||
rawValue = m_reverseMask;
|
||||
break;
|
||||
}
|
||||
|
||||
set(rawValue, m_forwardMask | m_reverseMask);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current value of the solenoid.
|
||||
*
|
||||
* @return The current value of the solenoid.
|
||||
*/
|
||||
public Value get() {
|
||||
byte value = getAll();
|
||||
|
||||
if ((value & m_forwardMask) != 0) return Value.kForward;
|
||||
if ((value & m_reverseMask) != 0) return Value.kReverse;
|
||||
return Value.kOff;
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Double Solenoid";
|
||||
}
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
//TODO: this is bad
|
||||
m_table.putString("Value", (get() == Value.kForward ? "Forward" : (get() == Value.kReverse ? "Reverse" : "Off")));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
set(Value.kOff); // Stop for safety
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value, boolean bln) {
|
||||
//TODO: this is bad also
|
||||
if (value.toString().equals("Reverse"))
|
||||
set(Value.kReverse);
|
||||
else if (value.toString().equals("Forward"))
|
||||
set(Value.kForward);
|
||||
else
|
||||
set(Value.kOff);
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
set(Value.kOff); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,641 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
|
||||
import edu.wpi.first.wpilibj.communication.FRCCommonControlData;
|
||||
import edu.wpi.first.wpilibj.communication.FRCCommonControlMasks;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Provide access to the network communication data to / from the Driver Station.
|
||||
*/
|
||||
public class DriverStation implements IInputOutput, RobotState.Interface {
|
||||
|
||||
/**
|
||||
* The size of the user status data
|
||||
*/
|
||||
public static final int USER_STATUS_DATA_SIZE = FRCNetworkCommunicationsLibrary.USER_STATUS_DATA_SIZE;
|
||||
/**
|
||||
* Slot for the analog module to read the battery
|
||||
*/
|
||||
public static final int kBatterySlot = 1;
|
||||
/**
|
||||
* Analog channel to read the battery
|
||||
*/
|
||||
public static final int kBatteryChannel = 7;
|
||||
/**
|
||||
* Number of Joystick Ports
|
||||
*/
|
||||
public static final int kJoystickPorts = 4;
|
||||
/**
|
||||
* Number of Joystick Axes
|
||||
*/
|
||||
public static final int kJoystickAxes = 6;
|
||||
/**
|
||||
* Convert from raw values to volts
|
||||
*/
|
||||
public static final double kDSAnalogInScaling = 5.0 / 1023.0;
|
||||
|
||||
/**
|
||||
* The robot alliance that the robot is a part of
|
||||
*/
|
||||
public static class Alliance {
|
||||
|
||||
/** The integer value representing this enumeration. */
|
||||
public final int value;
|
||||
/** The Alliance name. */
|
||||
public final String name;
|
||||
public static final int kRed_val = 0;
|
||||
public static final int kBlue_val = 1;
|
||||
public static final int kInvalid_val = 2;
|
||||
/** alliance: Red */
|
||||
public static final Alliance kRed = new Alliance(kRed_val, "Red");
|
||||
/** alliance: Blue */
|
||||
public static final Alliance kBlue = new Alliance(kBlue_val, "Blue");
|
||||
/** alliance: Invalid */
|
||||
public static final Alliance kInvalid = new Alliance(kInvalid_val, "invalid");
|
||||
|
||||
private Alliance(int value, String name) {
|
||||
this.value = value;
|
||||
this.name = name;
|
||||
}
|
||||
} /* Alliance */
|
||||
|
||||
|
||||
private static class DriverStationTask implements Runnable {
|
||||
|
||||
private DriverStation m_ds;
|
||||
|
||||
DriverStationTask(DriverStation ds) {
|
||||
m_ds = ds;
|
||||
}
|
||||
|
||||
public void run() {
|
||||
m_ds.task();
|
||||
}
|
||||
} /* DriverStationTask */
|
||||
|
||||
private static DriverStation instance = new DriverStation();
|
||||
private FRCCommonControlData m_controlData;
|
||||
private AnalogInput m_batteryChannel;
|
||||
private Thread m_thread;
|
||||
private final Object m_semaphore;
|
||||
private final Object m_dataSem;
|
||||
private int m_digitalOut;
|
||||
private volatile boolean m_thread_keepalive = true;
|
||||
private final Dashboard m_dashboardDefaultHigh;
|
||||
private final Dashboard m_dashboardDefaultLow;
|
||||
private IDashboard m_dashboardInUseHigh;
|
||||
private IDashboard m_dashboardInUseLow;
|
||||
private int m_updateNumber = 0;
|
||||
private double m_approxMatchTimeOffset = -1.0;
|
||||
private boolean m_userInDisabled = false;
|
||||
private boolean m_userInAutonomous = false;
|
||||
private boolean m_userInTeleop = false;
|
||||
private boolean m_userInTest = false;
|
||||
private boolean m_newControlData;
|
||||
private final ByteBuffer m_packetDataAvailableSem;
|
||||
|
||||
/**
|
||||
* Gets an instance of the DriverStation
|
||||
*
|
||||
* @return The DriverStation.
|
||||
*/
|
||||
public static DriverStation getInstance() {
|
||||
return DriverStation.instance;
|
||||
}
|
||||
|
||||
/**
|
||||
* DriverStation constructor.
|
||||
*
|
||||
* The single DriverStation instance is created statically with the
|
||||
* instance static member variable.
|
||||
*/
|
||||
protected DriverStation() {
|
||||
m_controlData = new FRCCommonControlData();
|
||||
m_semaphore = new Object();
|
||||
m_dataSem = new Object();
|
||||
|
||||
m_dashboardInUseHigh = m_dashboardDefaultHigh = new Dashboard(m_semaphore);
|
||||
m_dashboardInUseLow = m_dashboardDefaultLow = new Dashboard(m_semaphore);
|
||||
|
||||
// m_controlData is initialized in constructor FRCCommonControlData.
|
||||
|
||||
// XXX: Uncomment when analogChannel is fixed
|
||||
//m_batteryChannel = new AnalogChannel(kBatterySlot, kBatteryChannel);
|
||||
|
||||
m_packetDataAvailableSem = HALUtil.initializeMutexNormal();
|
||||
|
||||
// set the byte order
|
||||
m_packetDataAvailableSem.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
FRCNetworkCommunicationsLibrary.setNewDataSem(m_packetDataAvailableSem);
|
||||
|
||||
m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation");
|
||||
m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2);
|
||||
|
||||
m_thread.start();
|
||||
}
|
||||
|
||||
/**
|
||||
* Kill the thread
|
||||
*/
|
||||
public void release() {
|
||||
m_thread_keepalive = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Provides the service routine for the DS polling thread.
|
||||
*/
|
||||
private void task() {
|
||||
int safetyCounter = 0;
|
||||
while (m_thread_keepalive) {
|
||||
HALUtil.takeMutex(m_packetDataAvailableSem);
|
||||
synchronized (this) {
|
||||
getData();
|
||||
setData();
|
||||
}
|
||||
synchronized (m_dataSem) {
|
||||
m_dataSem.notifyAll();
|
||||
}
|
||||
if (++safetyCounter >= 5) {
|
||||
// System.out.println("Checking safety");
|
||||
MotorSafetyHelper.checkMotors();
|
||||
safetyCounter = 0;
|
||||
}
|
||||
if (m_userInDisabled) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramDisabled();
|
||||
}
|
||||
if (m_userInAutonomous) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramAutonomous();
|
||||
}
|
||||
if (m_userInTeleop) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTeleop();
|
||||
}
|
||||
if (m_userInTest) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTest();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Wait for new data from the driver station.
|
||||
*/
|
||||
public void waitForData() {
|
||||
waitForData(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Wait for new data or for timeout, which ever comes first. If timeout is
|
||||
* 0, wait for new data only.
|
||||
*
|
||||
* @param timeout The maximum time in milliseconds to wait.
|
||||
*/
|
||||
public void waitForData(long timeout) {
|
||||
synchronized (m_dataSem) {
|
||||
try {
|
||||
m_dataSem.wait(timeout);
|
||||
} catch (InterruptedException ex) {
|
||||
}
|
||||
}
|
||||
}
|
||||
private static boolean lastEnabled = false;
|
||||
|
||||
/**
|
||||
* Copy data from the DS task for the user.
|
||||
* If no new data exists, it will just be returned, otherwise
|
||||
* the data will be copied from the DS polling loop.
|
||||
*/
|
||||
protected synchronized void getData() {
|
||||
FRCNetworkCommunicationsLibrary.getCommonControlData(m_controlData);
|
||||
|
||||
if (!lastEnabled && isEnabled()) {
|
||||
// If starting teleop, assume that autonomous just took up 15 seconds
|
||||
if (isAutonomous()) {
|
||||
m_approxMatchTimeOffset = Timer.getFPGATimestamp();
|
||||
} else {
|
||||
m_approxMatchTimeOffset = Timer.getFPGATimestamp() - 15.0;
|
||||
}
|
||||
} else if (lastEnabled && !isEnabled()) {
|
||||
m_approxMatchTimeOffset = -1.0;
|
||||
}
|
||||
lastEnabled = isEnabled();
|
||||
|
||||
m_newControlData = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Copy status data from the DS task for the user.
|
||||
* This is used primarily to set digital outputs on the DS.
|
||||
*/
|
||||
protected void setData() {
|
||||
synchronized (m_semaphore) {
|
||||
FRCNetworkCommunicationsLibrary.setStatusData((float) getBatteryVoltage(),
|
||||
(byte) m_digitalOut,
|
||||
(byte) m_updateNumber,
|
||||
new String(m_dashboardInUseHigh.getBytes()),
|
||||
m_dashboardInUseHigh.getBytesLength(),
|
||||
new String(m_dashboardInUseLow.getBytes()),
|
||||
m_dashboardInUseLow.getBytesLength());
|
||||
m_dashboardInUseHigh.flush();
|
||||
m_dashboardInUseLow.flush();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the battery voltage from the specified AnalogChannel.
|
||||
*
|
||||
* This accessor assumes that the battery voltage is being measured
|
||||
* through the voltage divider on an analog breakout.
|
||||
*
|
||||
* @return The battery voltage.
|
||||
*/
|
||||
public double getBatteryVoltage() {
|
||||
// The Analog bumper has a voltage divider on the battery source.
|
||||
// Vbatt *--/\/\/\--* Vsample *--/\/\/\--* Gnd
|
||||
// 680 Ohms 1000 Ohms
|
||||
// XXX: Uncomment this when analog channel is fixed
|
||||
//return m_batteryChannel.getAverageVoltage() * (1680.0 / 1000.0);
|
||||
return 12.0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of the axis on a joystick.
|
||||
* This depends on the mapping of the joystick connected to the specified port.
|
||||
*
|
||||
* @param stick The joystick to read.
|
||||
* @param axis The analog axis value to read from the joystick.
|
||||
* @return The value of the axis on the joystick.
|
||||
*/
|
||||
public double getStickAxis(int stick, int axis) {
|
||||
if (axis < 1 || axis > kJoystickAxes) {
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
int value;
|
||||
switch (stick) {
|
||||
case 1:
|
||||
value = m_controlData.stick0Axes[axis - 1];
|
||||
break;
|
||||
case 2:
|
||||
value = m_controlData.stick1Axes[axis - 1];
|
||||
break;
|
||||
case 3:
|
||||
value = m_controlData.stick2Axes[axis - 1];
|
||||
break;
|
||||
case 4:
|
||||
value = m_controlData.stick3Axes[axis - 1];
|
||||
break;
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
double result;
|
||||
if (value < 0) {
|
||||
result = ((double) value) / 128.0;
|
||||
} else {
|
||||
result = ((double) value) / 127.0;
|
||||
}
|
||||
|
||||
// wpi_assert(result <= 1.0 && result >= -1.0);
|
||||
if (result > 1.0) {
|
||||
result = 1.0;
|
||||
} else if (result < -1.0) {
|
||||
result = -1.0;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* The state of the buttons on the joystick.
|
||||
* 12 buttons (4 msb are unused) from the joystick.
|
||||
*
|
||||
* @param stick The joystick to read.
|
||||
* @return The state of the buttons on the joystick.
|
||||
*/
|
||||
public int getStickButtons(final int stick) {
|
||||
switch (stick) {
|
||||
case 1:
|
||||
return m_controlData.stick0Buttons;
|
||||
case 2:
|
||||
return m_controlData.stick1Buttons;
|
||||
case 3:
|
||||
return m_controlData.stick2Buttons;
|
||||
case 4:
|
||||
return m_controlData.stick3Buttons;
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get an analog voltage from the Driver Station.
|
||||
* The analog values are returned as voltage values for the Driver Station analog inputs.
|
||||
* These inputs are typically used for advanced operator interfaces consisting of potentiometers
|
||||
* or resistor networks representing values on a rotary switch.
|
||||
*
|
||||
* @param channel The analog input channel on the driver station to read from. Valid range is 1 - 4.
|
||||
* @return The analog voltage on the input.
|
||||
*/
|
||||
public double getAnalogIn(final int channel) {
|
||||
switch (channel) {
|
||||
case 1:
|
||||
return kDSAnalogInScaling * m_controlData.analog1;
|
||||
case 2:
|
||||
return kDSAnalogInScaling * m_controlData.analog2;
|
||||
case 3:
|
||||
return kDSAnalogInScaling * m_controlData.analog3;
|
||||
case 4:
|
||||
return kDSAnalogInScaling * m_controlData.analog4;
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get values from the digital inputs on the Driver Station.
|
||||
* Return digital values from the Drivers Station. These values are typically used for buttons
|
||||
* and switches on advanced operator interfaces.
|
||||
* @param channel The digital input to get. Valid range is 1 - 8.
|
||||
* @return The value of the digital input
|
||||
*/
|
||||
public boolean getDigitalIn(final int channel) {
|
||||
return ((m_controlData.dsDigitalIn >> (channel - 1)) & 0x1) == 0x1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set a value for the digital outputs on the Driver Station.
|
||||
*
|
||||
* Control digital outputs on the Drivers Station. These values are typically used for
|
||||
* giving feedback on a custom operator station such as LEDs.
|
||||
*
|
||||
* @param channel The digital output to set. Valid range is 1 - 8.
|
||||
* @param value The state to set the digital output.
|
||||
*/
|
||||
public void setDigitalOut(final int channel, final boolean value) {
|
||||
m_digitalOut &= ~(0x1 << (channel - 1));
|
||||
m_digitalOut |= ((value ? 1 : 0) << (channel - 1));
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a value that was set for the digital outputs on the Driver Station.
|
||||
* @param channel The digital ouput to monitor. Valid range is 1 through 8.
|
||||
* @return A digital value being output on the Drivers Station.
|
||||
*/
|
||||
public boolean getDigitalOut(final int channel) {
|
||||
return ((m_digitalOut >> (channel - 1)) & 0x1) == 0x1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the
|
||||
* robot to be enabled.
|
||||
*
|
||||
* @return True if the robot is enabled, false otherwise.
|
||||
*/
|
||||
public boolean isEnabled() {
|
||||
return (m_controlData.control & FRCCommonControlMasks.ENABLED) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the
|
||||
* robot to be disabled.
|
||||
*
|
||||
* @return True if the robot should be disabled, false otherwise.
|
||||
*/
|
||||
public boolean isDisabled() {
|
||||
return !isEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the
|
||||
* robot to be running in autonomous mode.
|
||||
*
|
||||
* @return True if autonomous mode should be enabled, false otherwise.
|
||||
*/
|
||||
public boolean isAutonomous() {
|
||||
return (m_controlData.control & FRCCommonControlMasks.AUTONOMOUS) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the
|
||||
* robot to be running in test mode.
|
||||
* @return True if test mode should be enabled, false otherwise.
|
||||
*/
|
||||
public boolean isTest() {
|
||||
return (m_controlData.control & FRCCommonControlMasks.TEST) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets a value indicating whether the Driver Station requires the
|
||||
* robot to be running in operator-controlled mode.
|
||||
*
|
||||
* @return True if operator-controlled mode should be enabled, false otherwise.
|
||||
*/
|
||||
public boolean isOperatorControl() {
|
||||
return !(isAutonomous() || isTest());
|
||||
}
|
||||
|
||||
/**
|
||||
* Has a new control packet from the driver station arrived since the last time this function was called?
|
||||
* @return True if the control data has been updated since the last call.
|
||||
*/
|
||||
public synchronized boolean isNewControlData() {
|
||||
boolean result = m_newControlData;
|
||||
m_newControlData = false;
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the DS packet number.
|
||||
* The packet number is the index of this set of data returned by the driver station.
|
||||
* Each time new data is received, the packet number (included with the sent data) is returned.
|
||||
*
|
||||
* @return The DS packet number.
|
||||
*/
|
||||
public int getPacketNumber() {
|
||||
return m_controlData.packetIndex;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current alliance from the FMS
|
||||
* @return the current alliance
|
||||
*/
|
||||
public Alliance getAlliance() {
|
||||
switch (m_controlData.dsID_Alliance) {
|
||||
case 'R':
|
||||
return Alliance.kRed;
|
||||
case 'B':
|
||||
return Alliance.kBlue;
|
||||
default:
|
||||
return Alliance.kInvalid;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the location of the team's driver station controls.
|
||||
*
|
||||
* @return the location of the team's driver station controls: 1, 2, or 3
|
||||
*/
|
||||
public int getLocation() {
|
||||
return m_controlData.dsID_Position - '0';
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the team number that the Driver Station is configured for
|
||||
* @return The team number
|
||||
*/
|
||||
public int getTeamNumber() {
|
||||
return m_controlData.teamID;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the dashboard packer to use for sending high priority user data to a
|
||||
* dashboard receiver. This can idle or restore the default packer.
|
||||
* (Initializing SmartDashboard sets the high priority packer in use, so
|
||||
* beware that the default packer will then be idle. You can restore the
|
||||
* default high priority packer by calling
|
||||
* {@code setDashboardPackerToUseHigh(getDashboardPackerHigh())}.)
|
||||
*
|
||||
* @param dashboard any kind of IDashboard object
|
||||
*/
|
||||
public void setDashboardPackerToUseHigh(IDashboard dashboard) {
|
||||
m_dashboardInUseHigh = dashboard;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the default dashboard packer for sending high priority user data to
|
||||
* a dashboard receiver. This instance stays around even after a call to
|
||||
* {@link #setDashboardPackerToUseHigh} changes which packer is in use.
|
||||
*
|
||||
* @return the default Dashboard object; it may be idle
|
||||
*/
|
||||
public Dashboard getDashboardPackerHigh() {
|
||||
return m_dashboardDefaultHigh;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the dashboard packer that's currently in use for sending high
|
||||
* priority user data to a dashboard receiver. This can be any kind of
|
||||
* IDashboard.
|
||||
*
|
||||
* @return the current IDashboard object
|
||||
*/
|
||||
public IDashboard getDashboardPackerInUseHigh() {
|
||||
return m_dashboardInUseHigh;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the dashboard packer to use for sending low priority user data to a
|
||||
* dashboard receiver. This can idle or restore the default packer.
|
||||
*
|
||||
* @param dashboard any kind of IDashboard object
|
||||
*/
|
||||
public void setDashboardPackerToUseLow(IDashboard dashboard) {
|
||||
m_dashboardInUseLow = dashboard;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the default dashboard packer for sending low priority user data to
|
||||
* a dashboard receiver. This instance stays around even after a call to
|
||||
* {@link #setDashboardPackerToUseLow} changes which packer is in use.
|
||||
*
|
||||
* @return the default Dashboard object; it may be idle
|
||||
*/
|
||||
public Dashboard getDashboardPackerLow() {
|
||||
return m_dashboardDefaultLow;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the dashboard packer that's currently in use for sending low
|
||||
* priority user data to a dashboard receiver. This can be any kind of
|
||||
* IDashboard.
|
||||
*
|
||||
* @return the current IDashboard object
|
||||
*/
|
||||
public IDashboard getDashboardPackerInUseLow() {
|
||||
return m_dashboardInUseLow;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the status data monitor
|
||||
* @return The status data monitor for use with IDashboard objects which must
|
||||
* send data across the network.
|
||||
*/
|
||||
public Object getStatusDataMonitor() {
|
||||
return m_semaphore;
|
||||
}
|
||||
|
||||
/**
|
||||
* Increments the internal update number sent across the network along with
|
||||
* status data.
|
||||
*/
|
||||
void incrementUpdateNumber() {
|
||||
synchronized (m_semaphore) {
|
||||
m_updateNumber++;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Is the driver station attached to a Field Management System?
|
||||
* Note: This does not work with the Blue DS.
|
||||
* @return True if the robot is competing on a field being controlled by a Field Management System
|
||||
*/
|
||||
public boolean isFMSAttached() {
|
||||
return (m_controlData.control & FRCCommonControlMasks.FMS_ATTATCHED) > 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the approximate match time
|
||||
* The FMS does not currently send the official match time to the robots
|
||||
* This returns the time since the enable signal sent from the Driver Station
|
||||
* At the beginning of autonomous, the time is reset to 0.0 seconds
|
||||
* At the beginning of teleop, the time is reset to +15.0 seconds
|
||||
* If the robot is disabled, this returns 0.0 seconds
|
||||
* Warning: This is not an official time (so it cannot be used to argue with referees)
|
||||
* @return Match time in seconds since the beginning of autonomous
|
||||
*/
|
||||
public double getMatchTime() {
|
||||
if (m_approxMatchTimeOffset < 0.0) {
|
||||
return 0.0;
|
||||
}
|
||||
return Timer.getFPGATimestamp() - m_approxMatchTimeOffset;
|
||||
}
|
||||
|
||||
/** Only to be used to tell the Driver Station what code you claim to be executing
|
||||
* for diagnostic purposes only
|
||||
* @param entering If true, starting disabled code; if false, leaving disabled code */
|
||||
public void InDisabled(boolean entering) {
|
||||
m_userInDisabled=entering;
|
||||
}
|
||||
|
||||
/** Only to be used to tell the Driver Station what code you claim to be executing
|
||||
* for diagnostic purposes only
|
||||
* @param entering If true, starting autonomous code; if false, leaving autonomous code */
|
||||
public void InAutonomous(boolean entering) {
|
||||
m_userInAutonomous=entering;
|
||||
}
|
||||
|
||||
/** Only to be used to tell the Driver Station what code you claim to be executing
|
||||
* for diagnostic purposes only
|
||||
* @param entering If true, starting teleop code; if false, leaving teleop code */
|
||||
public void InOperatorControl(boolean entering) {
|
||||
m_userInTeleop=entering;
|
||||
}
|
||||
|
||||
/** Only to be used to tell the Driver Station what code you claim to be executing
|
||||
* for diagnostic purposes only
|
||||
* @param entering If true, starting test code; if false, leaving test code */
|
||||
public void InTest(boolean entering) {
|
||||
m_userInTeleop = entering;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,198 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Provide access to "LCD" on the Driver Station.
|
||||
* This is the Messages box on the DS Operation tab.
|
||||
*
|
||||
* Buffer the printed data locally and then send it
|
||||
* when UpdateLCD is called.
|
||||
*/
|
||||
public class DriverStationLCD extends SensorBase implements IInputOutput {
|
||||
|
||||
private static DriverStationLCD m_instance;
|
||||
/**
|
||||
* Driver station timeout in milliseconds
|
||||
*/
|
||||
public static final int kSyncTimeout_ms = 20;
|
||||
/**
|
||||
* Command to display text
|
||||
*/
|
||||
public static final int kFullDisplayTextCommand = 0x9FFF;
|
||||
/**
|
||||
* Maximum line length for Driver Station display
|
||||
*/
|
||||
public static final int kLineLength = 21;
|
||||
/**
|
||||
* Total number of lines available
|
||||
*/
|
||||
public static final int kNumLines = 6;
|
||||
|
||||
/**
|
||||
* The line number on the Driver Station LCD
|
||||
*/
|
||||
public static class Line {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kMain6_val = 0;
|
||||
static final int kUser1_val = 0;
|
||||
static final int kUser2_val = 1;
|
||||
static final int kUser3_val = 2;
|
||||
static final int kUser4_val = 3;
|
||||
static final int kUser5_val = 4;
|
||||
static final int kUser6_val = 5;
|
||||
/**
|
||||
* @deprecated Use kUser1
|
||||
* Line at the Top of the screen
|
||||
*/
|
||||
public static final Line kMain6 = new Line(kMain6_val);
|
||||
/**
|
||||
* Line at the Top of the screen
|
||||
*/
|
||||
public static final Line kUser1 = new Line(kUser1_val);
|
||||
/**
|
||||
* Line on the user screen
|
||||
*/
|
||||
public static final Line kUser2 = new Line(kUser2_val);
|
||||
/**
|
||||
* Line on the user screen
|
||||
*/
|
||||
public static final Line kUser3 = new Line(kUser3_val);
|
||||
/**
|
||||
* Line on the user screen
|
||||
*/
|
||||
public static final Line kUser4 = new Line(kUser4_val);
|
||||
/**
|
||||
* Line on the user screen
|
||||
*/
|
||||
public static final Line kUser5 = new Line(kUser5_val);
|
||||
/**
|
||||
* Bottom line on the user screen
|
||||
*/
|
||||
public static final Line kUser6 = new Line(kUser6_val);
|
||||
|
||||
private Line(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
byte[] m_textBuffer;
|
||||
|
||||
/**
|
||||
* Get an instance of the DriverStationLCD
|
||||
* @return an instance of the DriverStationLCD
|
||||
*/
|
||||
public static synchronized DriverStationLCD getInstance() {
|
||||
if (m_instance == null)
|
||||
m_instance = new DriverStationLCD();
|
||||
return m_instance;
|
||||
}
|
||||
|
||||
/**
|
||||
* DriverStationLCD constructor.
|
||||
*
|
||||
* This is only called once the first time GetInstance() is called
|
||||
*/
|
||||
private DriverStationLCD() {
|
||||
m_textBuffer = new byte[FRCNetworkCommunicationsLibrary.USER_DS_LCD_DATA_SIZE];
|
||||
|
||||
for (int i = 0; i < FRCNetworkCommunicationsLibrary.USER_DS_LCD_DATA_SIZE; i++) {
|
||||
m_textBuffer[i] = ' ';
|
||||
}
|
||||
|
||||
m_textBuffer[0] = (byte) (kFullDisplayTextCommand >> 8);
|
||||
m_textBuffer[1] = (byte) kFullDisplayTextCommand;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_DriverStationLCD, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send the text data to the Driver Station.
|
||||
*/
|
||||
public synchronized void updateLCD() {
|
||||
FRCNetworkCommunicationsLibrary.setUserDsLcdData(new String(m_textBuffer), FRCNetworkCommunicationsLibrary.USER_DS_LCD_DATA_SIZE, kSyncTimeout_ms);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print formatted text to the Driver Station LCD text buffer.
|
||||
*
|
||||
* Use UpdateLCD() periodically to actually send the test to the Driver Station.
|
||||
*
|
||||
* @param line The line on the LCD to print to.
|
||||
* @param startingColumn The column to start printing to. This is a 1-based number.
|
||||
* @param text the text to print
|
||||
*/
|
||||
public void println(Line line, int startingColumn, String text) {
|
||||
int start = startingColumn - 1;
|
||||
int maxLength = kLineLength - start;
|
||||
|
||||
if (startingColumn < 1 || startingColumn > kLineLength) {
|
||||
throw new IndexOutOfBoundsException("Column must be between 1 and " + kLineLength + ", inclusive");
|
||||
}
|
||||
|
||||
int length = text.length();
|
||||
int finalLength = (length < maxLength ? length : maxLength);
|
||||
synchronized (this) {
|
||||
for (int i = 0; i < finalLength; i++) {
|
||||
m_textBuffer[i + start + line.value * kLineLength + 2] = (byte)text.charAt(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Print formatted text to the Driver Station LCD text buffer.
|
||||
*
|
||||
* Use UpdateLCD() periodically to actually send the test to the Driver Station.
|
||||
*
|
||||
* @param line The line on the LCD to print to.
|
||||
* @param startingColumn The column to start printing to. This is a 1-based number.
|
||||
* @param text the text to print
|
||||
*/
|
||||
public void println(Line line, int startingColumn, StringBuffer text) {
|
||||
int start = startingColumn - 1;
|
||||
int maxLength = kLineLength - start;
|
||||
|
||||
if (startingColumn < 1 || startingColumn > kLineLength) {
|
||||
throw new IndexOutOfBoundsException("Column must be between 1 and " + kLineLength + ", inclusive");
|
||||
}
|
||||
|
||||
int length = text.length();
|
||||
int finalLength = (length < maxLength ? length : maxLength);
|
||||
synchronized (this) {
|
||||
for (int i = 0; i < finalLength; i++) {
|
||||
m_textBuffer[i + start + line.value * kLineLength + 2] = (byte) text.charAt(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear User Messages box on DS Operations Tab
|
||||
*
|
||||
* This method will clear all text currently displayed in the message box
|
||||
*/
|
||||
public void clear() {
|
||||
synchronized (this) {
|
||||
for (int i=0; i < kLineLength*kNumLines; i++) {
|
||||
m_textBuffer[i+2] = ' ';
|
||||
}
|
||||
}
|
||||
updateLCD();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,768 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
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.hal.EncoderJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
* Class to read quad encoders. Quadrature encoders are devices that count shaft
|
||||
* rotation and can sense direction. The output of the QuadEncoder class is an
|
||||
* integer that can count either up or down, and can go negative for reverse
|
||||
* direction counting. When creating QuadEncoders, a direction is supplied that
|
||||
* changes the sense of the output to make code more readable if the encoder is
|
||||
* mounted such that forward movement generates negative values. Quadrature
|
||||
* encoders have two digital outputs, an A Channel and a B Channel that are out
|
||||
* of phase with each other to allow the FPGA to do direction sensing.
|
||||
*/
|
||||
public class Encoder extends SensorBase implements CounterBase, PIDSource,
|
||||
ISensor, LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* The a source
|
||||
*/
|
||||
protected DigitalSource m_aSource; // the A phase of the quad encoder
|
||||
/**
|
||||
* The b source
|
||||
*/
|
||||
protected DigitalSource m_bSource; // the B phase of the quad encoder
|
||||
/**
|
||||
* The index source
|
||||
*/
|
||||
protected DigitalSource m_indexSource = null; // Index on some encoders
|
||||
private ByteBuffer m_encoder;
|
||||
private int m_index;
|
||||
private double m_distancePerPulse; // distance of travel for each encoder
|
||||
// tick
|
||||
private Counter m_counter; // Counter object for 1x and 2x encoding
|
||||
private EncodingType m_encodingType = EncodingType.k4X;
|
||||
private boolean m_allocatedA;
|
||||
private boolean m_allocatedB;
|
||||
private boolean m_allocatedI;
|
||||
private PIDSourceParameter m_pidSource;
|
||||
|
||||
/**
|
||||
* Common initialization code for Encoders. This code allocates resources
|
||||
* for Encoders and is common to all constructors.
|
||||
*
|
||||
* @param reverseDirection
|
||||
* If true, counts down instead of up (this is all relative)
|
||||
* @param 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.
|
||||
*/
|
||||
private void initEncoder(boolean reverseDirection) {
|
||||
switch (m_encodingType.value) {
|
||||
case EncodingType.k4X_val:
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
ByteBuffer index = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
index.order(ByteOrder.LITTLE_ENDIAN);
|
||||
m_encoder = EncoderJNI.initializeEncoder(
|
||||
(byte) m_aSource.getModuleForRouting(),
|
||||
m_aSource.getChannelForRouting(),
|
||||
(byte) (m_aSource.getAnalogTriggerForRouting() ? 1 : 0),
|
||||
(byte) m_bSource.getModuleForRouting(),
|
||||
m_bSource.getChannelForRouting(),
|
||||
(byte) (m_bSource.getAnalogTriggerForRouting() ? 1 : 0),
|
||||
(byte) (reverseDirection ? 1 : 0), index.asIntBuffer(), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
m_index = index.asIntBuffer().get(0);
|
||||
m_counter = null;
|
||||
break;
|
||||
case EncodingType.k2X_val:
|
||||
case EncodingType.k1X_val:
|
||||
m_counter = new Counter(m_encodingType, m_aSource, m_bSource,
|
||||
reverseDirection);
|
||||
break;
|
||||
}
|
||||
m_distancePerPulse = 1.0;
|
||||
m_pidSource = PIDSourceParameter.kDistance;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Encoder,
|
||||
m_index, m_encodingType.value);
|
||||
LiveWindow.addSensor("Encoder", m_aSource.getChannelForRouting(), this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
* The b channel digital input channel.
|
||||
* @param reverseDirection
|
||||
* represents the orientation of the encoder and inverts the
|
||||
* output values if necessary so forward represents positive
|
||||
* values.
|
||||
*/
|
||||
public Encoder(final int aChannel, final int bChannel,
|
||||
boolean reverseDirection) {
|
||||
m_allocatedA = true;
|
||||
m_allocatedB = true;
|
||||
m_allocatedI = false;
|
||||
m_aSource = new DigitalInput(aChannel);
|
||||
m_bSource = new DigitalInput(bChannel);
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
* The b channel digital input channel.
|
||||
*/
|
||||
public Encoder(final int aChannel, final int bChannel) {
|
||||
this(aChannel, bChannel, false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
* The b channel digital input channel.
|
||||
* @param reverseDirection
|
||||
* represents the orientation of the encoder and inverts the
|
||||
* output values if necessary so forward represents positive
|
||||
* values.
|
||||
* @param 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(final int aChannel, final int bChannel,
|
||||
boolean reverseDirection, final EncodingType encodingType) {
|
||||
m_allocatedA = true;
|
||||
m_allocatedB = true;
|
||||
m_allocatedI = false;
|
||||
if (encodingType == null)
|
||||
throw new NullPointerException("Given encoding type was null");
|
||||
m_encodingType = encodingType;
|
||||
m_aSource = new DigitalInput(aChannel);
|
||||
m_bSource = new DigitalInput(bChannel);
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
* Using an index pulse forces 4x encoding
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
* The b channel digital input channel.
|
||||
* @param indexChannel
|
||||
* The index channel digital input channel.
|
||||
* @param reverseDirection
|
||||
* represents the orientation of the encoder and inverts the
|
||||
* output values if necessary so forward represents positive
|
||||
* values.
|
||||
*/
|
||||
public Encoder(final int aChannel, final int bChannel,
|
||||
final int indexChannel, boolean reverseDirection) {
|
||||
m_allocatedA = true;
|
||||
m_allocatedB = true;
|
||||
m_allocatedI = true;
|
||||
m_aSource = new DigitalInput(aChannel);
|
||||
m_bSource = new DigitalInput(bChannel);
|
||||
m_indexSource = new DigitalInput(indexChannel);
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels.
|
||||
* Using an index pulse forces 4x encoding
|
||||
*
|
||||
* @param aChannel
|
||||
* The a channel digital input channel.
|
||||
* @param bChannel
|
||||
* The b channel digital input channel.
|
||||
* @param indexChannel
|
||||
* The index channel digital input channel.
|
||||
*/
|
||||
public Encoder(final int aChannel, final int bChannel,
|
||||
final int indexChannel) {
|
||||
this(aChannel, bChannel, indexChannel, false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels as
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
* the source that should be used for the b channel.
|
||||
* @param 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,
|
||||
boolean reverseDirection) {
|
||||
m_allocatedA = false;
|
||||
m_allocatedB = false;
|
||||
m_allocatedI = false;
|
||||
if (aSource == null)
|
||||
throw new NullPointerException("Digital Source A was null");
|
||||
m_aSource = aSource;
|
||||
if (bSource == null)
|
||||
throw new NullPointerException("Digital Source B was null");
|
||||
m_bSource = bSource;
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels as
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
* the source that should be used for the b channel.
|
||||
*/
|
||||
public Encoder(DigitalSource aSource, DigitalSource bSource) {
|
||||
this(aSource, bSource, false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels as
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
* the source that should be used for the b channel.
|
||||
* @param reverseDirection
|
||||
* represents the orientation of the encoder and inverts the
|
||||
* output values if necessary so forward represents positive
|
||||
* values.
|
||||
* @param 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,
|
||||
boolean reverseDirection, final EncodingType encodingType) {
|
||||
m_allocatedA = false;
|
||||
m_allocatedB = false;
|
||||
m_allocatedI = false;
|
||||
if (encodingType == null)
|
||||
throw new NullPointerException("Given encoding type was null");
|
||||
m_encodingType = encodingType;
|
||||
if (aSource == null)
|
||||
throw new NullPointerException("Digital Source A was null");
|
||||
m_aSource = aSource;
|
||||
if (bSource == null)
|
||||
throw new NullPointerException("Digital Source B was null");
|
||||
m_aSource = aSource;
|
||||
m_bSource = bSource;
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels as
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
* the source that should be used for the b channel.
|
||||
* @param indexSource
|
||||
* the source that should be used for the index channel.
|
||||
* @param 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, boolean reverseDirection) {
|
||||
m_allocatedA = false;
|
||||
m_allocatedB = false;
|
||||
m_allocatedI = false;
|
||||
if (aSource == null)
|
||||
throw new NullPointerException("Digital Source A was null");
|
||||
m_aSource = aSource;
|
||||
if (bSource == null)
|
||||
throw new NullPointerException("Digital Source B was null");
|
||||
m_aSource = aSource;
|
||||
m_bSource = bSource;
|
||||
m_indexSource = indexSource;
|
||||
initEncoder(reverseDirection);
|
||||
}
|
||||
|
||||
/**
|
||||
* Encoder constructor. Construct a Encoder given a and b channels as
|
||||
* digital inputs. This is used in the case where the digital inputs are
|
||||
* shared. The Encoder class will not allocate the digital inputs and assume
|
||||
* that they already are counted.
|
||||
*
|
||||
* @param aSource
|
||||
* The source that should be used for the a channel.
|
||||
* @param bSource
|
||||
* the source that should be used for the b channel.
|
||||
* @param indexSource
|
||||
* the source that should be used for the index channel.
|
||||
*/
|
||||
public Encoder(DigitalSource aSource, DigitalSource bSource,
|
||||
DigitalSource indexSource) {
|
||||
this(aSource, bSource, indexSource, false);
|
||||
}
|
||||
|
||||
public void free() {
|
||||
if (m_aSource != null && m_allocatedA) {
|
||||
m_aSource.free();
|
||||
m_allocatedA = false;
|
||||
}
|
||||
if (m_bSource != null && m_allocatedB) {
|
||||
m_bSource.free();
|
||||
m_allocatedB = false;
|
||||
}
|
||||
if (m_indexSource != null && m_allocatedI) {
|
||||
m_indexSource.free();
|
||||
m_allocatedI = false;
|
||||
}
|
||||
|
||||
m_aSource = null;
|
||||
m_bSource = null;
|
||||
m_indexSource = null;
|
||||
if (m_counter != null) {
|
||||
m_counter.free();
|
||||
m_counter = null;
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.freeEncoder(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Start the Encoder. Starts counting pulses on the Encoder device.
|
||||
*/
|
||||
public void start() {
|
||||
if (m_counter != null) {
|
||||
m_counter.start();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.startEncoder(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Stops counting pulses on the Encoder device. The value is not changed.
|
||||
*/
|
||||
public void stop() {
|
||||
if (m_counter != null) {
|
||||
m_counter.stop();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.stopEncoder(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the raw value from the encoder. The raw value is the actual count
|
||||
* unscaled by the 1x, 2x, or 4x scale factor.
|
||||
*
|
||||
* @return Current raw count from the encoder
|
||||
*/
|
||||
public int getRaw() {
|
||||
int value;
|
||||
if (m_counter != null) {
|
||||
value = m_counter.get();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
value = EncoderJNI.getEncoder(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the current count. Returns the current count on the Encoder. This
|
||||
* method compensates for the decoding type.
|
||||
*
|
||||
* @return Current count from the Encoder adjusted for the 1x, 2x, or 4x
|
||||
* scale factor.
|
||||
*/
|
||||
public int get() {
|
||||
return (int) (getRaw() * decodingScaleFactor());
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the Encoder distance to zero. Resets the current count to zero on
|
||||
* the encoder.
|
||||
*/
|
||||
public void reset() {
|
||||
if (m_counter != null) {
|
||||
m_counter.reset();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.resetEncoder(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the period of the most recent pulse. Returns the period of the
|
||||
* most recent Encoder pulse in seconds. This method compensates for the
|
||||
* decoding type.
|
||||
*
|
||||
* @deprecated Use getRate() in favor of this method. This returns unscaled
|
||||
* periods and getRate() scales using value from
|
||||
* setDistancePerPulse().
|
||||
*
|
||||
* @return Period in seconds of the most recent pulse.
|
||||
*/
|
||||
public double getPeriod() {
|
||||
double measuredPeriod;
|
||||
if (m_counter != null) {
|
||||
measuredPeriod = m_counter.getPeriod();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
measuredPeriod = EncoderJNI.getEncoderPeriod(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
return measuredPeriod / decodingScaleFactor();
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the maximum period for stopped detection. Sets the value that
|
||||
* represents the maximum period of the Encoder before it will assume that
|
||||
* the attached device is stopped. This timeout allows users to determine if
|
||||
* the wheels or other shaft has stopped rotating. This method compensates
|
||||
* for the decoding type.
|
||||
*
|
||||
*
|
||||
* @param maxPeriod
|
||||
* The maximum time between rising and falling edges before the
|
||||
* FPGA will report the device stopped. This is expressed in
|
||||
* seconds.
|
||||
*/
|
||||
public void setMaxPeriod(double maxPeriod) {
|
||||
if (m_counter != null) {
|
||||
m_counter.setMaxPeriod(maxPeriod * decodingScaleFactor());
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.setEncoderMaxPeriod(m_encoder, maxPeriod, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the encoder is stopped. Using the MaxPeriod value, a boolean
|
||||
* is returned that is true if the encoder is considered stopped and false
|
||||
* if it is still moving. A stopped encoder is one where the most recent
|
||||
* pulse width exceeds the MaxPeriod.
|
||||
*
|
||||
* @return True if the encoder is considered stopped.
|
||||
*/
|
||||
public boolean getStopped() {
|
||||
if (m_counter != null) {
|
||||
return m_counter.getStopped();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = EncoderJNI.getEncoderStopped(m_encoder, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The last direction the encoder value changed.
|
||||
*
|
||||
* @return The last direction the encoder value changed.
|
||||
*/
|
||||
public boolean getDirection() {
|
||||
if (m_counter != null) {
|
||||
return m_counter.getDirection();
|
||||
} else {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = EncoderJNI.getEncoderDirection(m_encoder, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The scale needed to convert a raw counter value into a number of encoder
|
||||
* pulses.
|
||||
*/
|
||||
private double decodingScaleFactor() {
|
||||
switch (m_encodingType.value) {
|
||||
case EncodingType.k1X_val:
|
||||
return 1.0;
|
||||
case EncodingType.k2X_val:
|
||||
return 0.5;
|
||||
case EncodingType.k4X_val:
|
||||
return 0.25;
|
||||
default:
|
||||
// This is never reached, EncodingType enum limits values
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the distance the robot has driven since the last reset.
|
||||
*
|
||||
* @return The distance driven since the last reset as scaled by the value
|
||||
* from setDistancePerPulse().
|
||||
*/
|
||||
public double getDistance() {
|
||||
return getRaw() * decodingScaleFactor() * m_distancePerPulse;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current rate of the encoder. Units are distance per second as
|
||||
* scaled by the value from setDistancePerPulse().
|
||||
*
|
||||
* @return The current rate of the encoder.
|
||||
*/
|
||||
public double getRate() {
|
||||
return m_distancePerPulse / getPeriod();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the minimum rate of the device before the hardware reports it
|
||||
* stopped.
|
||||
*
|
||||
* @param minRate
|
||||
* The minimum rate. The units are in distance per second as
|
||||
* scaled by the value from setDistancePerPulse().
|
||||
*/
|
||||
public void setMinRate(double minRate) {
|
||||
setMaxPeriod(m_distancePerPulse / minRate);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the distance per pulse for this encoder. This sets the multiplier
|
||||
* used to determine the distance driven based on the count value from the
|
||||
* encoder. Do not include the decoding type in this scale. The library
|
||||
* already compensates for the decoding type. Set this value based on the
|
||||
* encoder's rated Pulses per Revolution and factor in gearing reductions
|
||||
* following the encoder shaft. This distance can be in any units you like,
|
||||
* linear or angular.
|
||||
*
|
||||
* @param distancePerPulse
|
||||
* The scale factor that will be used to convert pulses to useful
|
||||
* units.
|
||||
*/
|
||||
public void setDistancePerPulse(double distancePerPulse) {
|
||||
m_distancePerPulse = distancePerPulse;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the direction sensing for this encoder. This sets the direction
|
||||
* sensing on the encoder so that it could count in the correct software
|
||||
* direction regardless of the mounting.
|
||||
*
|
||||
* @param reverseDirection
|
||||
* true if the encoder direction should be reversed
|
||||
*/
|
||||
public void setReverseDirection(boolean reverseDirection) {
|
||||
if (m_counter != null) {
|
||||
m_counter.setReverseDirection(reverseDirection);
|
||||
} else {
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
* TODO: Should this throw a checked exception, so that the user has to deal
|
||||
* with giving an incorrect value?
|
||||
*
|
||||
* @param samplesToAverage
|
||||
* The number of samples to average from 1 to 127.
|
||||
*/
|
||||
public void setSamplesToAverage(int samplesToAverage) {
|
||||
switch (m_encodingType.value) {
|
||||
case EncodingType.k4X_val:
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
EncoderJNI.setEncoderSamplesToAverage(m_encoder, samplesToAverage,
|
||||
status.asIntBuffer());
|
||||
if (status.duplicate().get() == HALUtil.PARAMETER_OUT_OF_RANGE) {
|
||||
throw new BoundaryException(BoundaryException.getMessage(
|
||||
samplesToAverage, 1, 127));
|
||||
}
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
break;
|
||||
case EncodingType.k1X_val:
|
||||
case EncodingType.k2X_val:
|
||||
m_counter.setSamplesToAverage(samplesToAverage);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Samples to Average which specifies the number of samples of the
|
||||
* timer to average when calculating the period. Perform averaging to
|
||||
* account for mechanical imperfections or as oversampling to increase
|
||||
* resolution.
|
||||
*
|
||||
* @return SamplesToAverage The number of samples being averaged (from 1 to
|
||||
* 127)
|
||||
*/
|
||||
public int getSamplesToAverage() {
|
||||
switch (m_encodingType.value) {
|
||||
case EncodingType.k4X_val:
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = EncoderJNI.getEncoderSamplesToAverage(m_encoder, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
case EncodingType.k1X_val:
|
||||
case EncodingType.k2X_val:
|
||||
return m_counter.getSamplesToAverage();
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set which parameter of the encoder you are using as a process control
|
||||
* variable. The encoder class supports the rate and distance parameters.
|
||||
*
|
||||
* @param pidSource
|
||||
* An enum to select the parameter.
|
||||
*/
|
||||
public void setPIDSourceParameter(PIDSourceParameter pidSource) {
|
||||
BoundaryException.assertWithinBounds(pidSource.value, 0, 1);
|
||||
m_pidSource = pidSource;
|
||||
}
|
||||
|
||||
/**
|
||||
* Implement the PIDSource interface.
|
||||
*
|
||||
* @return The current value of the selected source parameter.
|
||||
*/
|
||||
public double pidGet() {
|
||||
switch (m_pidSource.value) {
|
||||
case PIDSourceParameter.kDistance_val:
|
||||
return getDistance();
|
||||
case PIDSourceParameter.kRate_val:
|
||||
return getRate();
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
switch (m_encodingType.value) {
|
||||
case EncodingType.k4X_val:
|
||||
return "Quadrature Encoder";
|
||||
default:
|
||||
return "Encoder";
|
||||
}
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Speed", getRate());
|
||||
m_table.putNumber("Distance", getDistance());
|
||||
m_table.putNumber("Distance per Tick", m_distancePerPulse);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,92 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
|
||||
/**
|
||||
* Alias for counter class.
|
||||
* Implement the gear tooth sensor supplied by FIRST. Currently there is no reverse sensing on
|
||||
* the gear tooth sensor, but in future versions we might implement the necessary timing in the
|
||||
* FPGA to sense direction.
|
||||
*/
|
||||
public class GearTooth extends Counter implements ISensor {
|
||||
|
||||
private static final double kGearToothThreshold = 55e-6;
|
||||
|
||||
/**
|
||||
* Common code called by the constructors.
|
||||
*/
|
||||
public void enableDirectionSensing(boolean directionSensitive) {
|
||||
if (directionSensitive) {
|
||||
setPulseLengthMode(kGearToothThreshold);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Construct a GearTooth sensor given a channel.
|
||||
*
|
||||
* No direction sensing is assumed.
|
||||
*
|
||||
* @param channel The GPIO channel that the sensor is connected to.
|
||||
*/
|
||||
public GearTooth(final int channel) {
|
||||
this(channel,false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Construct a GearTooth sensor given a channel.
|
||||
*
|
||||
* @param channel The GPIO channel that the sensor is connected to.
|
||||
* @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
|
||||
*/
|
||||
public GearTooth(final int channel, boolean directionSensitive) {
|
||||
super(channel);
|
||||
enableDirectionSensing(directionSensitive);
|
||||
if(directionSensitive) {
|
||||
UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, 0, "D");
|
||||
} else {
|
||||
UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, 0);
|
||||
}
|
||||
LiveWindow.addSensor("GearTooth", channel, this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Construct a GearTooth sensor given a digital input.
|
||||
* This should be used when sharing digial inputs.
|
||||
*
|
||||
* @param source An object that fully descibes the input that the sensor is connected to.
|
||||
* @param directionSensitive Enable the pulse length decoding in hardware to specify count direction.
|
||||
*/
|
||||
public GearTooth(DigitalSource source, boolean directionSensitive) {
|
||||
super(source);
|
||||
enableDirectionSensing(directionSensitive);
|
||||
}
|
||||
|
||||
/**
|
||||
* Construct a GearTooth sensor given a digital input.
|
||||
* This should be used when sharing digial inputs.
|
||||
*
|
||||
* No direction sensing is assumed.
|
||||
*
|
||||
* @param source An object that fully descibes the input that the sensor is connected to.
|
||||
*/
|
||||
public GearTooth(DigitalSource source) {
|
||||
this(source,false);
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Gear Tooth";
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,273 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
* Use a rate gyro to return the robots heading relative to a starting position.
|
||||
* The Gyro class tracks the robots heading based on the starting position. As
|
||||
* the robot rotates the new heading is computed by integrating the rate of
|
||||
* rotation returned by the sensor. When the class is instantiated, it does a
|
||||
* short calibration routine where it samples the gyro while at rest to
|
||||
* determine the default offset. This is subtracted from each sample to
|
||||
* determine the heading.
|
||||
*/
|
||||
public class Gyro extends SensorBase implements PIDSource, ISensor,
|
||||
LiveWindowSendable {
|
||||
|
||||
static final int kOversampleBits = 10;
|
||||
static final int kAverageBits = 0;
|
||||
static final double kSamplesPerSecond = 50.0;
|
||||
static final double kCalibrationSampleTime = 5.0;
|
||||
static final double kDefaultVoltsPerDegreePerSecond = 0.007;
|
||||
AnalogInput m_analog;
|
||||
double m_voltsPerDegreePerSecond;
|
||||
double m_offset;
|
||||
int m_center;
|
||||
boolean m_channelAllocated;
|
||||
AccumulatorResult result;
|
||||
private PIDSourceParameter m_pidSource;
|
||||
|
||||
/**
|
||||
* Initialize the gyro. Calibrate the gyro by running for a number of
|
||||
* samples and computing the center value for this part. Then use the center
|
||||
* value as the Accumulator center value for subsequent measurements. It's
|
||||
* important to make sure that the robot is not moving while the centering
|
||||
* calculations are in progress, this is typically done when the robot is
|
||||
* first turned on while it's sitting at rest before the competition starts.
|
||||
*/
|
||||
private void initGyro() {
|
||||
result = new AccumulatorResult();
|
||||
if (m_analog == null) {
|
||||
System.out.println("Null m_analog");
|
||||
}
|
||||
m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
|
||||
m_analog.setAverageBits(kAverageBits);
|
||||
m_analog.setOversampleBits(kOversampleBits);
|
||||
double sampleRate = kSamplesPerSecond
|
||||
* (1 << (kAverageBits + kOversampleBits));
|
||||
AnalogInput.setGlobalSampleRate(sampleRate);
|
||||
|
||||
Timer.delay(1.0);
|
||||
m_analog.initAccumulator();
|
||||
|
||||
Timer.delay(kCalibrationSampleTime);
|
||||
|
||||
m_analog.getAccumulatorOutput(result);
|
||||
|
||||
m_center = (int) ((double) result.value / (double) result.count + .5);
|
||||
|
||||
m_offset = ((double) result.value / (double) result.count)
|
||||
- (double) m_center;
|
||||
|
||||
m_analog.setAccumulatorCenter(m_center);
|
||||
|
||||
m_analog.setAccumulatorDeadband(0); // /< TODO: compute / parameterize
|
||||
// this
|
||||
m_analog.resetAccumulator();
|
||||
|
||||
setPIDSourceParameter(PIDSourceParameter.kAngle);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Gyro, m_analog.getChannel());
|
||||
LiveWindow.addSensor("Gyro", m_analog.getChannel(), this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gyro constructor with only a channel.
|
||||
*
|
||||
* @param channel
|
||||
* The analog channel the gyro is connected to.
|
||||
*/
|
||||
public Gyro(int channel) {
|
||||
m_analog = new AnalogInput(channel);
|
||||
m_channelAllocated = true;
|
||||
initGyro();
|
||||
}
|
||||
|
||||
/**
|
||||
* Gyro constructor with a precreated analog channel object. Use this
|
||||
* constructor when the analog channel needs to be shared. There is no
|
||||
* reference counting when an AnalogChannel is passed to the gyro.
|
||||
*
|
||||
* @param channel
|
||||
* The AnalogChannel object that the gyro is connected to.
|
||||
*/
|
||||
public Gyro(AnalogInput channel) {
|
||||
m_analog = channel;
|
||||
if (m_analog == null) {
|
||||
System.err
|
||||
.println("Analog channel supplied to Gyro constructor is null");
|
||||
} else {
|
||||
m_channelAllocated = false;
|
||||
initGyro();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the gyro. Resets the gyro to a heading of zero. This can be used if
|
||||
* there is significant drift in the gyro and it needs to be recalibrated
|
||||
* after it has been running.
|
||||
*/
|
||||
public void reset() {
|
||||
if (m_analog != null) {
|
||||
m_analog.resetAccumulator();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Delete (free) the accumulator and the analog components used for the
|
||||
* gyro.
|
||||
*/
|
||||
public void free() {
|
||||
if (m_analog != null && m_channelAllocated) {
|
||||
m_analog.free();
|
||||
}
|
||||
m_analog = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the actual angle in degrees that the robot is currently facing.
|
||||
*
|
||||
* The angle is based on the current accumulator value corrected by the
|
||||
* oversampling rate, the gyro type and the A/D calibration values. The
|
||||
* angle is continuous, that is can go beyond 360 degrees. This make
|
||||
* algorithms that wouldn't want to see a discontinuity in the gyro output
|
||||
* as it sweeps past 0 on the second time around.
|
||||
*
|
||||
* @return the current heading of the robot in degrees. This heading is
|
||||
* based on integration of the returned rate from the gyro.
|
||||
*/
|
||||
public double getAngle() {
|
||||
if (m_analog == null) {
|
||||
return 0.0;
|
||||
} else {
|
||||
m_analog.getAccumulatorOutput(result);
|
||||
|
||||
long value = result.value - (long) (result.count * m_offset);
|
||||
|
||||
double scaledValue = value
|
||||
* 1e-9
|
||||
* m_analog.getLSBWeight()
|
||||
* (1 << m_analog.getAverageBits())
|
||||
/ (AnalogInput.getGlobalSampleRate() * m_voltsPerDegreePerSecond);
|
||||
|
||||
return scaledValue;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the rate of rotation of the gyro
|
||||
*
|
||||
* The rate is based on the most recent reading of the gyro analog value
|
||||
*
|
||||
* @return the current rate in degrees per second
|
||||
*/
|
||||
public double getRate() {
|
||||
if (m_analog == null) {
|
||||
return 0.0;
|
||||
} else {
|
||||
return (m_analog.getAverageValue() - ((double) m_center + m_offset))
|
||||
* 1e-9
|
||||
* m_analog.getLSBWeight()
|
||||
/ ((1 << m_analog.getOversampleBits()) * m_voltsPerDegreePerSecond);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the gyro type based on the sensitivity. This takes the number of
|
||||
* volts/degree/second sensitivity of the gyro and uses it in subsequent
|
||||
* calculations to allow the code to work with multiple gyros.
|
||||
*
|
||||
* @param voltsPerDegreePerSecond
|
||||
* The type of gyro specified as the voltage that represents one
|
||||
* degree/second.
|
||||
*/
|
||||
public void setSensitivity(double voltsPerDegreePerSecond) {
|
||||
m_voltsPerDegreePerSecond = voltsPerDegreePerSecond;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set which parameter of the encoder you are using as a process control
|
||||
* variable. The Gyro class supports the rate and angle parameters
|
||||
*
|
||||
* @param pidSource
|
||||
* An enum to select the parameter.
|
||||
*/
|
||||
public void setPIDSourceParameter(PIDSourceParameter pidSource) {
|
||||
BoundaryException.assertWithinBounds(pidSource.value, 1, 2);
|
||||
m_pidSource = pidSource;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the angle of the gyro for use with PIDControllers
|
||||
*
|
||||
* @return the current angle according to the gyro
|
||||
*/
|
||||
public double pidGet() {
|
||||
switch (m_pidSource.value) {
|
||||
case PIDSourceParameter.kRate_val:
|
||||
return getRate();
|
||||
case PIDSourceParameter.kAngle_val:
|
||||
return getAngle();
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Gyro";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAngle());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,268 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.HALLibrary;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.hal.I2CJNI;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
/**
|
||||
* I2C bus interface class.
|
||||
*
|
||||
* This class is intended to be used by sensor (and other I2C device) drivers.
|
||||
* It probably should not be used directly.
|
||||
*
|
||||
*/
|
||||
public class I2C extends SensorBase {
|
||||
public enum Port {kOnboard(0), kMXP(1);
|
||||
private int value;
|
||||
|
||||
private Port(int value){
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
public int getValue(){
|
||||
return this.value;
|
||||
}
|
||||
};
|
||||
|
||||
private Port m_port;
|
||||
private int m_deviceAddress;
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param deviceAddress
|
||||
* The address of the device on the I2C bus.
|
||||
*/
|
||||
public I2C(Port port, int deviceAddress) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
m_port = port;
|
||||
m_deviceAddress = deviceAddress;
|
||||
|
||||
I2CJNI.i2CInitialize((byte)m_port.getValue(), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_I2C, deviceAddress);
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
public void free() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Generic transaction.
|
||||
*
|
||||
* This is a lower-level interface to the I2C hardware giving you more
|
||||
* control over each transaction.
|
||||
*
|
||||
* @param dataToSend
|
||||
* Buffer of data to send as part of the transaction.
|
||||
* @param sendSize
|
||||
* Number of bytes to send as part of the transaction. [0..6]
|
||||
* @param dataReceived
|
||||
* Buffer to read data into.
|
||||
* @param receiveSize
|
||||
* Number of bytes to read from the device. [0..7]
|
||||
* @return Transfer Aborted... false for success, true for aborted.
|
||||
*/
|
||||
public synchronized boolean transaction(byte[] dataToSend, int sendSize,
|
||||
byte[] dataReceived, int receiveSize) {
|
||||
boolean aborted = true;
|
||||
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(sendSize);
|
||||
dataToSendBuffer.put(dataToSend);
|
||||
ByteBuffer dataReceivedBuffer = ByteBuffer.allocateDirect(receiveSize);
|
||||
|
||||
aborted = I2CJNI
|
||||
.i2CTransaction((byte) m_port.getValue(), (byte) m_deviceAddress,
|
||||
dataToSendBuffer, (byte) sendSize,
|
||||
dataReceivedBuffer, (byte) receiveSize) != 0;
|
||||
/*if (status.get() == HALUtil.PARAMETER_OUT_OF_RANGE) {
|
||||
if (sendSize > 6) {
|
||||
throw new BoundaryException(BoundaryException.getMessage(
|
||||
sendSize, 0, 6));
|
||||
} else if (receiveSize > 7) {
|
||||
throw new BoundaryException(BoundaryException.getMessage(
|
||||
receiveSize, 0, 7));
|
||||
} else {
|
||||
throw new RuntimeException(
|
||||
HALLibrary.PARAMETER_OUT_OF_RANGE_MESSAGE);
|
||||
}
|
||||
}
|
||||
HALUtil.checkStatus(status);*/
|
||||
dataReceivedBuffer.get(dataReceived);
|
||||
return aborted;
|
||||
}
|
||||
|
||||
/**
|
||||
* Attempt to address a device on the I2C bus.
|
||||
*
|
||||
* This allows you to figure out if there is a device on the I2C bus that
|
||||
* responds to the address specified in the constructor.
|
||||
*
|
||||
* @return Transfer Aborted... false for success, true for aborted.
|
||||
*/
|
||||
public boolean addressOnly() {
|
||||
return transaction(null, (byte) 0, null, (byte) 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a write transaction with the device.
|
||||
*
|
||||
* Write a single byte to a register on a device and wait until the
|
||||
* transaction is complete.
|
||||
*
|
||||
* @param registerAddress
|
||||
* The address of the register on the device to be written.
|
||||
* @param data
|
||||
* The byte to write to the register on the device.
|
||||
*/
|
||||
public synchronized boolean write(int registerAddress, int data) {
|
||||
byte[] buffer = new byte[2];
|
||||
buffer[0] = (byte) registerAddress;
|
||||
buffer[1] = (byte) data;
|
||||
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(2);
|
||||
dataToSendBuffer.put(buffer);
|
||||
|
||||
return I2CJNI.i2CWrite((byte)m_port.getValue(), (byte) m_deviceAddress, dataToSendBuffer, (byte)buffer.length) < 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a write transaction with the device.
|
||||
*
|
||||
* Write multiple bytes to a register on a device and wait until the
|
||||
* transaction is complete.
|
||||
*
|
||||
* @param data
|
||||
* The data to write to the device.
|
||||
*/
|
||||
public synchronized boolean writeBulk(byte[] data) {
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(data.length);
|
||||
dataToSendBuffer.put(data);
|
||||
|
||||
return I2CJNI.i2CWrite((byte)m_port.getValue(), (byte) m_deviceAddress, dataToSendBuffer, (byte)data.length) < 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a read transaction with the device.
|
||||
*
|
||||
* Read 1 to 7 bytes from a device. Most I2C devices will auto-increment the
|
||||
* register pointer internally allowing you to read up to 7 consecutive
|
||||
* registers on a device in a single transaction.
|
||||
*
|
||||
* @param registerAddress
|
||||
* The register to read first in the transaction.
|
||||
* @param count
|
||||
* The number of bytes to read in the transaction. [1..7]
|
||||
* @param buffer
|
||||
* A pointer to the array of bytes to store the data read from
|
||||
* the device.
|
||||
* @return Transfer Aborted... false for success, true for aborted.
|
||||
*/
|
||||
public boolean read(int registerAddress, int count, byte[] buffer) {
|
||||
BoundaryException.assertWithinBounds(count, 1, 7);
|
||||
if (buffer == null) {
|
||||
throw new NullPointerException("Null return buffer was given");
|
||||
}
|
||||
byte[] registerAddressArray = new byte[1];
|
||||
registerAddressArray[0] = (byte) registerAddress;
|
||||
|
||||
return transaction(registerAddressArray, registerAddressArray.length,
|
||||
buffer, count);
|
||||
}
|
||||
|
||||
/**
|
||||
* Execute a read only transaction with the device.
|
||||
*
|
||||
* Read 1 to 7 bytes from a device. This method does not write any data to prompt
|
||||
* the device.
|
||||
*
|
||||
* @param buffer
|
||||
* A pointer to the array of bytes to store the data read from
|
||||
* the device.
|
||||
* @param count
|
||||
* The number of bytes to read in the transaction. [1..7]
|
||||
* @return Transfer Aborted... false for success, true for aborted.
|
||||
*/
|
||||
public boolean readOnly(byte[] buffer, int count) {
|
||||
BoundaryException.assertWithinBounds(count, 1, 7);
|
||||
if (buffer == null) {
|
||||
throw new NullPointerException("Null return buffer was given");
|
||||
}
|
||||
|
||||
ByteBuffer dataReceivedBuffer = ByteBuffer.allocateDirect(count);
|
||||
|
||||
int retVal = I2CJNI.i2CRead((byte)m_port.getValue(), (byte) m_deviceAddress, dataReceivedBuffer, (byte)count);
|
||||
dataReceivedBuffer.get(buffer);
|
||||
return retVal < 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a broadcast write to all devices on the I2C bus.
|
||||
*
|
||||
* This is not currently implemented!
|
||||
*
|
||||
* @param registerAddress
|
||||
* The register to write on all devices on the bus.
|
||||
* @param data
|
||||
* The value to write to the devices.
|
||||
*/
|
||||
public void broadcast(int registerAddress, int data) {
|
||||
}
|
||||
|
||||
/**
|
||||
* Verify that a device's registers contain expected values.
|
||||
*
|
||||
* Most devices will have a set of registers that contain a known value that
|
||||
* can be used to identify them. This allows an I2C device driver to easily
|
||||
* verify that the device contains the expected value.
|
||||
*
|
||||
* @pre The device must support and be configured to use register
|
||||
* auto-increment.
|
||||
*
|
||||
* @param registerAddress
|
||||
* The base register to start reading from the device.
|
||||
* @param count
|
||||
* The size of the field to be verified.
|
||||
* @param expected
|
||||
* A buffer containing the values expected from the device.
|
||||
* @return true if the sensor was verified to be connected
|
||||
*/
|
||||
public boolean verifySensor(int registerAddress, int count, byte[] expected) {
|
||||
// TODO: Make use of all 7 read bytes
|
||||
byte[] deviceData = new byte[4];
|
||||
for (int i = 0, curRegisterAddress = registerAddress; i < count; i += 4, curRegisterAddress += 4) {
|
||||
int toRead = count - i < 4 ? count - i : 4;
|
||||
// Read the chunk of data. Return false if the sensor does not
|
||||
// respond.
|
||||
if (read(curRegisterAddress, toRead, deviceData)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
for (byte j = 0; j < toRead; j++) {
|
||||
if (deviceData[j] != expected[i + j]) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,34 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
/**
|
||||
* Represents a Dashboard which can provide data to be sent by the DriverStation
|
||||
* class.
|
||||
* @author pmalmsten
|
||||
*/
|
||||
public interface IDashboard {
|
||||
/**
|
||||
* Gets a reference to the current data to be sent to the dashboard.
|
||||
* @return Byte array of data.
|
||||
*/
|
||||
public byte[] getBytes();
|
||||
|
||||
/**
|
||||
* Gets the length of the current data to be sent to the
|
||||
* dashboard.
|
||||
* @return The length of the data array to be sent to the dashboard.
|
||||
*/
|
||||
public int getBytesLength();
|
||||
|
||||
/**
|
||||
* If the dashboard had data buffered to be sent, calling this method
|
||||
* will reset the output buffer.
|
||||
*/
|
||||
public void flush();
|
||||
}
|
||||
@@ -0,0 +1,134 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.InterruptJNI;
|
||||
import edu.wpi.first.wpilibj.hal.InterruptJNI.InterruptHandlerFunction;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
|
||||
/**
|
||||
* Base for sensors to be used with interrupts
|
||||
*/
|
||||
public abstract class InterruptableSensorBase extends SensorBase {
|
||||
|
||||
/**
|
||||
* The interrupt resource
|
||||
*/
|
||||
protected ByteBuffer m_interrupt;
|
||||
/**
|
||||
* The interrupt manager resource
|
||||
*/
|
||||
protected InterruptHandlerFunction m_manager;
|
||||
/**
|
||||
* The index of the interrupt
|
||||
*/
|
||||
protected int m_interruptIndex;
|
||||
/**
|
||||
* Resource manager
|
||||
*/
|
||||
protected static Resource interrupts = new Resource(8);
|
||||
|
||||
/**
|
||||
* Create a new InterrupatableSensorBase
|
||||
*/
|
||||
public InterruptableSensorBase() {
|
||||
m_manager = null;
|
||||
m_interrupt = null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Allocate the interrupt
|
||||
*
|
||||
* @param watcher
|
||||
*/
|
||||
public void allocateInterrupts(boolean watcher) {
|
||||
if (!watcher) {
|
||||
throw new IllegalArgumentException(
|
||||
"Interrupt callbacks not yet supported");
|
||||
}
|
||||
// Expects the calling leaf class to allocate an interrupt index.
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
m_interrupt = InterruptJNI.initializeInterrupts(m_interruptIndex,
|
||||
(byte) (watcher ? 1 : 0), status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Cancel interrupts on this device. This deallocates all the chipobject
|
||||
* structures and disables any interrupts.
|
||||
*/
|
||||
public void cancelInterrupts() {
|
||||
if (m_interrupt == null || m_manager == null) {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
InterruptJNI.cleanInterrupts(m_interrupt, status);
|
||||
HALUtil.checkStatus(status);
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* In synchronous mode, wait for the defined interrupt to occur.
|
||||
*
|
||||
* @param timeout
|
||||
* Timeout in seconds
|
||||
*/
|
||||
public void waitForInterrupt(double timeout) {
|
||||
if (m_interrupt == null || m_manager == null) {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
InterruptJNI.waitForInterrupt(m_interrupt, (float) timeout, status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable interrupts to occur on this input. Interrupts are disabled when
|
||||
* the RequestInterrupt call is made. This gives time to do the setup of the
|
||||
* other options before starting to field interrupts.
|
||||
*/
|
||||
public void enableInterrupts() {
|
||||
if (m_interrupt == null || m_manager == null) {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
InterruptJNI.enableInterrupts(m_interrupt, status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable Interrupts without without deallocating structures.
|
||||
*/
|
||||
public void disableInterrupts() {
|
||||
if (m_interrupt == null || m_manager == null) {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
InterruptJNI.disableInterrupts(m_interrupt, status);
|
||||
HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the timestamp for the interrupt that occurred most recently. This
|
||||
* is in the same time domain as getClock().
|
||||
*
|
||||
* @return Timestamp in seconds since boot.
|
||||
*/
|
||||
public double readInterruptTimestamp() {
|
||||
if (m_interrupt == null || m_manager == null) {
|
||||
throw new IllegalStateException();
|
||||
}
|
||||
IntBuffer status = IntBuffer.allocate(1);
|
||||
double timestamp = InterruptJNI.readInterruptTimestamp(m_interrupt, status);
|
||||
HALUtil.checkStatus(status);
|
||||
return timestamp;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,280 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
|
||||
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.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
|
||||
/**
|
||||
* IterativeRobot implements a specific type of Robot Program framework, extending the RobotBase class.
|
||||
*
|
||||
* The IterativeRobot class is intended to be subclassed by a user creating a robot program.
|
||||
*
|
||||
* This class is intended to implement the "old style" default code, by providing
|
||||
* the following functions which are called by the main loop, startCompetition(), at the appropriate times:
|
||||
*
|
||||
* robotInit() -- provide for initialization at robot power-on
|
||||
*
|
||||
* init() functions -- each of the following functions is called once when the
|
||||
* appropriate mode is entered:
|
||||
* - DisabledInit() -- called only when first disabled
|
||||
* - AutonomousInit() -- called each and every time autonomous is entered from another mode
|
||||
* - TeleopInit() -- called each and every time teleop is entered from another mode
|
||||
* - TestInit() -- called each and every time test mode is entered from anothermode
|
||||
*
|
||||
* Periodic() functions -- each of these functions is called iteratively at the
|
||||
* appropriate periodic rate (aka the "slow loop"). The period of
|
||||
* the iterative robot is synced to the driver station control packets,
|
||||
* giving a periodic frequency of about 50Hz (50 times per second).
|
||||
* - disabledPeriodic()
|
||||
* - autonomousPeriodic()
|
||||
* - teleopPeriodic()
|
||||
* - testPeriodoc()
|
||||
*
|
||||
*/
|
||||
public class IterativeRobot extends RobotBase {
|
||||
private boolean m_disabledInitialized;
|
||||
private boolean m_autonomousInitialized;
|
||||
private boolean m_teleopInitialized;
|
||||
private boolean m_testInitialized;
|
||||
|
||||
/**
|
||||
* Constructor for RobotIterativeBase
|
||||
*
|
||||
* The constructor initializes the instance variables for the robot to indicate
|
||||
* the status of initialization for disabled, autonomous, and teleop code.
|
||||
*/
|
||||
public IterativeRobot() {
|
||||
// set status for initialization of disabled, autonomous, and teleop code.
|
||||
m_disabledInitialized = false;
|
||||
m_autonomousInitialized = false;
|
||||
m_teleopInitialized = false;
|
||||
m_testInitialized = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide an alternate "main loop" via startCompetition().
|
||||
*
|
||||
*/
|
||||
public void startCompetition() {
|
||||
UsageReporting.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Iterative);
|
||||
|
||||
robotInit();
|
||||
|
||||
// tracing support:
|
||||
final int TRACE_LOOP_MAX = 100;
|
||||
int loopCount = TRACE_LOOP_MAX;
|
||||
Object marker = null;
|
||||
boolean didDisabledPeriodic = false;
|
||||
boolean didAutonomousPeriodic = false;
|
||||
boolean didTeleopPeriodic = false;
|
||||
boolean didTestPeriodic = false;
|
||||
|
||||
// loop forever, calling the appropriate mode-dependent function
|
||||
LiveWindow.setEnabled(false);
|
||||
while (true) {
|
||||
// Call the appropriate function depending upon the current robot mode
|
||||
if (isDisabled()) {
|
||||
// call DisabledInit() if we are now just entering disabled mode from
|
||||
// either a different mode or from power-on
|
||||
if (!m_disabledInitialized) {
|
||||
LiveWindow.setEnabled(false);
|
||||
disabledInit();
|
||||
m_disabledInitialized = true;
|
||||
// reset the initialization flags for the other modes
|
||||
m_autonomousInitialized = false;
|
||||
m_teleopInitialized = false;
|
||||
m_testInitialized = false;
|
||||
}
|
||||
if (nextPeriodReady()) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramDisabled();
|
||||
disabledPeriodic();
|
||||
didDisabledPeriodic = true;
|
||||
}
|
||||
} else if (isTest()) {
|
||||
// call TestInit() if we are now just entering test mode from either
|
||||
// a different mode or from power-on
|
||||
if (!m_testInitialized) {
|
||||
LiveWindow.setEnabled(true);
|
||||
testInit();
|
||||
m_testInitialized = true;
|
||||
m_autonomousInitialized = false;
|
||||
m_teleopInitialized = false;
|
||||
m_disabledInitialized = false;
|
||||
}
|
||||
if (nextPeriodReady()) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTest();
|
||||
testPeriodic();
|
||||
didTestPeriodic = true;
|
||||
}
|
||||
} else if (isAutonomous()) {
|
||||
// call Autonomous_Init() if this is the first time
|
||||
// we've entered autonomous_mode
|
||||
if (!m_autonomousInitialized) {
|
||||
LiveWindow.setEnabled(false);
|
||||
// KBS NOTE: old code reset all PWMs and relays to "safe values"
|
||||
// whenever entering autonomous mode, before calling
|
||||
// "Autonomous_Init()"
|
||||
autonomousInit();
|
||||
m_autonomousInitialized = true;
|
||||
m_testInitialized = false;
|
||||
m_teleopInitialized = false;
|
||||
m_disabledInitialized = false;
|
||||
}
|
||||
if (nextPeriodReady()) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramAutonomous();
|
||||
autonomousPeriodic();
|
||||
didAutonomousPeriodic = true;
|
||||
}
|
||||
} else {
|
||||
// call Teleop_Init() if this is the first time
|
||||
// we've entered teleop_mode
|
||||
if (!m_teleopInitialized) {
|
||||
LiveWindow.setEnabled(false);
|
||||
teleopInit();
|
||||
m_teleopInitialized = true;
|
||||
m_testInitialized = false;
|
||||
m_autonomousInitialized = false;
|
||||
m_disabledInitialized = false;
|
||||
}
|
||||
if (nextPeriodReady()) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTeleop();
|
||||
teleopPeriodic();
|
||||
didTeleopPeriodic = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the appropriate next periodic function should be called.
|
||||
* Call the periodic functions whenever a packet is received from the Driver Station, or about every 20ms.
|
||||
*/
|
||||
private boolean nextPeriodReady() {
|
||||
return m_ds.isNewControlData();
|
||||
}
|
||||
|
||||
/* ----------- Overridable initialization code -----------------*/
|
||||
|
||||
/**
|
||||
* Robot-wide initialization code should go here.
|
||||
*
|
||||
* Users should override this method for default Robot-wide initialization which will
|
||||
* be called when the robot is first powered on. It will be called exactly 1 time.
|
||||
*/
|
||||
public void robotInit() {
|
||||
System.out.println("Default IterativeRobot.robotInit() method... Overload me!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialization code for disabled mode should go here.
|
||||
*
|
||||
* Users should override this method for initialization code which will be called each time
|
||||
* the robot enters disabled mode.
|
||||
*/
|
||||
public void disabledInit() {
|
||||
System.out.println("Default IterativeRobot.disabledInit() method... Overload me!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialization code for autonomous mode should go here.
|
||||
*
|
||||
* Users should override this method for initialization code which will be called each time
|
||||
* the robot enters autonomous mode.
|
||||
*/
|
||||
public void autonomousInit() {
|
||||
System.out.println("Default IterativeRobot.autonomousInit() method... Overload me!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialization code for teleop mode should go here.
|
||||
*
|
||||
* Users should override this method for initialization code which will be called each time
|
||||
* the robot enters teleop mode.
|
||||
*/
|
||||
public void teleopInit() {
|
||||
System.out.println("Default IterativeRobot.teleopInit() method... Overload me!");
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialization code for test mode should go here.
|
||||
*
|
||||
* Users should override this method for initialization code which will be called each time
|
||||
* the robot enters test mode.
|
||||
*/
|
||||
public void testInit() {
|
||||
System.out.println("Default IterativeRobot.testInit() method... Overload me!");
|
||||
}
|
||||
|
||||
/* ----------- Overridable periodic code -----------------*/
|
||||
|
||||
private boolean dpFirstRun = true;
|
||||
/**
|
||||
* Periodic code for disabled mode should go here.
|
||||
*
|
||||
* Users should override this method for code which will be called periodically at a regular
|
||||
* rate while the robot is in disabled mode.
|
||||
*/
|
||||
public void disabledPeriodic() {
|
||||
if (dpFirstRun) {
|
||||
System.out.println("Default IterativeRobot.disabledPeriodic() method... Overload me!");
|
||||
dpFirstRun = false;
|
||||
}
|
||||
Timer.delay(0.001);
|
||||
}
|
||||
|
||||
private boolean apFirstRun = true;
|
||||
|
||||
/**
|
||||
* Periodic code for autonomous mode should go here.
|
||||
*
|
||||
* Users should override this method for code which will be called periodically at a regular
|
||||
* rate while the robot is in autonomous mode.
|
||||
*/
|
||||
public void autonomousPeriodic() {
|
||||
if (apFirstRun) {
|
||||
System.out.println("Default IterativeRobot.autonomousPeriodic() method... Overload me!");
|
||||
apFirstRun = false;
|
||||
}
|
||||
Timer.delay(0.001);
|
||||
}
|
||||
|
||||
private boolean tpFirstRun = true;
|
||||
|
||||
/**
|
||||
* Periodic code for teleop mode should go here.
|
||||
*
|
||||
* Users should override this method for code which will be called periodically at a regular
|
||||
* rate while the robot is in teleop mode.
|
||||
*/
|
||||
public void teleopPeriodic() {
|
||||
if (tpFirstRun) {
|
||||
System.out.println("Default IterativeRobot.teleopPeriodic() method... Overload me!");
|
||||
tpFirstRun = false;
|
||||
}
|
||||
Timer.delay(0.001);
|
||||
}
|
||||
|
||||
private boolean tmpFirstRun = true;
|
||||
|
||||
/**
|
||||
* Periodic code for test mode should go here
|
||||
*
|
||||
* Users should override this method for code which will be called periodically at a regular rate
|
||||
* while the robot is in test mode.
|
||||
*/
|
||||
public void testPeriodic() {
|
||||
if (tmpFirstRun) {
|
||||
System.out.println("Default IterativeRobot.testPeriodic() method... Overload me!");
|
||||
tmpFirstRun = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,102 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* Texas Instruments Jaguar Speed Controller as a PWM device.
|
||||
*/
|
||||
public class Jaguar extends SafePWM implements SpeedController, IDeviceController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
*/
|
||||
private void initJaguar() {
|
||||
/*
|
||||
* Input profile defined by Luminary Micro.
|
||||
*
|
||||
* Full reverse ranges from 0.671325ms to 0.6972211ms
|
||||
* Proportional reverse ranges from 0.6972211ms to 1.4482078ms
|
||||
* Neutral ranges from 1.4482078ms to 1.5517922ms
|
||||
* Proportional forward ranges from 1.5517922ms to 2.3027789ms
|
||||
* Full forward ranges from 2.3027789ms to 2.328675ms
|
||||
*/
|
||||
setBounds(2.31, 1.55, 1.507, 1.454, .697);
|
||||
setPeriodMultiplier(PeriodMultiplier.k1X);
|
||||
setRaw(m_centerPwm);
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Jaguar, getChannel());
|
||||
LiveWindow.addActuator("Jaguar", getChannel(), this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the Jaguar is attached to.
|
||||
*/
|
||||
public Jaguar(final int channel) {
|
||||
super(channel);
|
||||
initJaguar();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* @deprecated For compatibility with CANJaguar
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed to set. Value should be between -1.0 and 1.0.
|
||||
* @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
|
||||
*/
|
||||
@Deprecated
|
||||
@Override
|
||||
public void set(double speed, byte syncGroup) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed value between -1.0 and 1.0 to set.
|
||||
*/
|
||||
@Override
|
||||
public void set(double speed) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the recently set value of the PWM.
|
||||
*
|
||||
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
||||
*/
|
||||
@Override
|
||||
public double get() {
|
||||
return getSpeed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Write out the PID value as seen in the PIDOutput base object.
|
||||
*
|
||||
* @param output Write out the PWM value as was found in the PIDController
|
||||
*/
|
||||
@Override
|
||||
public void pidWrite(double output) {
|
||||
set(output);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,354 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.parsing.IInputOutput;
|
||||
|
||||
/**
|
||||
* Handle input from standard Joysticks connected to the Driver Station.
|
||||
* This class handles standard input that comes from the Driver Station. Each time a value is requested
|
||||
* the most recent value is returned. There is a single class instance for each joystick and the mapping
|
||||
* of ports to hardware buttons depends on the code in the driver station.
|
||||
*/
|
||||
public class Joystick extends GenericHID implements IInputOutput {
|
||||
|
||||
static final byte kDefaultXAxis = 1;
|
||||
static final byte kDefaultYAxis = 2;
|
||||
static final byte kDefaultZAxis = 3;
|
||||
static final byte kDefaultTwistAxis = 3;
|
||||
static final byte kDefaultThrottleAxis = 4;
|
||||
static final int kDefaultTriggerButton = 1;
|
||||
static final int kDefaultTopButton = 2;
|
||||
|
||||
/**
|
||||
* Represents an analog axis on a joystick.
|
||||
*/
|
||||
public static class AxisType {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kX_val = 0;
|
||||
static final int kY_val = 1;
|
||||
static final int kZ_val = 2;
|
||||
static final int kTwist_val = 3;
|
||||
static final int kThrottle_val = 4;
|
||||
static final int kNumAxis_val = 5;
|
||||
/**
|
||||
* axis: x-axis
|
||||
*/
|
||||
public static final AxisType kX = new AxisType(kX_val);
|
||||
/**
|
||||
* axis: y-axis
|
||||
*/
|
||||
public static final AxisType kY = new AxisType(kY_val);
|
||||
/**
|
||||
* axis: z-axis
|
||||
*/
|
||||
public static final AxisType kZ = new AxisType(kZ_val);
|
||||
/**
|
||||
* axis: twist
|
||||
*/
|
||||
public static final AxisType kTwist = new AxisType(kTwist_val);
|
||||
/**
|
||||
* axis: throttle
|
||||
*/
|
||||
public static final AxisType kThrottle = new AxisType(kThrottle_val);
|
||||
/**
|
||||
* axis: number of axis
|
||||
*/
|
||||
public static final AxisType kNumAxis = new AxisType(kNumAxis_val);
|
||||
|
||||
private AxisType(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Represents a digital button on the JoyStick
|
||||
*/
|
||||
public static class ButtonType {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kTrigger_val = 0;
|
||||
static final int kTop_val = 1;
|
||||
static final int kNumButton_val = 2;
|
||||
/**
|
||||
* button: trigger
|
||||
*/
|
||||
public static final ButtonType kTrigger = new ButtonType((kTrigger_val));
|
||||
/**
|
||||
* button: top button
|
||||
*/
|
||||
public static final ButtonType kTop = new ButtonType(kTop_val);
|
||||
/**
|
||||
* button: num button types
|
||||
*/
|
||||
public static final ButtonType kNumButton = new ButtonType((kNumButton_val));
|
||||
|
||||
private ButtonType(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
private DriverStation m_ds;
|
||||
private final int m_port;
|
||||
private final byte[] m_axes;
|
||||
private final byte[] m_buttons;
|
||||
|
||||
/**
|
||||
* Construct an instance of a joystick.
|
||||
* The joystick index is the usb port on the drivers station.
|
||||
*
|
||||
* @param port The port on the driver station that the joystick is plugged into.
|
||||
*/
|
||||
public Joystick(final int port) {
|
||||
this(port, AxisType.kNumAxis.value, ButtonType.kNumButton.value);
|
||||
|
||||
m_axes[AxisType.kX.value] = kDefaultXAxis;
|
||||
m_axes[AxisType.kY.value] = kDefaultYAxis;
|
||||
m_axes[AxisType.kZ.value] = kDefaultZAxis;
|
||||
m_axes[AxisType.kTwist.value] = kDefaultTwistAxis;
|
||||
m_axes[AxisType.kThrottle.value] = kDefaultThrottleAxis;
|
||||
|
||||
m_buttons[ButtonType.kTrigger.value] = kDefaultTriggerButton;
|
||||
m_buttons[ButtonType.kTop.value] = kDefaultTopButton;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Joystick, port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Protected version of the constructor to be called by sub-classes.
|
||||
*
|
||||
* This constructor allows the subclass to configure the number of constants
|
||||
* for axes and buttons.
|
||||
*
|
||||
* @param port The port on the driver station that the joystick is plugged into.
|
||||
* @param numAxisTypes The number of axis types in the enum.
|
||||
* @param numButtonTypes The number of button types in the enum.
|
||||
*/
|
||||
protected Joystick(int port, int numAxisTypes, int numButtonTypes) {
|
||||
m_ds = DriverStation.getInstance();
|
||||
m_axes = new byte[numAxisTypes];
|
||||
m_buttons = new byte[numButtonTypes];
|
||||
m_port = port;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the X value of the joystick.
|
||||
* This depends on the mapping of the joystick connected to the current port.
|
||||
*
|
||||
* @param hand Unused
|
||||
* @return The X value of the joystick.
|
||||
*/
|
||||
public double getX(Hand hand) {
|
||||
return getRawAxis(m_axes[AxisType.kX.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Y value of the joystick.
|
||||
* This depends on the mapping of the joystick connected to the current port.
|
||||
*
|
||||
* @param hand Unused
|
||||
* @return The Y value of the joystick.
|
||||
*/
|
||||
public double getY(Hand hand) {
|
||||
return getRawAxis(m_axes[AxisType.kY.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Z value of the joystick.
|
||||
* This depends on the mapping of the joystick connected to the current port.
|
||||
*
|
||||
* @param hand Unused
|
||||
* @return The Z value of the joystick.
|
||||
*/
|
||||
public double getZ(Hand hand) {
|
||||
return getRawAxis(m_axes[AxisType.kZ.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the twist value of the current joystick.
|
||||
* This depends on the mapping of the joystick connected to the current port.
|
||||
*
|
||||
* @return The Twist value of the joystick.
|
||||
*/
|
||||
public double getTwist() {
|
||||
return getRawAxis(m_axes[AxisType.kTwist.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the throttle value of the current joystick.
|
||||
* This depends on the mapping of the joystick connected to the current port.
|
||||
*
|
||||
* @return The Throttle value of the joystick.
|
||||
*/
|
||||
public double getThrottle() {
|
||||
return getRawAxis(m_axes[AxisType.kThrottle.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of the axis.
|
||||
*
|
||||
* @param axis The axis to read [1-6].
|
||||
* @return The value of the axis.
|
||||
*/
|
||||
public double getRawAxis(final int axis) {
|
||||
return m_ds.getStickAxis(m_port, axis);
|
||||
}
|
||||
|
||||
/**
|
||||
* For the current joystick, return the axis determined by the argument.
|
||||
*
|
||||
* This is for cases where the joystick axis is returned programatically, otherwise one of the
|
||||
* previous functions would be preferable (for example getX()).
|
||||
*
|
||||
* @param axis The axis to read.
|
||||
* @return The value of the axis.
|
||||
*/
|
||||
public double getAxis(final AxisType axis) {
|
||||
switch (axis.value) {
|
||||
case AxisType.kX_val:
|
||||
return getX();
|
||||
case AxisType.kY_val:
|
||||
return getY();
|
||||
case AxisType.kZ_val:
|
||||
return getZ();
|
||||
case AxisType.kTwist_val:
|
||||
return getTwist();
|
||||
case AxisType.kThrottle_val:
|
||||
return getThrottle();
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the state of the trigger on the joystick.
|
||||
*
|
||||
* Look up which button has been assigned to the trigger and read its state.
|
||||
*
|
||||
* @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
|
||||
* @return The state of the trigger.
|
||||
*/
|
||||
public boolean getTrigger(Hand hand) {
|
||||
return getRawButton(m_buttons[ButtonType.kTrigger.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the state of the top button on the joystick.
|
||||
*
|
||||
* Look up which button has been assigned to the top and read its state.
|
||||
*
|
||||
* @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
|
||||
* @return The state of the top button.
|
||||
*/
|
||||
public boolean getTop(Hand hand) {
|
||||
return getRawButton(m_buttons[ButtonType.kTop.value]);
|
||||
}
|
||||
|
||||
/**
|
||||
* This is not supported for the Joystick.
|
||||
* This method is only here to complete the GenericHID interface.
|
||||
*
|
||||
* @param hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface.
|
||||
* @return The state of the bumper (always false)
|
||||
*/
|
||||
public boolean getBumper(Hand hand) {
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the button value for buttons 1 through 12.
|
||||
*
|
||||
* The buttons are returned in a single 16 bit value with one bit representing the state
|
||||
* of each button. The appropriate button is returned as a boolean value.
|
||||
*
|
||||
* @param button The button number to be read.
|
||||
* @return The state of the button.
|
||||
*/
|
||||
public boolean getRawButton(final int button) {
|
||||
return ((0x1 << (button - 1)) & m_ds.getStickButtons(m_port)) != 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get buttons based on an enumerated type.
|
||||
*
|
||||
* The button type will be looked up in the list of buttons and then read.
|
||||
*
|
||||
* @param button The type of button to read.
|
||||
* @return The state of the button.
|
||||
*/
|
||||
public boolean getButton(ButtonType button) {
|
||||
switch (button.value) {
|
||||
case ButtonType.kTrigger_val:
|
||||
return getTrigger();
|
||||
case ButtonType.kTop_val:
|
||||
return getTop();
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the magnitude of the direction vector formed by the joystick's
|
||||
* current position relative to its origin
|
||||
*
|
||||
* @return The magnitude of the direction vector
|
||||
*/
|
||||
public double getMagnitude() {
|
||||
return Math.sqrt(Math.pow(getX(), 2) + Math.pow(getY(), 2));
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the direction of the vector formed by the joystick and its origin
|
||||
* in radians
|
||||
*
|
||||
* @return The direction of the vector in radians
|
||||
*/
|
||||
public double getDirectionRadians() {
|
||||
return Math.atan2(getX(), -getY());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the direction of the vector formed by the joystick and its origin
|
||||
* in degrees
|
||||
*
|
||||
* uses acos(-1) to represent Pi due to absence of readily accessable Pi
|
||||
* constant in C++
|
||||
*
|
||||
* @return The direction of the vector in degrees
|
||||
*/
|
||||
public double getDirectionDegrees() {
|
||||
return Math.toDegrees(getDirectionRadians());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the channel currently associated with the specified axis.
|
||||
*
|
||||
* @param axis The axis to look up the channel for.
|
||||
* @return The channel fr the axis.
|
||||
*/
|
||||
public int getAxisChannel(AxisType axis) {
|
||||
return m_axes[axis.value];
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the channel associated with a specified axis.
|
||||
*
|
||||
* @param axis The axis to set the channel for.
|
||||
* @param channel The channel to set the axis to.
|
||||
*/
|
||||
public void setAxisChannel(AxisType axis, int channel) {
|
||||
m_axes[axis.value] = (byte) channel;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,493 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.PWMJNI;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
|
||||
/**
|
||||
* Class implements the PWM generation in the FPGA.
|
||||
* Values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped
|
||||
* to the hardware dependent values, in this case 0-255 for the FPGA.
|
||||
* Changes are immediately sent to the FPGA, and the update occurs at the next
|
||||
* FPGA cycle. There is no delay.
|
||||
*
|
||||
* As of revision 0.1.4 of the FPGA, the FPGA interprets the 0-255 values as follows:
|
||||
* 255 = full "forward"
|
||||
* 254 to 129 = linear scaling from "full forward" to "center"
|
||||
* 128 = center value
|
||||
* 127 to 2 = linear scaling from "center" to "full reverse"
|
||||
* 1 = full "reverse"
|
||||
* 0 = disabled (i.e. PWM output is held low)
|
||||
*/
|
||||
public class PWM extends SensorBase implements LiveWindowSendable {
|
||||
private static Resource allocated = new Resource( kPwmChannels);
|
||||
|
||||
/**
|
||||
* Represents the amount to multiply the minimum servo-pulse pwm period by.
|
||||
*/
|
||||
public static class PeriodMultiplier {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int k1X_val = 1;
|
||||
static final int k2X_val = 2;
|
||||
static final int k4X_val = 4;
|
||||
/**
|
||||
* Period Multiplier: don't skip pulses
|
||||
*/
|
||||
public static final PeriodMultiplier k1X = new PeriodMultiplier(k1X_val);
|
||||
/**
|
||||
* Period Multiplier: skip every other pulse
|
||||
*/
|
||||
public static final PeriodMultiplier k2X = new PeriodMultiplier(k2X_val);
|
||||
/**
|
||||
* Period Multiplier: skip three out of four pulses
|
||||
*/
|
||||
public static final PeriodMultiplier k4X = new PeriodMultiplier(k4X_val);
|
||||
|
||||
private PeriodMultiplier(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
private int m_channel;
|
||||
private ByteBuffer m_port;
|
||||
/**
|
||||
* kDefaultPwmPeriod is in ms
|
||||
*
|
||||
* - 20ms periods (50 Hz) are the "safest" setting in that this works for all devices
|
||||
* - 20ms periods seem to be desirable for Vex Motors
|
||||
* - 20ms periods are the specified period for HS-322HD servos, but work reliably down
|
||||
* to 10.0 ms; starting at about 8.5ms, the servo sometimes hums and get hot;
|
||||
* by 5.0ms the hum is nearly continuous
|
||||
* - 10ms periods work well for Victor 884
|
||||
* - 5ms periods allows higher update rates for Luminary Micro Jaguar speed controllers.
|
||||
* Due to the shipping firmware on the Jaguar, we can't run the update period less
|
||||
* than 5.05 ms.
|
||||
*
|
||||
* kDefaultPwmPeriod is the 1x period (5.05 ms). In hardware, the period scaling is implemented as an
|
||||
* output squelch to get longer periods for old devices.
|
||||
*/
|
||||
protected static final double kDefaultPwmPeriod = 5.05;
|
||||
/**
|
||||
* kDefaultPwmCenter is the PWM range center in ms
|
||||
*/
|
||||
protected static final double kDefaultPwmCenter = 1.5;
|
||||
/**
|
||||
* kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
|
||||
*/
|
||||
protected static final int kDefaultPwmStepsDown = 1000;
|
||||
public static final int kPwmDisabled = 0;
|
||||
boolean m_eliminateDeadband;
|
||||
int m_maxPwm;
|
||||
int m_deadbandMaxPwm;
|
||||
int m_centerPwm;
|
||||
int m_deadbandMinPwm;
|
||||
int m_minPwm;
|
||||
|
||||
/**
|
||||
* Initialize PWMs given a channel.
|
||||
*
|
||||
* This method is private and is the common path for all the constructors
|
||||
* for creating PWM instances. Checks channel value ranges and allocates
|
||||
* the appropriate channel. The allocation is only done to help users
|
||||
* ensure that they don't double assign channels.
|
||||
*/
|
||||
private void initPWM(final int channel) {
|
||||
checkPWMChannel(channel);
|
||||
try {
|
||||
allocated.allocate(channel);
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException(
|
||||
"PWM channel " + channel + " is already allocated");
|
||||
}
|
||||
m_channel = channel;
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
m_port = DIOJNI.initializeDigitalPort(DIOJNI.getPort((byte) m_channel), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
PWMJNI.setPWM(m_port, (short) 0, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
m_eliminateDeadband = false;
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_PWM, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Allocate a PWM given a channel.
|
||||
*
|
||||
* @param channel The PWM channel.
|
||||
*/
|
||||
public PWM(final int channel) {
|
||||
initPWM(channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the PWM channel.
|
||||
*
|
||||
* Free the resource associated with the PWM channel and set the value to 0.
|
||||
*/
|
||||
public void free() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
PWMJNI.setPWM(m_port, (short) 0, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
PWMJNI.freeDIO(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
allocated.free(m_channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Optionally eliminate the deadband from a speed controller.
|
||||
* @param eliminateDeadband If true, set the motor curve on the Jaguar to eliminate
|
||||
* the deadband in the middle of the range. Otherwise, keep the full range without
|
||||
* modifying any values.
|
||||
*/
|
||||
public void enableDeadbandElimination(boolean eliminateDeadband) {
|
||||
m_eliminateDeadband = eliminateDeadband;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the bounds on the PWM values.
|
||||
* This sets the bounds on the PWM values for a particular each type of controller. The values
|
||||
* determine the upper and lower speeds as well as the deadband bracket.
|
||||
* @deprecated Recommended to set bounds in ms using {@link #setBounds(double, double, double, double, double)}
|
||||
* @param max The Minimum pwm value
|
||||
* @param deadbandMax The high end of the deadband range
|
||||
* @param center The center speed (off)
|
||||
* @param deadbandMin The low end of the deadband range
|
||||
* @param min The minimum pwm value
|
||||
*/
|
||||
public void setBounds(final int max, final int deadbandMax, final int center, final int deadbandMin, final int min) {
|
||||
m_maxPwm = max;
|
||||
m_deadbandMaxPwm = deadbandMax;
|
||||
m_centerPwm = center;
|
||||
m_deadbandMinPwm = deadbandMin;
|
||||
m_minPwm = min;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the bounds on the PWM pulse widths.
|
||||
* This sets the bounds on the PWM values for a particular type of controller. The values
|
||||
* determine the upper and lower speeds as well as the deadband bracket.
|
||||
* @param max The max PWM pulse width in ms
|
||||
* @param deadbandMax The high end of the deadband range pulse width in ms
|
||||
* @param center The center (off) pulse width in ms
|
||||
* @param deadbandMin The low end of the deadband pulse width in ms
|
||||
* @param min The minimum pulse width in ms
|
||||
*/
|
||||
protected void setBounds(double max, double deadbandMax, double center, double deadbandMin, double min) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double loopTime = DIOJNI.getLoopTiming(status.asIntBuffer())/(kSystemClockTicksPerMicrosecond*1e3);
|
||||
|
||||
m_maxPwm = (int)((max-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1);
|
||||
m_deadbandMaxPwm = (int)((deadbandMax-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1);
|
||||
m_centerPwm = (int)((center-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1);
|
||||
m_deadbandMinPwm = (int)((deadbandMin-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1);
|
||||
m_minPwm = (int)((min-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the channel number associated with the PWM Object.
|
||||
*
|
||||
* @return The channel number.
|
||||
*/
|
||||
public int getChannel() {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value based on a position.
|
||||
*
|
||||
* This is intended to be used by servos.
|
||||
*
|
||||
* @pre SetMaxPositivePwm() called.
|
||||
* @pre SetMinNegativePwm() called.
|
||||
*
|
||||
* @param pos The position to set the servo between 0.0 and 1.0.
|
||||
*/
|
||||
public void setPosition(double pos) {
|
||||
if (pos < 0.0) {
|
||||
pos = 0.0;
|
||||
} else if (pos > 1.0) {
|
||||
pos = 1.0;
|
||||
}
|
||||
|
||||
int rawValue;
|
||||
// note, need to perform the multiplication below as floating point before converting to int
|
||||
rawValue = (int) ((pos * (double)getFullRangeScaleFactor()) + getMinNegativePwm());
|
||||
|
||||
// send the computed pwm value to the FPGA
|
||||
setRaw(rawValue);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the PWM value in terms of a position.
|
||||
*
|
||||
* This is intended to be used by servos.
|
||||
*
|
||||
* @pre SetMaxPositivePwm() called.
|
||||
* @pre SetMinNegativePwm() called.
|
||||
*
|
||||
* @return The position the servo is set to between 0.0 and 1.0.
|
||||
*/
|
||||
public double getPosition() {
|
||||
int value = getRaw();
|
||||
if (value < getMinNegativePwm()) {
|
||||
return 0.0;
|
||||
} else if (value > getMaxPositivePwm()) {
|
||||
return 1.0;
|
||||
} else {
|
||||
return (double)(value - getMinNegativePwm()) / (double)getFullRangeScaleFactor();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value based on a speed.
|
||||
*
|
||||
* This is intended to be used by speed controllers.
|
||||
*
|
||||
* @pre SetMaxPositivePwm() called.
|
||||
* @pre SetMinPositivePwm() called.
|
||||
* @pre SetCenterPwm() called.
|
||||
* @pre SetMaxNegativePwm() called.
|
||||
* @pre SetMinNegativePwm() called.
|
||||
*
|
||||
* @param speed The speed to set the speed controller between -1.0 and 1.0.
|
||||
*/
|
||||
final void setSpeed(double speed) {
|
||||
// clamp speed to be in the range 1.0 >= speed >= -1.0
|
||||
if (speed < -1.0) {
|
||||
speed = -1.0;
|
||||
} else if (speed > 1.0) {
|
||||
speed = 1.0;
|
||||
}
|
||||
|
||||
// calculate the desired output pwm value by scaling the speed appropriately
|
||||
int rawValue;
|
||||
if (speed == 0.0) {
|
||||
rawValue = getCenterPwm();
|
||||
} else if (speed > 0.0) {
|
||||
rawValue = (int) (speed * ((double)getPositiveScaleFactor()) +
|
||||
((double)getMinPositivePwm()) + 0.5);
|
||||
} else {
|
||||
rawValue = (int) (speed * ((double)getNegativeScaleFactor()) +
|
||||
((double)getMaxNegativePwm()) + 0.5);
|
||||
}
|
||||
|
||||
// send the computed pwm value to the FPGA
|
||||
setRaw(rawValue);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the PWM value in terms of speed.
|
||||
*
|
||||
* This is intended to be used by speed controllers.
|
||||
*
|
||||
* @pre SetMaxPositivePwm() called.
|
||||
* @pre SetMinPositivePwm() called.
|
||||
* @pre SetMaxNegativePwm() called.
|
||||
* @pre SetMinNegativePwm() called.
|
||||
*
|
||||
* @return The most recently set speed between -1.0 and 1.0.
|
||||
*/
|
||||
public double getSpeed() {
|
||||
int value = getRaw();
|
||||
if (value > getMaxPositivePwm()) {
|
||||
return 1.0;
|
||||
} else if (value < getMinNegativePwm()) {
|
||||
return -1.0;
|
||||
} else if (value > getMinPositivePwm()) {
|
||||
return (double) (value - getMinPositivePwm()) / (double)getPositiveScaleFactor();
|
||||
} else if (value < getMaxNegativePwm()) {
|
||||
return (double) (value - getMaxNegativePwm()) / (double)getNegativeScaleFactor();
|
||||
} else {
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value directly to the hardware.
|
||||
*
|
||||
* Write a raw value to a PWM channel.
|
||||
*
|
||||
* @param value Raw PWM value. Range 0 - 255.
|
||||
*/
|
||||
public void setRaw(int value) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
PWMJNI.setPWM(m_port, (short) value, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the PWM value directly from the hardware.
|
||||
*
|
||||
* Read a raw value from a PWM channel.
|
||||
*
|
||||
* @return Raw PWM control value. Range: 0 - 255.
|
||||
*/
|
||||
public int getRaw() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
int value = PWMJNI.getPWM(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Slow down the PWM signal for old devices.
|
||||
*
|
||||
* @param mult The period multiplier to apply to this channel
|
||||
*/
|
||||
public void setPeriodMultiplier(PeriodMultiplier mult) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
switch (mult.value) {
|
||||
case PeriodMultiplier.k4X_val:
|
||||
// Squelch 3 out of 4 outputs
|
||||
PWMJNI.setPWMPeriodScale(m_port, 3, status.asIntBuffer());
|
||||
break;
|
||||
case PeriodMultiplier.k2X_val:
|
||||
// Squelch 1 out of 2 outputs
|
||||
PWMJNI.setPWMPeriodScale(m_port, 1, status.asIntBuffer());
|
||||
break;
|
||||
case PeriodMultiplier.k1X_val:
|
||||
// Don't squelch any outputs
|
||||
PWMJNI.setPWMPeriodScale(m_port, 0, status.asIntBuffer());
|
||||
break;
|
||||
default:
|
||||
//Cannot hit this, limited by PeriodMultiplier enum
|
||||
}
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
private int getMaxPositivePwm() {
|
||||
return m_maxPwm;
|
||||
}
|
||||
|
||||
;
|
||||
|
||||
private int getMinPositivePwm() {
|
||||
return m_eliminateDeadband ? m_deadbandMaxPwm : m_centerPwm + 1;
|
||||
}
|
||||
|
||||
;
|
||||
|
||||
private int getCenterPwm() {
|
||||
return m_centerPwm;
|
||||
}
|
||||
|
||||
;
|
||||
|
||||
private int getMaxNegativePwm() {
|
||||
return m_eliminateDeadband ? m_deadbandMinPwm : m_centerPwm - 1;
|
||||
}
|
||||
|
||||
;
|
||||
|
||||
private int getMinNegativePwm() {
|
||||
return m_minPwm;
|
||||
}
|
||||
|
||||
;
|
||||
|
||||
private int getPositiveScaleFactor() {
|
||||
return getMaxPositivePwm() - getMinPositivePwm();
|
||||
} ///< The scale for positive speeds.
|
||||
|
||||
private int getNegativeScaleFactor() {
|
||||
return getMaxNegativePwm() - getMinNegativePwm();
|
||||
} ///< The scale for negative speeds.
|
||||
|
||||
private int getFullRangeScaleFactor() {
|
||||
return getMaxPositivePwm() - getMinNegativePwm();
|
||||
} ///< The scale for positions.
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Speed Controller";
|
||||
}
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getSpeed());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
setSpeed(0); // Stop for safety
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value, boolean bln) {
|
||||
setSpeed(((Double) value).doubleValue());
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
setSpeed(0); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,62 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.PDPJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
|
||||
/**
|
||||
* Class for getting voltage, current, and temperature from the CAN PDP
|
||||
* @author Thomas Clark
|
||||
*/
|
||||
public class PowerDistributionPanel extends SensorBase {
|
||||
public PowerDistributionPanel() {
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The voltage of the PDP
|
||||
*/
|
||||
public double getVoltage() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double voltage = PDPJNI.getPDPVoltage(status.asIntBuffer());
|
||||
|
||||
return voltage;
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The temperature of the PDP in degrees Celsius
|
||||
*/
|
||||
public double getTemperature() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double temperature = PDPJNI.getPDPTemperature(status.asIntBuffer());
|
||||
|
||||
return temperature;
|
||||
}
|
||||
|
||||
/**
|
||||
* @return The current of one of the PDP channels (channels 0-15) in Amperes
|
||||
*/
|
||||
public double getCurrent(int channel) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
double current = PDPJNI.getPDPChannelCurrent((byte)channel, status.asIntBuffer());
|
||||
|
||||
checkPDPChannel(channel);
|
||||
|
||||
return current;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,827 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.FileInputStream;
|
||||
import java.io.FileOutputStream;
|
||||
import java.io.IOException;
|
||||
import java.io.InputStream;
|
||||
import java.io.OutputStream;
|
||||
import java.util.Hashtable;
|
||||
import java.util.Vector;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* The preferences class provides a relatively simple way to save important
|
||||
* values to the cRIO to access the next time the cRIO is booted.
|
||||
*
|
||||
* <p>This class loads and saves from a file inside the cRIO. The user can not
|
||||
* access the file directly, but may modify values at specific fields which will
|
||||
* then be saved to the file when {@link Preferences#save() save()} is
|
||||
* called.</p>
|
||||
*
|
||||
* <p>This class is thread safe.</p>
|
||||
*
|
||||
* <p>This will also interact with {@link NetworkTable} by creating a table
|
||||
* called "Preferences" with all the key-value pairs. To save using
|
||||
* {@link NetworkTable}, simply set the boolean at position ~S A V E~ to true.
|
||||
* Also, if the value of any variable is " in the {@link NetworkTable}, then
|
||||
* that represents non-existence in the {@link Preferences} table</p>
|
||||
*
|
||||
* @author Joe Grinstead
|
||||
*/
|
||||
public class Preferences {
|
||||
|
||||
/**
|
||||
* The Preferences table name
|
||||
*/
|
||||
private static final String TABLE_NAME = "Preferences";
|
||||
/**
|
||||
* The value of the save field
|
||||
*/
|
||||
private static final String SAVE_FIELD = "~S A V E~";
|
||||
/**
|
||||
* The file to save to
|
||||
*/
|
||||
private static final String FILE_NAME = "wpilib-preferences.ini";
|
||||
/**
|
||||
* The characters to put between a field and value
|
||||
*/
|
||||
private static final byte[] VALUE_PREFIX = {'=', '\"'};
|
||||
/**
|
||||
* The characters to put after the value
|
||||
*/
|
||||
private static final byte[] VALUE_SUFFIX = {'\"', '\n'};
|
||||
/**
|
||||
* The newline character
|
||||
*/
|
||||
private static final byte[] NEW_LINE = {'\n'};
|
||||
/**
|
||||
* The singleton instance
|
||||
*/
|
||||
private static Preferences instance;
|
||||
|
||||
/**
|
||||
* Returns the preferences instance.
|
||||
*
|
||||
* @return the preferences instance
|
||||
*/
|
||||
public synchronized static Preferences getInstance() {
|
||||
if (instance == null) {
|
||||
instance = new Preferences();
|
||||
}
|
||||
return instance;
|
||||
}
|
||||
/**
|
||||
* The semaphore for beginning reads and writes to the file
|
||||
*/
|
||||
private final Object fileLock = new Object();
|
||||
/**
|
||||
* The semaphore for reading from the table
|
||||
*/
|
||||
private final Object lock = new Object();
|
||||
/**
|
||||
* The actual values (String->String)
|
||||
*/
|
||||
private Hashtable values;
|
||||
/**
|
||||
* The keys in the order they were read from the file
|
||||
*/
|
||||
private Vector keys;
|
||||
/**
|
||||
* The comments that were in the file sorted by which key they appeared over
|
||||
* (String->Comment)
|
||||
*/
|
||||
private Hashtable comments;
|
||||
/**
|
||||
* The comment at the end of the file
|
||||
*/
|
||||
private Comment endComment;
|
||||
|
||||
/**
|
||||
* Creates a preference class that will automatically read the file in a
|
||||
* different thread. Any call to its methods will be blocked until the
|
||||
* thread is finished reading.
|
||||
*/
|
||||
private Preferences() {
|
||||
values = new Hashtable();
|
||||
keys = new Vector();
|
||||
|
||||
// We synchronized on fileLock and then wait
|
||||
// for it to know that the reading thread has started
|
||||
synchronized (fileLock) {
|
||||
new Thread() {
|
||||
public void run() {
|
||||
read();
|
||||
}
|
||||
} .start();
|
||||
try {
|
||||
fileLock.wait();
|
||||
} catch (InterruptedException ex) {
|
||||
}
|
||||
}
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Preferences, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @return a vector of the keys
|
||||
*/
|
||||
public Vector getKeys() {
|
||||
synchronized (lock) {
|
||||
return keys;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given value into the given key position
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains an illegal
|
||||
* character
|
||||
*/
|
||||
private void put(String key, String value) {
|
||||
synchronized (lock) {
|
||||
if (key == null) {
|
||||
throw new NullPointerException();
|
||||
}
|
||||
ImproperPreferenceKeyException.confirmString(key);
|
||||
if (values.put(key, value) == null) {
|
||||
keys.addElement(key);
|
||||
}
|
||||
NetworkTable.getTable(TABLE_NAME).putString(key, value);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given string into the preferences table.
|
||||
*
|
||||
* <p>The value may not have quotation marks, nor may the key have any
|
||||
* whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care). at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws NullPointerException if value is null
|
||||
* @throws IllegalArgumentException if value contains a quotation mark
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putString(String key, String value) {
|
||||
if (value == null) {
|
||||
throw new NullPointerException();
|
||||
}
|
||||
if (value.indexOf('"') != -1) {
|
||||
throw new IllegalArgumentException("Can not put string:" + value + " because it contains quotation marks");
|
||||
}
|
||||
put(key, value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given int into the preferences table.
|
||||
*
|
||||
* <p>The key may not have any whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care) at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putInt(String key, int value) {
|
||||
put(key, String.valueOf(value));
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given double into the preferences table.
|
||||
*
|
||||
* <p>The key may not have any whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care) at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putDouble(String key, double value) {
|
||||
put(key, String.valueOf(value));
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given float into the preferences table.
|
||||
*
|
||||
* <p>The key may not have any whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care) at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putFloat(String key, float value) {
|
||||
put(key, String.valueOf(value));
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given boolean into the preferences table.
|
||||
*
|
||||
* <p>The key may not have any whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care) at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putBoolean(String key, boolean value) {
|
||||
put(key, String.valueOf(value));
|
||||
}
|
||||
|
||||
/**
|
||||
* Puts the given long into the preferences table.
|
||||
*
|
||||
* <p>The key may not have any whitespace nor an equals sign</p>
|
||||
*
|
||||
* <p>This will <b>NOT</b> save the value to memory between power cycles, to
|
||||
* do that you must call {@link Preferences#save() save()} (which must be
|
||||
* used with care) at some point after calling this.</p>
|
||||
*
|
||||
* @param key the key
|
||||
* @param value the value
|
||||
* @throws ImproperPreferenceKeyException if the key contains any whitespace
|
||||
* or an equals sign
|
||||
*/
|
||||
public void putLong(String key, long value) {
|
||||
put(key, String.valueOf(value));
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the value at the given key.
|
||||
*
|
||||
* @param key the key
|
||||
* @return the value (or null if none exists)
|
||||
* @throws NullPointerException if the key is null
|
||||
*/
|
||||
private String get(String key) {
|
||||
synchronized (lock) {
|
||||
if (key == null) {
|
||||
throw new NullPointerException();
|
||||
}
|
||||
return (String) values.get(key);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns whether or not there is a key with the given name.
|
||||
*
|
||||
* @param key the key
|
||||
* @return if there is a value at the given key
|
||||
* @throws NullPointerException if key is null
|
||||
*/
|
||||
public boolean containsKey(String key) {
|
||||
return get(key) != null;
|
||||
}
|
||||
|
||||
/**
|
||||
* Remove a preference
|
||||
*
|
||||
* @param key the key
|
||||
* @throws NullPointerException if key is null
|
||||
*/
|
||||
public void remove(String key) {
|
||||
synchronized (lock) {
|
||||
if (key == null) {
|
||||
throw new NullPointerException();
|
||||
}
|
||||
values.remove(key);
|
||||
keys.removeElement(key);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the string at the given key. If this table does not have a value
|
||||
* for that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws NullPointerException if the key is null
|
||||
*/
|
||||
public String getString(String key, String backup) {
|
||||
String value = get(key);
|
||||
return value == null ? backup : value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the int at the given key. If this table does not have a value for
|
||||
* that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws IncompatibleTypeException if the value in the table can not be
|
||||
* converted to an int
|
||||
*/
|
||||
public int getInt(String key, int backup) {
|
||||
String value = get(key);
|
||||
if (value == null) {
|
||||
return backup;
|
||||
} else {
|
||||
try {
|
||||
return Integer.parseInt(value);
|
||||
} catch (NumberFormatException e) {
|
||||
throw new IncompatibleTypeException(value, "int");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the double at the given key. If this table does not have a value
|
||||
* for that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws IncompatibleTypeException if the value in the table can not be
|
||||
* converted to an double
|
||||
*/
|
||||
public double getDouble(String key, double backup) {
|
||||
String value = get(key);
|
||||
if (value == null) {
|
||||
return backup;
|
||||
} else {
|
||||
try {
|
||||
return Double.parseDouble(value);
|
||||
} catch (NumberFormatException e) {
|
||||
throw new IncompatibleTypeException(value, "double");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the boolean at the given key. If this table does not have a value
|
||||
* for that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws IncompatibleTypeException if the value in the table can not be
|
||||
* converted to a boolean
|
||||
*/
|
||||
public boolean getBoolean(String key, boolean backup) {
|
||||
String value = get(key);
|
||||
if (value == null) {
|
||||
return backup;
|
||||
} else {
|
||||
if (value.equalsIgnoreCase("true")) {
|
||||
return true;
|
||||
} else if (value.equalsIgnoreCase("false")) {
|
||||
return false;
|
||||
} else {
|
||||
throw new IncompatibleTypeException(value, "boolean");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the float at the given key. If this table does not have a value
|
||||
* for that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws IncompatibleTypeException if the value in the table can not be
|
||||
* converted to a float
|
||||
*/
|
||||
public float getFloat(String key, float backup) {
|
||||
String value = get(key);
|
||||
if (value == null) {
|
||||
return backup;
|
||||
} else {
|
||||
try {
|
||||
return Float.parseFloat(value);
|
||||
} catch (NumberFormatException e) {
|
||||
throw new IncompatibleTypeException(value, "float");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the long at the given key. If this table does not have a value
|
||||
* for that position, then the given backup value will be returned.
|
||||
*
|
||||
* @param key the key
|
||||
* @param backup the value to return if none exists in the table
|
||||
* @return either the value in the table, or the backup
|
||||
* @throws IncompatibleTypeException if the value in the table can not be
|
||||
* converted to a long
|
||||
*/
|
||||
public long getLong(String key, long backup) {
|
||||
String value = get(key);
|
||||
if (value == null) {
|
||||
put(key, String.valueOf(backup));
|
||||
return backup;
|
||||
} else {
|
||||
try {
|
||||
return Long.parseLong(value);
|
||||
} catch (NumberFormatException e) {
|
||||
throw new IncompatibleTypeException(value, "long");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Saves the preferences to a file on the cRIO.
|
||||
*
|
||||
* <p>This should <b>NOT</b> be called often. Too many writes can damage the
|
||||
* cRIO's flash memory. While it is ok to save once or twice a match, this
|
||||
* should never be called every run of
|
||||
* {@link IterativeRobot#teleopPeriodic()}.</p>
|
||||
*
|
||||
* <p>The actual writing of the file is done in a separate thread. However,
|
||||
* any call to a get or put method will wait until the table is fully saved
|
||||
* before continuing.</p>
|
||||
*/
|
||||
public void save() {
|
||||
synchronized (fileLock) {
|
||||
new Thread() {
|
||||
public void run() {
|
||||
write();
|
||||
}
|
||||
} .start();
|
||||
try {
|
||||
fileLock.wait();
|
||||
} catch (InterruptedException ex) {
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Internal method that actually writes the table to a file. This is called
|
||||
* in its own thread when {@link Preferences#save() save()} is called.
|
||||
*/
|
||||
private void write() {
|
||||
synchronized (lock) {
|
||||
synchronized (fileLock) {
|
||||
fileLock.notifyAll();
|
||||
}
|
||||
|
||||
File file = null;
|
||||
FileOutputStream output = null;
|
||||
try {
|
||||
file = new File(FILE_NAME);
|
||||
|
||||
if (file.exists())
|
||||
file.delete();
|
||||
|
||||
file.createNewFile();
|
||||
|
||||
output = new FileOutputStream(file);
|
||||
|
||||
for (int i = 0; i < keys.size(); i++) {
|
||||
String key = (String) keys.elementAt(i);
|
||||
String value = (String) values.get(key);
|
||||
|
||||
if (comments != null) {
|
||||
Comment comment = (Comment) comments.get(key);
|
||||
if (comment != null) {
|
||||
comment.write(output);
|
||||
}
|
||||
}
|
||||
|
||||
output.write(key.getBytes());
|
||||
output.write(VALUE_PREFIX);
|
||||
output.write(value.getBytes());
|
||||
output.write(VALUE_SUFFIX);
|
||||
}
|
||||
|
||||
if (endComment != null) {
|
||||
endComment.write(output);
|
||||
}
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
} finally {
|
||||
if (output != null) {
|
||||
try {
|
||||
output.close();
|
||||
} catch (IOException ex) {
|
||||
}
|
||||
}
|
||||
NetworkTable.getTable(TABLE_NAME).putBoolean(SAVE_FIELD, false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The internal method to read from a file. This will be called in its own
|
||||
* thread when the preferences singleton is first created.
|
||||
*/
|
||||
private void read() {
|
||||
class EndOfStreamException extends Exception {
|
||||
}
|
||||
|
||||
class Reader {
|
||||
|
||||
InputStream stream;
|
||||
|
||||
Reader(InputStream stream) {
|
||||
this.stream = stream;
|
||||
}
|
||||
|
||||
public char read() throws IOException, EndOfStreamException {
|
||||
int input = stream.read();
|
||||
if (input == -1) {
|
||||
throw new EndOfStreamException();
|
||||
} else {
|
||||
// Check for carriage returns
|
||||
return input == '\r' ? '\n' : (char) input;
|
||||
}
|
||||
}
|
||||
|
||||
char readWithoutWhitespace() throws IOException, EndOfStreamException {
|
||||
while (true) {
|
||||
char value = read();
|
||||
switch (value) {
|
||||
case ' ':
|
||||
case '\t':
|
||||
continue;
|
||||
default:
|
||||
return value;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
synchronized (lock) {
|
||||
synchronized (fileLock) {
|
||||
fileLock.notifyAll();
|
||||
}
|
||||
|
||||
Comment comment = null;
|
||||
|
||||
|
||||
|
||||
File file = null;
|
||||
FileInputStream input = null;
|
||||
try {
|
||||
file = new File(FILE_NAME);
|
||||
|
||||
if (file.exists()) {
|
||||
input = new FileInputStream(file);
|
||||
Reader reader = new Reader(input);
|
||||
|
||||
StringBuffer buffer;
|
||||
|
||||
while (true) {
|
||||
char value = reader.readWithoutWhitespace();
|
||||
|
||||
if (value == '\n' || value == ';') {
|
||||
if (comment == null) {
|
||||
comment = new Comment();
|
||||
}
|
||||
|
||||
if (value == '\n') {
|
||||
comment.addBytes(NEW_LINE);
|
||||
} else {
|
||||
buffer = new StringBuffer(30);
|
||||
for (; value != '\n'; value = reader.read()) {
|
||||
buffer.append(value);
|
||||
}
|
||||
buffer.append('\n');
|
||||
comment.addBytes(buffer.toString().getBytes());
|
||||
}
|
||||
} else {
|
||||
buffer = new StringBuffer(30);
|
||||
for (; value != '='; value = reader.readWithoutWhitespace()) {
|
||||
buffer.append(value);
|
||||
}
|
||||
String name = buffer.toString();
|
||||
buffer = new StringBuffer(30);
|
||||
|
||||
boolean shouldBreak = false;
|
||||
|
||||
value = reader.readWithoutWhitespace();
|
||||
if (value == '"') {
|
||||
for (value = reader.read(); value != '"'; value = reader.read()) {
|
||||
buffer.append(value);
|
||||
}
|
||||
// Clear the line
|
||||
while (reader.read() != '\n');
|
||||
} else {
|
||||
try {
|
||||
for (; value != '\n'; value = reader.readWithoutWhitespace()) {
|
||||
buffer.append(value);
|
||||
}
|
||||
} catch (EndOfStreamException e) {
|
||||
shouldBreak = true;
|
||||
}
|
||||
}
|
||||
|
||||
String result = buffer.toString();
|
||||
|
||||
keys.addElement(name);
|
||||
values.put(name, result);
|
||||
NetworkTable.getTable(TABLE_NAME).putString(name, result);
|
||||
|
||||
if (comment != null) {
|
||||
if (comments == null) {
|
||||
comments = new Hashtable();
|
||||
}
|
||||
comments.put(name, comment);
|
||||
comment = null;
|
||||
}
|
||||
|
||||
|
||||
if (shouldBreak) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} catch (IOException ex) {
|
||||
ex.printStackTrace();
|
||||
} catch (EndOfStreamException ex) {
|
||||
System.out.println("Done Reading");
|
||||
}
|
||||
|
||||
if (input != null) {
|
||||
try {
|
||||
input.close();
|
||||
} catch (IOException ex) {
|
||||
}
|
||||
}
|
||||
|
||||
if (comment != null) {
|
||||
endComment = comment;
|
||||
}
|
||||
}
|
||||
|
||||
NetworkTable.getTable(TABLE_NAME).putBoolean(SAVE_FIELD, false);
|
||||
// TODO: Verify that this works even though it changes with subtables.
|
||||
// Should work since preferences shouldn't have subtables.
|
||||
NetworkTable.getTable(TABLE_NAME).addTableListener(new ITableListener() {
|
||||
public void valueChanged(ITable source, String key, Object value, boolean isNew) {
|
||||
if (key.equals(SAVE_FIELD)) {
|
||||
if (((Boolean) value).booleanValue()) {
|
||||
save();
|
||||
}
|
||||
} else {
|
||||
synchronized (lock) {
|
||||
if (!ImproperPreferenceKeyException.isAcceptable(key) || value.toString().indexOf('"') != -1) {
|
||||
if (values.contains(key) || keys.contains(key)) {
|
||||
values.remove(key);
|
||||
keys.removeElement(key);
|
||||
NetworkTable.getTable(TABLE_NAME).putString(key, "\"");
|
||||
}
|
||||
} else {
|
||||
if (values.put(key, value.toString()) == null) {
|
||||
keys.addElement(key);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
/**
|
||||
* A class representing some comment lines in the ini file. This is used so
|
||||
* that if a programmer ever directly modifies the ini file, then his/her
|
||||
* comments will still be there after {@link Preferences#save() save()} is
|
||||
* called.
|
||||
*/
|
||||
private static class Comment {
|
||||
|
||||
/**
|
||||
* A vector of byte arrays. Each array represents a line to write
|
||||
*/
|
||||
private Vector bytes = new Vector();
|
||||
|
||||
/**
|
||||
* Appends the given bytes to the comment.
|
||||
*
|
||||
* @param bytes the bytes to add
|
||||
*/
|
||||
private void addBytes(byte[] bytes) {
|
||||
this.bytes.addElement(bytes);
|
||||
}
|
||||
|
||||
/**
|
||||
* Writes this comment to the given stream
|
||||
*
|
||||
* @param stream the stream to write to
|
||||
* @throws IOException if the stream has a problem
|
||||
*/
|
||||
private void write(OutputStream stream) throws IOException {
|
||||
for (int i = 0; i < bytes.size(); i++) {
|
||||
stream.write((byte[]) bytes.elementAt(i));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This exception is thrown if the a value requested cannot be converted to
|
||||
* the requested type.
|
||||
*/
|
||||
public static class IncompatibleTypeException extends RuntimeException {
|
||||
|
||||
/**
|
||||
* Creates an exception with a description based on the input
|
||||
*
|
||||
* @param value the value that can not be converted
|
||||
* @param type the type that the value can not be converted to
|
||||
*/
|
||||
public IncompatibleTypeException(String value, String type) {
|
||||
super("Cannot convert \"" + value + "\" into " + type);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Should be thrown if a string can not be used as a key in the preferences
|
||||
* file. This happens if the string contains a new line, a space, a tab, or
|
||||
* an equals sign.
|
||||
*/
|
||||
public static class ImproperPreferenceKeyException extends RuntimeException {
|
||||
|
||||
/**
|
||||
* Instantiates an exception with a descriptive message based on the
|
||||
* input.
|
||||
*
|
||||
* @param value the illegal key
|
||||
* @param letter the specific character that made it illegal
|
||||
*/
|
||||
public ImproperPreferenceKeyException(String value, char letter) {
|
||||
super("Preference key \""
|
||||
+ value + "\" is not allowed to contain letter with ASCII code:" + (byte) letter);
|
||||
}
|
||||
|
||||
/**
|
||||
* Tests if the given string is ok to use as a key in the preference
|
||||
* table. If not, then a {@link ImproperPreferenceKeyException} will be
|
||||
* thrown.
|
||||
*
|
||||
* @param value the value to test
|
||||
*/
|
||||
public static void confirmString(String value) {
|
||||
for (int i = 0; i < value.length(); i++) {
|
||||
char letter = value.charAt(i);
|
||||
switch (letter) {
|
||||
case '=':
|
||||
case '\n':
|
||||
case '\r':
|
||||
case ' ':
|
||||
case '\t':
|
||||
throw new ImproperPreferenceKeyException(value, letter);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns whether or not the given string is ok to use in the
|
||||
* preference table.
|
||||
*
|
||||
* @param value
|
||||
* @return
|
||||
*/
|
||||
public static boolean isAcceptable(String value) {
|
||||
for (int i = 0; i < value.length(); i++) {
|
||||
char letter = value.charAt(i);
|
||||
switch (letter) {
|
||||
case '=':
|
||||
case '\n':
|
||||
case '\r':
|
||||
case ' ':
|
||||
case '\t':
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,407 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.RelayJNI;
|
||||
import edu.wpi.first.wpilibj.hal.HALLibrary;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Class for VEX Robotics Spike style relay outputs. Relays are intended to be
|
||||
* connected to Spikes or similar relays. The relay channels controls a pair of
|
||||
* pins that are either both off, one on, the other on, or both on. This
|
||||
* translates into two Spike outputs at 0v, one at 12v and one at 0v, one at 0v
|
||||
* and the other at 12v, or two Spike outputs at 12V. This allows off, full
|
||||
* forward, or full reverse control of motors without variable speed. It also
|
||||
* allows the two channels (forward and reverse) to be used independently for
|
||||
* something that does not care about voltage polarity (like a solenoid).
|
||||
*/
|
||||
public class Relay extends SensorBase implements IDeviceController,
|
||||
LiveWindowSendable {
|
||||
/**
|
||||
* This class represents errors in trying to set relay values contradictory
|
||||
* to the direction to which the relay is set.
|
||||
*/
|
||||
public class InvalidValueException extends RuntimeException {
|
||||
|
||||
/**
|
||||
* Create a new exception with the given message
|
||||
*
|
||||
* @param message
|
||||
* the message to pass with the exception
|
||||
*/
|
||||
public InvalidValueException(String message) {
|
||||
super(message);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The state to drive a Relay to.
|
||||
*/
|
||||
public static class Value {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kOff_val = 0;
|
||||
static final int kOn_val = 1;
|
||||
static final int kForward_val = 2;
|
||||
static final int kReverse_val = 3;
|
||||
/**
|
||||
* value: off
|
||||
*/
|
||||
public static final Value kOff = new Value(kOff_val);
|
||||
/**
|
||||
* value: on for relays with defined direction
|
||||
*/
|
||||
public static final Value kOn = new Value(kOn_val);
|
||||
/**
|
||||
* value: forward
|
||||
*/
|
||||
public static final Value kForward = new Value(kForward_val);
|
||||
/**
|
||||
* value: reverse
|
||||
*/
|
||||
public static final Value kReverse = new Value(kReverse_val);
|
||||
|
||||
private Value(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The Direction(s) that a relay is configured to operate in.
|
||||
*/
|
||||
public static class Direction {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kBoth_val = 0;
|
||||
static final int kForward_val = 1;
|
||||
static final int kReverse_val = 2;
|
||||
/**
|
||||
* direction: both directions are valid
|
||||
*/
|
||||
public static final Direction kBoth = new Direction(kBoth_val);
|
||||
/**
|
||||
* direction: Only forward is valid
|
||||
*/
|
||||
public static final Direction kForward = new Direction(kForward_val);
|
||||
/**
|
||||
* direction: only reverse is valid
|
||||
*/
|
||||
public static final Direction kReverse = new Direction(kReverse_val);
|
||||
|
||||
private Direction(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int m_channel;
|
||||
private ByteBuffer m_port;
|
||||
private Direction m_direction;
|
||||
private static Resource relayChannels = new Resource(kRelayChannels * 2);
|
||||
|
||||
/**
|
||||
* Common relay initialization method. This code is common to all Relay
|
||||
* constructors and initializes the relay and reserves all resources that
|
||||
* need to be locked. Initially the relay is set to both lines at 0v.
|
||||
*/
|
||||
private void initRelay() {
|
||||
SensorBase.checkRelayChannel(m_channel);
|
||||
try {
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kForward) {
|
||||
relayChannels.allocate(m_channel * 2);
|
||||
UsageReporting.report(tResourceType.kResourceType_Relay, m_channel);
|
||||
}
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kReverse) {
|
||||
relayChannels.allocate(m_channel * 2 + 1);
|
||||
UsageReporting.report(tResourceType.kResourceType_Relay, m_channel + 128);
|
||||
}
|
||||
} catch (CheckedAllocationException e) {
|
||||
throw new AllocationException("Relay channel " + m_channel + " is already allocated");
|
||||
}
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
m_port = DIOJNI.initializeDigitalPort(DIOJNI.getPort((byte) m_channel), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
LiveWindow.addActuator("Relay", m_channel, this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Relay constructor given a channel.
|
||||
*
|
||||
* @param channel
|
||||
* The channel number for this relay.
|
||||
* @param direction
|
||||
* The direction that the Relay object will control.
|
||||
*/
|
||||
public Relay(final int channel, Direction direction) {
|
||||
if (direction == null)
|
||||
throw new NullPointerException("Null Direction was given");
|
||||
m_channel = channel;
|
||||
m_direction = direction;
|
||||
initRelay();
|
||||
}
|
||||
|
||||
/**
|
||||
* Relay constructor given a channel, allowing both directions.
|
||||
*
|
||||
* @param channel
|
||||
* The channel number for this relay.
|
||||
*/
|
||||
public Relay(final int channel) {
|
||||
m_channel = channel;
|
||||
m_direction = Direction.kBoth;
|
||||
initRelay();
|
||||
}
|
||||
|
||||
public void free() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
RelayJNI.setRelayForward(m_port, (byte) 0, status.asIntBuffer());
|
||||
RelayJNI.setRelayForward(m_port, (byte) 0, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
|
||||
relayChannels.free(m_channel);
|
||||
}
|
||||
if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
|
||||
relayChannels.free(m_channel + 1);
|
||||
}
|
||||
|
||||
DIOJNI.freeDIO(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the relay state.
|
||||
*
|
||||
* Valid values depend on which directions of the relay are controlled by
|
||||
* the object.
|
||||
*
|
||||
* When set to kBothDirections, the relay can be set to any of the four
|
||||
* states: 0v-0v, 12v-0v, 0v-12v, 12v-12v
|
||||
*
|
||||
* When set to kForwardOnly or kReverseOnly, you can specify the constant
|
||||
* for the direction or you can simply specify kOff_val and kOn_val. Using
|
||||
* only kOff_val and kOn_val is recommended.
|
||||
*
|
||||
* @param value
|
||||
* The state to set the relay.
|
||||
*/
|
||||
public void set(Value value) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
switch (value.value) {
|
||||
case Value.kOff_val:
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kForward) {
|
||||
RelayJNI.setRelayForward(m_port, (byte) 0, status.asIntBuffer());
|
||||
}
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kReverse) {
|
||||
RelayJNI.setRelayReverse(m_port, (byte) 0, status.asIntBuffer());
|
||||
}
|
||||
break;
|
||||
case Value.kOn_val:
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kForward) {
|
||||
RelayJNI.setRelayForward(m_port, (byte) 1, status.asIntBuffer());
|
||||
}
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kReverse) {
|
||||
RelayJNI.setRelayReverse(m_port, (byte) 1, status.asIntBuffer());
|
||||
}
|
||||
break;
|
||||
case Value.kForward_val:
|
||||
if (m_direction == Direction.kReverse)
|
||||
throw new InvalidValueException(
|
||||
"A relay configured for reverse cannot be set to forward");
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kForward) {
|
||||
RelayJNI.setRelayForward(m_port, (byte) 1, status.asIntBuffer());
|
||||
}
|
||||
if (m_direction == Direction.kBoth) {
|
||||
RelayJNI.setRelayReverse(m_port, (byte) 0, status.asIntBuffer());
|
||||
}
|
||||
break;
|
||||
case Value.kReverse_val:
|
||||
if (m_direction == Direction.kForward)
|
||||
throw new InvalidValueException(
|
||||
"A relay configured for forward cannot be set to reverse");
|
||||
if (m_direction == Direction.kBoth) {
|
||||
RelayJNI.setRelayForward(m_port, (byte) 0, status.asIntBuffer());
|
||||
}
|
||||
if (m_direction == Direction.kBoth
|
||||
|| m_direction == Direction.kReverse) {
|
||||
RelayJNI.setRelayReverse(m_port, (byte) 1, status.asIntBuffer());
|
||||
}
|
||||
break;
|
||||
default:
|
||||
// Cannot hit this, limited by Value enum
|
||||
}
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Relay State
|
||||
*
|
||||
* Gets the current state of the relay.
|
||||
*
|
||||
* When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff
|
||||
* not kForward/kReverse (per the recommendation in Set)
|
||||
*
|
||||
* @return The current state of the relay as a Relay::Value
|
||||
*/
|
||||
public Value get() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
if (RelayJNI.getRelayForward(m_port, status.asIntBuffer()) != 0) {
|
||||
if (RelayJNI.getRelayReverse(m_port, status.asIntBuffer()) != 0) {
|
||||
return Value.kOn;
|
||||
} else {
|
||||
if (m_direction == Direction.kForward) {
|
||||
return Value.kOn;
|
||||
} else {
|
||||
return Value.kForward;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (RelayJNI.getRelayReverse(m_port, status.asIntBuffer()) != 0) {
|
||||
if (m_direction == Direction.kForward) {
|
||||
return Value.kOn;
|
||||
} else {
|
||||
return Value.kReverse;
|
||||
}
|
||||
} else {
|
||||
return Value.kOff;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the Relay Direction
|
||||
*
|
||||
* Changes which values the relay can be set to depending on which direction
|
||||
* is used
|
||||
*
|
||||
* Valid inputs are kBothDirections, kForwardOnly, and kReverseOnly
|
||||
*
|
||||
* @param direction
|
||||
* The direction for the relay to operate in
|
||||
*/
|
||||
public void setDirection(Direction direction) {
|
||||
if (direction == null)
|
||||
throw new NullPointerException("Null Direction was given");
|
||||
if (m_direction == direction) {
|
||||
return;
|
||||
}
|
||||
|
||||
free();
|
||||
|
||||
m_direction = direction;
|
||||
|
||||
initRelay();
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Relay";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
if (get() == Value.kOn) {
|
||||
m_table.putString("Value", "On");
|
||||
} else if (get() == Value.kForward) {
|
||||
m_table.putString("Value", "Forward");
|
||||
} else if (get() == Value.kReverse) {
|
||||
m_table.putString("Value", "Reverse");
|
||||
} else {
|
||||
m_table.putString("Value", "Off");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value,
|
||||
boolean bln) {
|
||||
String val = ((String) value);
|
||||
if (val.equals("Off")) {
|
||||
set(Value.kOff);
|
||||
} else if (val.equals("Forward")) {
|
||||
set(Value.kForward);
|
||||
} else if (val.equals("Reverse")) {
|
||||
set(Value.kReverse);
|
||||
}
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,112 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Track resources in the program.
|
||||
* The Resource class is a convenient way of keeping track of allocated arbitrary resources
|
||||
* in the program. Resources are just indicies that have an lower and upper bound that are
|
||||
* tracked by this class. In the library they are used for tracking allocation of hardware channels
|
||||
* but this is purely arbitrary. The resource class does not do any actual allocation, but
|
||||
* simply tracks if a given index is currently in use.
|
||||
*
|
||||
* WARNING: this should only be statically allocated. When the program loads into memory all the
|
||||
* static constructors are called. At that time a linked list of all the "Resources" is created.
|
||||
* Then when the program actually starts - in the Robot constructor, all resources are initialized.
|
||||
* This ensures that the program is restartable in memory without having to unload/reload.
|
||||
*/
|
||||
public class Resource {
|
||||
|
||||
private static Resource m_resourceList = null;
|
||||
private final boolean m_numAllocated[];
|
||||
private final int m_size;
|
||||
private final Resource m_nextResource;
|
||||
|
||||
/**
|
||||
* Clears all allocated resources
|
||||
*/
|
||||
public static void restartProgram() {
|
||||
for (Resource r = Resource.m_resourceList; r != null; r = r.m_nextResource) {
|
||||
for (int i = 0; i < r.m_size; i++) {
|
||||
r.m_numAllocated[i] = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Allocate storage for a new instance of Resource.
|
||||
* Allocate a bool array of values that will get initialized to indicate that no resources
|
||||
* have been allocated yet. The indicies of the resources are 0..size-1.
|
||||
*
|
||||
* @param size The number of blocks to allocate
|
||||
*/
|
||||
public Resource(final int size) {
|
||||
m_size = size;
|
||||
m_numAllocated = new boolean[m_size];
|
||||
for (int i = 0; i < m_size; i++) {
|
||||
m_numAllocated[i] = false;
|
||||
}
|
||||
m_nextResource = Resource.m_resourceList;
|
||||
Resource.m_resourceList = this;
|
||||
}
|
||||
|
||||
/**
|
||||
* Allocate a resource.
|
||||
* When a resource is requested, mark it allocated. In this case, a free resource value
|
||||
* within the range is located and returned after it is marked allocated.
|
||||
*
|
||||
* @return The index of the allocated block.
|
||||
* @throws CheckedAllocationException If there are no resources available to be allocated.
|
||||
*/
|
||||
public int allocate() throws CheckedAllocationException {
|
||||
for (int i = 0; i < m_size; i++) {
|
||||
if (m_numAllocated[i] == false) {
|
||||
m_numAllocated[i] = true;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
throw new CheckedAllocationException("No available resources");
|
||||
}
|
||||
|
||||
/**
|
||||
* Allocate a specific resource value.
|
||||
* The user requests a specific resource value, i.e. channel number and it is verified
|
||||
* unallocated, then returned.
|
||||
*
|
||||
* @param index The resource to allocate
|
||||
* @return The index of the allocated block
|
||||
* @throws CheckedAllocationException If there are no resources available to be allocated.
|
||||
*/
|
||||
public int allocate(final int index) throws CheckedAllocationException {
|
||||
if (index >= m_size || index < 0) {
|
||||
throw new CheckedAllocationException("Index " + index + " out of range");
|
||||
}
|
||||
if (m_numAllocated[index] == true) {
|
||||
throw new CheckedAllocationException("Resource at index " + index + " already allocated");
|
||||
}
|
||||
m_numAllocated[index] = true;
|
||||
return index;
|
||||
}
|
||||
|
||||
/**
|
||||
* Free an allocated resource.
|
||||
* After a resource is no longer needed, for example a destructor is called for a channel assignment
|
||||
* class, Free will release the resource value so it can be reused somewhere else in the program.
|
||||
*
|
||||
* @param index The index of the resource to free.
|
||||
*/
|
||||
public void free(final int index) {
|
||||
if (m_numAllocated[index] == false)
|
||||
throw new AllocationException("No resource available to be freed");
|
||||
m_numAllocated[index] = false;
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,211 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.net.URL;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.util.Enumeration;
|
||||
import java.util.jar.Manifest;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.internal.HardwareHLUsageReporting;
|
||||
import edu.wpi.first.wpilibj.internal.HardwareTimer;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
|
||||
/**
|
||||
* Implement a Robot Program framework.
|
||||
* The RobotBase class is intended to be subclassed by a user creating a robot program.
|
||||
* Overridden autonomous() and operatorControl() methods are called at the appropriate time
|
||||
* as the match proceeds. In the current implementation, the Autonomous code will run to
|
||||
* completion before the OperatorControl code could start. In the future the Autonomous code
|
||||
* might be spawned as a task, then killed at the end of the Autonomous period.
|
||||
*/
|
||||
public abstract class RobotBase {
|
||||
/**
|
||||
* The VxWorks priority that robot code should work at (so Java code should run at)
|
||||
*/
|
||||
public static final int ROBOT_TASK_PRIORITY = 101;
|
||||
|
||||
/**
|
||||
* Boolean System property. If true (default), send System.err messages to the driver station.
|
||||
*/
|
||||
public final static String ERRORS_TO_DRIVERSTATION_PROP = "first.driverstation.senderrors";
|
||||
|
||||
protected final DriverStation m_ds;
|
||||
|
||||
/**
|
||||
* Constructor for a generic robot program.
|
||||
* User code should be placed in the constructor that runs before the Autonomous or Operator
|
||||
* Control period starts. The constructor will run to completion before Autonomous is entered.
|
||||
*
|
||||
* This must be used to ensure that the communications code starts. In the future it would be
|
||||
* nice to put this code into it's own task that loads on boot so ensure that it runs.
|
||||
*/
|
||||
protected RobotBase() {
|
||||
// TODO: StartCAPI();
|
||||
// TODO: See if the next line is necessary
|
||||
// Resource.RestartProgram();
|
||||
|
||||
// if (getBooleanProperty(ERRORS_TO_DRIVERSTATION_PROP, true)) {
|
||||
// Utility.sendErrorStreamToDriverStation(true);
|
||||
// }
|
||||
NetworkTable.setServerMode();//must be before b
|
||||
m_ds = DriverStation.getInstance();
|
||||
NetworkTable.getTable(""); // forces network tables to initialize
|
||||
NetworkTable.getTable("LiveWindow").getSubTable("~STATUS~").putBoolean("LW Enabled", false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the resources for a RobotBase class.
|
||||
*/
|
||||
public void free() {
|
||||
}
|
||||
|
||||
/**
|
||||
* @return If the robot is running in simulation.
|
||||
*/
|
||||
public static boolean isSimulation() {
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* @return If the robot is running in the real world.
|
||||
*/
|
||||
public static boolean isReal() {
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the Robot is currently disabled.
|
||||
* @return True if the Robot is currently disabled by the field controls.
|
||||
*/
|
||||
public boolean isDisabled() {
|
||||
return m_ds.isDisabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the Robot is currently enabled.
|
||||
* @return True if the Robot is currently enabled by the field controls.
|
||||
*/
|
||||
public boolean isEnabled() {
|
||||
return m_ds.isEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the robot is currently in Autonomous mode.
|
||||
* @return True if the robot is currently operating Autonomously as determined by the field controls.
|
||||
*/
|
||||
public boolean isAutonomous() {
|
||||
return m_ds.isAutonomous();
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the robot is currently in Test mode
|
||||
* @return True if the robot is currently operating in Test mode as determined by the driver station.
|
||||
*/
|
||||
public boolean isTest() {
|
||||
return m_ds.isTest();
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine if the robot is currently in Operator Control mode.
|
||||
* @return True if the robot is currently operating in Tele-Op mode as determined by the field controls.
|
||||
*/
|
||||
public boolean isOperatorControl() {
|
||||
return m_ds.isOperatorControl();
|
||||
}
|
||||
|
||||
/**
|
||||
* Indicates if new data is available from the driver station.
|
||||
* @return Has new data arrived over the network since the last time this function was called?
|
||||
*/
|
||||
public boolean isNewDataAvailable() {
|
||||
return m_ds.isNewControlData();
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide an alternate "main loop" via startCompetition().
|
||||
*/
|
||||
public abstract void startCompetition();
|
||||
|
||||
public static boolean getBooleanProperty(String name, boolean defaultValue) {
|
||||
String propVal = System.getProperty(name);
|
||||
if (propVal == null) {
|
||||
return defaultValue;
|
||||
}
|
||||
if (propVal.equalsIgnoreCase("false")) {
|
||||
return false;
|
||||
} else if (propVal.equalsIgnoreCase("true")) {
|
||||
return true;
|
||||
} else {
|
||||
throw new IllegalStateException(propVal);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Starting point for the applications. Starts the OtaServer and then runs
|
||||
* the robot.
|
||||
* @throws javax.microedition.midlet.MIDletStateChangeException
|
||||
*/
|
||||
public static void main(String args[]) {
|
||||
boolean errorOnExit = false;
|
||||
|
||||
// Set some implementations so that the static methods work properly
|
||||
Timer.SetImplementation(new HardwareTimer());
|
||||
HLUsageReporting.SetImplementation(new HardwareHLUsageReporting());
|
||||
RobotState.SetImplementation(DriverStation.getInstance());
|
||||
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationReserve();
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramStarting();
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_Language, tInstances.kLanguage_Java);
|
||||
|
||||
String robotName = "";
|
||||
Enumeration<URL> resources = null;
|
||||
try {
|
||||
resources = RobotBase.class.getClassLoader().getResources("META-INF/MANIFEST.MF");
|
||||
} catch (IOException e) {e.printStackTrace();}
|
||||
while (resources != null && resources.hasMoreElements()) {
|
||||
try {
|
||||
Manifest manifest = new Manifest(resources.nextElement().openStream());
|
||||
robotName = manifest.getMainAttributes().getValue("Robot-Class");
|
||||
} catch (IOException e) {e.printStackTrace();}
|
||||
}
|
||||
|
||||
RobotBase robot;
|
||||
try {
|
||||
robot = (RobotBase) Class.forName(robotName).newInstance();
|
||||
} catch (InstantiationException|IllegalAccessException|ClassNotFoundException e) {
|
||||
System.err.println("WARNING: Robots don't quit!");
|
||||
System.err.println("ERROR: Could not instantiate robot "+robotName+"!");
|
||||
return;
|
||||
}
|
||||
|
||||
try {
|
||||
robot.startCompetition();
|
||||
} catch (Throwable t) {
|
||||
t.printStackTrace();
|
||||
errorOnExit = true;
|
||||
} finally {
|
||||
// startCompetition never returns unless exception occurs....
|
||||
System.err.println("WARNING: Robots don't quit!");
|
||||
if (errorOnExit) {
|
||||
System.err.println("---> The startCompetition() method (or methods called by it) should have handled the exception above.");
|
||||
} else {
|
||||
System.err.println("---> Unexpected return from startCompetition() method.");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,759 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.can.CANNotInitializedException;
|
||||
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.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Utility class for handling Robot drive based on a definition of the motor configuration.
|
||||
* The robot drive class handles basic driving for a robot. Currently, 2 and 4 motor standard
|
||||
* drive trains are supported. In the future other drive types like swerve and meccanum might
|
||||
* be implemented. Motor channel numbers are passed supplied on creation of the class. Those are
|
||||
* used for either the drive function (intended for hand created drive code, such as autonomous)
|
||||
* or with the Tank/Arcade functions intended to be used for Operator Control driving.
|
||||
*/
|
||||
public class RobotDrive implements MotorSafety, IUtility {
|
||||
|
||||
protected MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
/**
|
||||
* The location of a motor on the robot for the purpose of driving
|
||||
*/
|
||||
public static class MotorType {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kFrontLeft_val = 0;
|
||||
static final int kFrontRight_val = 1;
|
||||
static final int kRearLeft_val = 2;
|
||||
static final int kRearRight_val = 3;
|
||||
/**
|
||||
* motortype: front left
|
||||
*/
|
||||
public static final MotorType kFrontLeft = new MotorType(kFrontLeft_val);
|
||||
/**
|
||||
* motortype: front right
|
||||
*/
|
||||
public static final MotorType kFrontRight = new MotorType(kFrontRight_val);
|
||||
/**
|
||||
* motortype: rear left
|
||||
*/
|
||||
public static final MotorType kRearLeft = new MotorType(kRearLeft_val);
|
||||
/**
|
||||
* motortype: rear right
|
||||
*/
|
||||
public static final MotorType kRearRight = new MotorType(kRearRight_val);
|
||||
|
||||
private MotorType(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
public static final double kDefaultExpirationTime = 0.1;
|
||||
public static final double kDefaultSensitivity = 0.5;
|
||||
public static final double kDefaultMaxOutput = 1.0;
|
||||
protected static final int kMaxNumberOfMotors = 4;
|
||||
protected final int m_invertedMotors[] = new int[4];
|
||||
protected double m_sensitivity;
|
||||
protected double m_maxOutput;
|
||||
protected SpeedController m_frontLeftMotor;
|
||||
protected SpeedController m_frontRightMotor;
|
||||
protected SpeedController m_rearLeftMotor;
|
||||
protected SpeedController m_rearRightMotor;
|
||||
protected boolean m_allocatedSpeedControllers;
|
||||
protected boolean m_isCANInitialized = false;//TODO: fix can
|
||||
protected static boolean kArcadeRatioCurve_Reported = false;
|
||||
protected static boolean kTank_Reported = false;
|
||||
protected static boolean kArcadeStandard_Reported = false;
|
||||
protected static boolean kMecanumCartesian_Reported = false;
|
||||
protected static boolean kMecanumPolar_Reported = false;
|
||||
|
||||
/** Constructor for RobotDrive with 2 motors specified with channel numbers.
|
||||
* Set up parameters for a two wheel drive system where the
|
||||
* left and right motor pwm channels are specified in the call.
|
||||
* This call assumes Jaguars for controlling the motors.
|
||||
* @param leftMotorChannel The PWM channel number that drives the left motor.
|
||||
* @param rightMotorChannel The PWM channel number that drives the right motor.
|
||||
*/
|
||||
public RobotDrive(final int leftMotorChannel, final int rightMotorChannel) {
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
m_frontLeftMotor = null;
|
||||
m_rearLeftMotor = new Jaguar(leftMotorChannel);
|
||||
m_frontRightMotor = null;
|
||||
m_rearRightMotor = new Jaguar(rightMotorChannel);
|
||||
for (int i = 0; i < kMaxNumberOfMotors; i++) {
|
||||
m_invertedMotors[i] = 1;
|
||||
}
|
||||
m_allocatedSpeedControllers = true;
|
||||
setupMotorSafety();
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for RobotDrive with 4 motors specified with channel numbers.
|
||||
* Set up parameters for a four wheel drive system where all four motor
|
||||
* pwm channels are specified in the call.
|
||||
* This call assumes Jaguars for controlling the motors.
|
||||
* @param frontLeftMotor Front left motor channel number
|
||||
* @param rearLeftMotor Rear Left motor channel number
|
||||
* @param frontRightMotor Front right motor channel number
|
||||
* @param rearRightMotor Rear Right motor channel number
|
||||
*/
|
||||
public RobotDrive(final int frontLeftMotor, final int rearLeftMotor,
|
||||
final int frontRightMotor, final int rearRightMotor) {
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
m_rearLeftMotor = new Jaguar(rearLeftMotor);
|
||||
m_rearRightMotor = new Jaguar(rearRightMotor);
|
||||
m_frontLeftMotor = new Jaguar(frontLeftMotor);
|
||||
m_frontRightMotor = new Jaguar(frontRightMotor);
|
||||
for (int i = 0; i < kMaxNumberOfMotors; i++) {
|
||||
m_invertedMotors[i] = 1;
|
||||
}
|
||||
m_allocatedSpeedControllers = true;
|
||||
setupMotorSafety();
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for RobotDrive with 2 motors specified as SpeedController objects.
|
||||
* The SpeedController version of the constructor enables programs to use the RobotDrive classes with
|
||||
* subclasses of the SpeedController objects, for example, versions with ramping or reshaping of
|
||||
* the curve to suit motor bias or dead-band elimination.
|
||||
* @param leftMotor The left SpeedController object used to drive the robot.
|
||||
* @param rightMotor the right SpeedController object used to drive the robot.
|
||||
*/
|
||||
public RobotDrive(SpeedController leftMotor, SpeedController rightMotor) {
|
||||
if (leftMotor == null || rightMotor == null) {
|
||||
m_rearLeftMotor = m_rearRightMotor = null;
|
||||
throw new NullPointerException("Null motor provided");
|
||||
}
|
||||
m_frontLeftMotor = null;
|
||||
m_rearLeftMotor = leftMotor;
|
||||
m_frontRightMotor = null;
|
||||
m_rearRightMotor = rightMotor;
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
for (int i = 0; i < kMaxNumberOfMotors; i++) {
|
||||
m_invertedMotors[i] = 1;
|
||||
}
|
||||
m_allocatedSpeedControllers = false;
|
||||
setupMotorSafety();
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor for RobotDrive with 4 motors specified as SpeedController objects.
|
||||
* Speed controller input version of RobotDrive (see previous comments).
|
||||
* @param rearLeftMotor The back left SpeedController object used to drive the robot.
|
||||
* @param frontLeftMotor The front left SpeedController object used to drive the robot
|
||||
* @param rearRightMotor The back right SpeedController object used to drive the robot.
|
||||
* @param frontRightMotor The front right SpeedController object used to drive the robot.
|
||||
*/
|
||||
public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor,
|
||||
SpeedController frontRightMotor, SpeedController rearRightMotor) {
|
||||
if (frontLeftMotor == null || rearLeftMotor == null || frontRightMotor == null || rearRightMotor == null) {
|
||||
m_frontLeftMotor = m_rearLeftMotor = m_frontRightMotor = m_rearRightMotor = null;
|
||||
throw new NullPointerException("Null motor provided");
|
||||
}
|
||||
m_frontLeftMotor = frontLeftMotor;
|
||||
m_rearLeftMotor = rearLeftMotor;
|
||||
m_frontRightMotor = frontRightMotor;
|
||||
m_rearRightMotor = rearRightMotor;
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
for (int i = 0; i < kMaxNumberOfMotors; i++) {
|
||||
m_invertedMotors[i] = 1;
|
||||
}
|
||||
m_allocatedSpeedControllers = false;
|
||||
setupMotorSafety();
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Drive the motors at "speed" and "curve".
|
||||
*
|
||||
* The speed and curve are -1.0 to +1.0 values where 0.0 represents stopped and
|
||||
* not turning. The algorithm for adding in the direction attempts to provide a constant
|
||||
* turn radius for differing speeds.
|
||||
*
|
||||
* This function will most likely be used in an autonomous routine.
|
||||
*
|
||||
* @param outputMagnitude The forward component of the output magnitude to send to the motors.
|
||||
* @param curve The rate of turn, constant for different forward speeds.
|
||||
*/
|
||||
public void drive(double outputMagnitude, double curve) {
|
||||
double leftOutput, rightOutput;
|
||||
|
||||
if(!kArcadeRatioCurve_Reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(), tInstances.kRobotDrive_ArcadeRatioCurve);
|
||||
kArcadeRatioCurve_Reported = true;
|
||||
}
|
||||
if (curve < 0) {
|
||||
double value = Math.log(-curve);
|
||||
double ratio = (value - m_sensitivity) / (value + m_sensitivity);
|
||||
if (ratio == 0) {
|
||||
ratio = .0000000001;
|
||||
}
|
||||
leftOutput = outputMagnitude / ratio;
|
||||
rightOutput = outputMagnitude;
|
||||
} else if (curve > 0) {
|
||||
double value = Math.log(curve);
|
||||
double ratio = (value - m_sensitivity) / (value + m_sensitivity);
|
||||
if (ratio == 0) {
|
||||
ratio = .0000000001;
|
||||
}
|
||||
leftOutput = outputMagnitude;
|
||||
rightOutput = outputMagnitude / ratio;
|
||||
} else {
|
||||
leftOutput = outputMagnitude;
|
||||
rightOutput = outputMagnitude;
|
||||
}
|
||||
setLeftRightMotorOutputs(leftOutput, rightOutput);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* drive the robot using two joystick inputs. The Y-axis will be selected from
|
||||
* each Joystick object.
|
||||
* @param leftStick The joystick to control the left side of the robot.
|
||||
* @param rightStick The joystick to control the right side of the robot.
|
||||
*/
|
||||
public void tankDrive(GenericHID leftStick, GenericHID rightStick) {
|
||||
if (leftStick == null || rightStick == null) {
|
||||
throw new NullPointerException("Null HID provided");
|
||||
}
|
||||
tankDrive(leftStick.getY(), rightStick.getY(), true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* drive the robot using two joystick inputs. The Y-axis will be selected from
|
||||
* each Joystick object.
|
||||
* @param leftStick The joystick to control the left side of the robot.
|
||||
* @param rightStick The joystick to control the right side of the robot.
|
||||
* @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
|
||||
*/
|
||||
public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs) {
|
||||
if (leftStick == null || rightStick == null) {
|
||||
throw new NullPointerException("Null HID provided");
|
||||
}
|
||||
tankDrive(leftStick.getY(), rightStick.getY(), squaredInputs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* This function lets you pick the axis to be used on each Joystick object for the left
|
||||
* and right sides of the robot.
|
||||
* @param leftStick The Joystick object to use for the left side of the robot.
|
||||
* @param leftAxis The axis to select on the left side Joystick object.
|
||||
* @param rightStick The Joystick object to use for the right side of the robot.
|
||||
* @param rightAxis The axis to select on the right side Joystick object.
|
||||
*/
|
||||
public void tankDrive(GenericHID leftStick, final int leftAxis,
|
||||
GenericHID rightStick, final int rightAxis) {
|
||||
if (leftStick == null || rightStick == null) {
|
||||
throw new NullPointerException("Null HID provided");
|
||||
}
|
||||
tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* This function lets you pick the axis to be used on each Joystick object for the left
|
||||
* and right sides of the robot.
|
||||
* @param leftStick The Joystick object to use for the left side of the robot.
|
||||
* @param leftAxis The axis to select on the left side Joystick object.
|
||||
* @param rightStick The Joystick object to use for the right side of the robot.
|
||||
* @param rightAxis The axis to select on the right side Joystick object.
|
||||
* @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
|
||||
*/
|
||||
public void tankDrive(GenericHID leftStick, final int leftAxis,
|
||||
GenericHID rightStick, final int rightAxis, boolean squaredInputs) {
|
||||
if (leftStick == null || rightStick == null) {
|
||||
throw new NullPointerException("Null HID provided");
|
||||
}
|
||||
tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), squaredInputs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* This function lets you directly provide joystick values from any source.
|
||||
* @param leftValue The value of the left stick.
|
||||
* @param rightValue The value of the right stick.
|
||||
* @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
|
||||
*/
|
||||
public void tankDrive(double leftValue, double rightValue, boolean squaredInputs) {
|
||||
|
||||
if(!kTank_Reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(), tInstances.kRobotDrive_Tank);
|
||||
kTank_Reported = true;
|
||||
}
|
||||
|
||||
// square the inputs (while preserving the sign) to increase fine control while permitting full power
|
||||
leftValue = limit(leftValue);
|
||||
rightValue = limit(rightValue);
|
||||
if(squaredInputs) {
|
||||
if (leftValue >= 0.0) {
|
||||
leftValue = (leftValue * leftValue);
|
||||
} else {
|
||||
leftValue = -(leftValue * leftValue);
|
||||
}
|
||||
if (rightValue >= 0.0) {
|
||||
rightValue = (rightValue * rightValue);
|
||||
} else {
|
||||
rightValue = -(rightValue * rightValue);
|
||||
}
|
||||
}
|
||||
setLeftRightMotorOutputs(leftValue, rightValue);
|
||||
}
|
||||
|
||||
/**
|
||||
* Provide tank steering using the stored robot configuration.
|
||||
* This function lets you directly provide joystick values from any source.
|
||||
* @param leftValue The value of the left stick.
|
||||
* @param rightValue The value of the right stick.
|
||||
*/
|
||||
public void tankDrive(double leftValue, double rightValue) {
|
||||
tankDrive(leftValue, rightValue, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* Given a single Joystick, the class assumes the Y axis for the move value and the X axis
|
||||
* for the rotate value.
|
||||
* (Should add more information here regarding the way that arcade drive works.)
|
||||
* @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
|
||||
* for forwards/backwards and the X-axis will be selected for rotation rate.
|
||||
* @param squaredInputs If true, the sensitivity will be decreased for small values
|
||||
*/
|
||||
public void arcadeDrive(GenericHID stick, boolean squaredInputs) {
|
||||
// simply call the full-featured arcadeDrive with the appropriate values
|
||||
arcadeDrive(stick.getY(), stick.getX(), squaredInputs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* Given a single Joystick, the class assumes the Y axis for the move value and the X axis
|
||||
* for the rotate value.
|
||||
* (Should add more information here regarding the way that arcade drive works.)
|
||||
* @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
|
||||
* for forwards/backwards and the X-axis will be selected for rotation rate.
|
||||
*/
|
||||
public void arcadeDrive(GenericHID stick) {
|
||||
this.arcadeDrive(stick, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* Given two joystick instances and two axis, compute the values to send to either two
|
||||
* or four motors.
|
||||
* @param moveStick The Joystick object that represents the forward/backward direction
|
||||
* @param moveAxis The axis on the moveStick object to use for forwards/backwards (typically Y_AXIS)
|
||||
* @param rotateStick The Joystick object that represents the rotation value
|
||||
* @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
|
||||
* @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
|
||||
*/
|
||||
public void arcadeDrive(GenericHID moveStick, final int moveAxis,
|
||||
GenericHID rotateStick, final int rotateAxis,
|
||||
boolean squaredInputs) {
|
||||
double moveValue = moveStick.getRawAxis(moveAxis);
|
||||
double rotateValue = rotateStick.getRawAxis(rotateAxis);
|
||||
|
||||
arcadeDrive(moveValue, rotateValue, squaredInputs);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* Given two joystick instances and two axis, compute the values to send to either two
|
||||
* or four motors.
|
||||
* @param moveStick The Joystick object that represents the forward/backward direction
|
||||
* @param moveAxis The axis on the moveStick object to use for forwards/backwards (typically Y_AXIS)
|
||||
* @param rotateStick The Joystick object that represents the rotation value
|
||||
* @param rotateAxis The axis on the rotation object to use for the rotate right/left (typically X_AXIS)
|
||||
*/
|
||||
public void arcadeDrive(GenericHID moveStick, final int moveAxis,
|
||||
GenericHID rotateStick, final int rotateAxis) {
|
||||
this.arcadeDrive(moveStick, moveAxis, rotateStick, rotateAxis, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* This function lets you directly provide joystick values from any source.
|
||||
* @param moveValue The value to use for forwards/backwards
|
||||
* @param rotateValue The value to use for the rotate right/left
|
||||
* @param squaredInputs If set, decreases the sensitivity at low speeds
|
||||
*/
|
||||
public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs) {
|
||||
// local variables to hold the computed PWM values for the motors
|
||||
if(!kArcadeStandard_Reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(), tInstances.kRobotDrive_ArcadeStandard);
|
||||
kArcadeStandard_Reported = true;
|
||||
}
|
||||
|
||||
double leftMotorSpeed;
|
||||
double rightMotorSpeed;
|
||||
|
||||
moveValue = limit(moveValue);
|
||||
rotateValue = limit(rotateValue);
|
||||
|
||||
if (squaredInputs) {
|
||||
// square the inputs (while preserving the sign) to increase fine control while permitting full power
|
||||
if (moveValue >= 0.0) {
|
||||
moveValue = (moveValue * moveValue);
|
||||
} else {
|
||||
moveValue = -(moveValue * moveValue);
|
||||
}
|
||||
if (rotateValue >= 0.0) {
|
||||
rotateValue = (rotateValue * rotateValue);
|
||||
} else {
|
||||
rotateValue = -(rotateValue * rotateValue);
|
||||
}
|
||||
}
|
||||
|
||||
if (moveValue > 0.0) {
|
||||
if (rotateValue > 0.0) {
|
||||
leftMotorSpeed = moveValue - rotateValue;
|
||||
rightMotorSpeed = Math.max(moveValue, rotateValue);
|
||||
} else {
|
||||
leftMotorSpeed = Math.max(moveValue, -rotateValue);
|
||||
rightMotorSpeed = moveValue + rotateValue;
|
||||
}
|
||||
} else {
|
||||
if (rotateValue > 0.0) {
|
||||
leftMotorSpeed = -Math.max(-moveValue, rotateValue);
|
||||
rightMotorSpeed = moveValue + rotateValue;
|
||||
} else {
|
||||
leftMotorSpeed = moveValue - rotateValue;
|
||||
rightMotorSpeed = -Math.max(-moveValue, -rotateValue);
|
||||
}
|
||||
}
|
||||
|
||||
setLeftRightMotorOutputs(leftMotorSpeed, rightMotorSpeed);
|
||||
}
|
||||
|
||||
/**
|
||||
* Arcade drive implements single stick driving.
|
||||
* This function lets you directly provide joystick values from any source.
|
||||
* @param moveValue The value to use for fowards/backwards
|
||||
* @param rotateValue The value to use for the rotate right/left
|
||||
*/
|
||||
public void arcadeDrive(double moveValue, double rotateValue) {
|
||||
this.arcadeDrive(moveValue, rotateValue, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Drive method for Mecanum wheeled robots.
|
||||
*
|
||||
* A method for driving with Mecanum wheeled robots. There are 4 wheels
|
||||
* on the robot, arranged so that the front and back wheels are toed in 45 degrees.
|
||||
* When looking at the wheels from the top, the roller axles should form an X across the robot.
|
||||
*
|
||||
* This is designed to be directly driven by joystick axes.
|
||||
*
|
||||
* @param x The speed that the robot should drive in the X direction. [-1.0..1.0]
|
||||
* @param y The speed that the robot should drive in the Y direction.
|
||||
* This input is inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]
|
||||
* @param rotation The rate of rotation for the robot that is completely independent of
|
||||
* the translation. [-1.0..1.0]
|
||||
* @param gyroAngle The current angle reading from the gyro. Use this to implement field-oriented controls.
|
||||
*/
|
||||
public void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle) {
|
||||
if(!kMecanumCartesian_Reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(), tInstances.kRobotDrive_MecanumCartesian);
|
||||
kMecanumCartesian_Reported = true;
|
||||
}
|
||||
double xIn = x;
|
||||
double yIn = y;
|
||||
// Negate y for the joystick.
|
||||
yIn = -yIn;
|
||||
// Compenstate for gyro angle.
|
||||
double rotated[] = rotateVector(xIn, yIn, gyroAngle);
|
||||
xIn = rotated[0];
|
||||
yIn = rotated[1];
|
||||
|
||||
double wheelSpeeds[] = new double[kMaxNumberOfMotors];
|
||||
wheelSpeeds[MotorType.kFrontLeft_val] = xIn + yIn + rotation;
|
||||
wheelSpeeds[MotorType.kFrontRight_val] = -xIn + yIn - rotation;
|
||||
wheelSpeeds[MotorType.kRearLeft_val] = -xIn + yIn + rotation;
|
||||
wheelSpeeds[MotorType.kRearRight_val] = xIn + yIn - rotation;
|
||||
|
||||
normalize(wheelSpeeds);
|
||||
|
||||
byte syncGroup = (byte)0x80;
|
||||
|
||||
m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft_val] * m_invertedMotors[MotorType.kFrontLeft_val] * m_maxOutput, syncGroup);
|
||||
m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight_val] * m_invertedMotors[MotorType.kFrontRight_val] * m_maxOutput, syncGroup);
|
||||
m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft_val] * m_invertedMotors[MotorType.kRearLeft_val] * m_maxOutput, syncGroup);
|
||||
m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight_val] * m_invertedMotors[MotorType.kRearRight_val] * m_maxOutput, syncGroup);
|
||||
|
||||
if (m_isCANInitialized) {
|
||||
try {
|
||||
CANJaguar.updateSyncGroup(syncGroup);
|
||||
} catch (CANNotInitializedException e) {
|
||||
m_isCANInitialized = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (m_safetyHelper != null) m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Drive method for Mecanum wheeled robots.
|
||||
*
|
||||
* A method for driving with Mecanum wheeled robots. There are 4 wheels
|
||||
* on the robot, arranged so that the front and back wheels are toed in 45 degrees.
|
||||
* When looking at the wheels from the top, the roller axles should form an X across the robot.
|
||||
*
|
||||
* @param magnitude The speed that the robot should drive in a given direction.
|
||||
* @param direction The direction the robot should drive in degrees. The direction and maginitute are
|
||||
* independent of the rotation rate.
|
||||
* @param rotation The rate of rotation for the robot that is completely independent of
|
||||
* the magnitute or direction. [-1.0..1.0]
|
||||
*/
|
||||
public void mecanumDrive_Polar(double magnitude, double direction, double rotation) {
|
||||
if(!kMecanumPolar_Reported) {
|
||||
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(), tInstances.kRobotDrive_MecanumPolar);
|
||||
kMecanumPolar_Reported = true;
|
||||
}
|
||||
double frontLeftSpeed, rearLeftSpeed, frontRightSpeed, rearRightSpeed;
|
||||
// Normalized for full power along the Cartesian axes.
|
||||
magnitude = limit(magnitude) * Math.sqrt(2.0);
|
||||
// The rollers are at 45 degree angles.
|
||||
double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
|
||||
double cosD = Math.cos(dirInRad);
|
||||
double sinD = Math.sin(dirInRad);
|
||||
|
||||
double wheelSpeeds[] = new double[kMaxNumberOfMotors];
|
||||
wheelSpeeds[MotorType.kFrontLeft_val] = (sinD * magnitude + rotation);
|
||||
wheelSpeeds[MotorType.kFrontRight_val] = (cosD * magnitude - rotation);
|
||||
wheelSpeeds[MotorType.kRearLeft_val] = (cosD * magnitude + rotation);
|
||||
wheelSpeeds[MotorType.kRearRight_val] = (sinD * magnitude - rotation);
|
||||
|
||||
normalize(wheelSpeeds);
|
||||
|
||||
byte syncGroup = (byte)0x80;
|
||||
|
||||
m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft_val] * m_invertedMotors[MotorType.kFrontLeft_val] * m_maxOutput, syncGroup);
|
||||
m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight_val] * m_invertedMotors[MotorType.kFrontRight_val] * m_maxOutput, syncGroup);
|
||||
m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft_val] * m_invertedMotors[MotorType.kRearLeft_val] * m_maxOutput, syncGroup);
|
||||
m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight_val] * m_invertedMotors[MotorType.kRearRight_val] * m_maxOutput, syncGroup);
|
||||
|
||||
if (m_isCANInitialized) {
|
||||
try {
|
||||
CANJaguar.updateSyncGroup(syncGroup);
|
||||
} catch (CANNotInitializedException e) {
|
||||
m_isCANInitialized = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (m_safetyHelper != null) m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Holonomic Drive method for Mecanum wheeled robots.
|
||||
*
|
||||
* This is an alias to mecanumDrive_Polar() for backward compatability
|
||||
*
|
||||
* @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
|
||||
* @param direction The direction the robot should drive. The direction and maginitute are
|
||||
* independent of the rotation rate.
|
||||
* @param rotation The rate of rotation for the robot that is completely independent of
|
||||
* the magnitute or direction. [-1.0..1.0]
|
||||
*/
|
||||
void holonomicDrive(float magnitude, float direction, float rotation) {
|
||||
mecanumDrive_Polar(magnitude, direction, rotation);
|
||||
}
|
||||
|
||||
/** Set the speed of the right and left motors.
|
||||
* This is used once an appropriate drive setup function is called such as
|
||||
* twoWheelDrive(). The motors are set to "leftSpeed" and "rightSpeed"
|
||||
* and includes flipping the direction of one side for opposing motors.
|
||||
* @param leftOutput The speed to send to the left side of the robot.
|
||||
* @param rightOutput The speed to send to the right side of the robot.
|
||||
*/
|
||||
public void setLeftRightMotorOutputs(double leftOutput, double rightOutput) {
|
||||
if (m_rearLeftMotor == null || m_rearRightMotor == null) {
|
||||
throw new NullPointerException("Null motor provided");
|
||||
}
|
||||
|
||||
byte syncGroup = (byte)0x80;
|
||||
|
||||
if (m_frontLeftMotor != null) {
|
||||
m_frontLeftMotor.set(limit(leftOutput) * m_invertedMotors[MotorType.kFrontLeft_val] * m_maxOutput, syncGroup);
|
||||
}
|
||||
m_rearLeftMotor.set(limit(leftOutput) * m_invertedMotors[MotorType.kRearLeft_val] * m_maxOutput, syncGroup);
|
||||
|
||||
if (m_frontRightMotor != null) {
|
||||
m_frontRightMotor.set(-limit(rightOutput) * m_invertedMotors[MotorType.kFrontRight_val] * m_maxOutput, syncGroup);
|
||||
}
|
||||
m_rearRightMotor.set(-limit(rightOutput) * m_invertedMotors[MotorType.kRearRight_val] * m_maxOutput, syncGroup);
|
||||
|
||||
if (m_isCANInitialized) {
|
||||
try {
|
||||
CANJaguar.updateSyncGroup(syncGroup);
|
||||
} catch (CANNotInitializedException e) {
|
||||
m_isCANInitialized = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (m_safetyHelper != null) m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Limit motor values to the -1.0 to +1.0 range.
|
||||
*/
|
||||
protected static double limit(double num) {
|
||||
if (num > 1.0) {
|
||||
return 1.0;
|
||||
}
|
||||
if (num < -1.0) {
|
||||
return -1.0;
|
||||
}
|
||||
return num;
|
||||
}
|
||||
|
||||
/**
|
||||
* Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
|
||||
*/
|
||||
protected static void normalize(double wheelSpeeds[]) {
|
||||
double maxMagnitude = Math.abs(wheelSpeeds[0]);
|
||||
int i;
|
||||
for (i=1; i<kMaxNumberOfMotors; i++) {
|
||||
double temp = Math.abs(wheelSpeeds[i]);
|
||||
if (maxMagnitude < temp) maxMagnitude = temp;
|
||||
}
|
||||
if (maxMagnitude > 1.0) {
|
||||
for (i=0; i<kMaxNumberOfMotors; i++) {
|
||||
wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Rotate a vector in Cartesian space.
|
||||
*/
|
||||
protected static double[] rotateVector(double x, double y, double angle) {
|
||||
double cosA = Math.cos(angle * (3.14159 / 180.0));
|
||||
double sinA = Math.sin(angle * (3.14159 / 180.0));
|
||||
double out[] = new double[2];
|
||||
out[0] = x * cosA - y * sinA;
|
||||
out[1] = x * sinA + y * cosA;
|
||||
return out;
|
||||
}
|
||||
|
||||
/**
|
||||
* Invert a motor direction.
|
||||
* This is used when a motor should run in the opposite direction as the drive
|
||||
* code would normally run it. Motors that are direct drive would be inverted, the
|
||||
* drive code assumes that the motors are geared with one reversal.
|
||||
* @param motor The motor index to invert.
|
||||
* @param isInverted True if the motor should be inverted when operated.
|
||||
*/
|
||||
public void setInvertedMotor(MotorType motor, boolean isInverted) {
|
||||
m_invertedMotors[motor.value] = isInverted ? -1 : 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the turning sensitivity.
|
||||
*
|
||||
* This only impacts the drive() entry-point.
|
||||
* @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value)
|
||||
*/
|
||||
public void setSensitivity(double sensitivity) {
|
||||
m_sensitivity = sensitivity;
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus.
|
||||
* @param maxOutput Multiplied with the output percentage computed by the drive functions.
|
||||
*/
|
||||
public void setMaxOutput(double maxOutput) {
|
||||
m_maxOutput = maxOutput;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Free the speed controllers if they were allocated locally
|
||||
*/
|
||||
public void free() {
|
||||
if (m_allocatedSpeedControllers) {
|
||||
if (m_frontLeftMotor != null) {
|
||||
((PWM) m_frontLeftMotor).free();
|
||||
}
|
||||
if (m_frontRightMotor != null) {
|
||||
((PWM) m_frontRightMotor).free();
|
||||
}
|
||||
if (m_rearLeftMotor != null) {
|
||||
((PWM) m_rearLeftMotor).free();
|
||||
}
|
||||
if (m_rearRightMotor != null) {
|
||||
((PWM) m_rearRightMotor).free();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
public String getDescription() {
|
||||
return "Robot Drive";
|
||||
}
|
||||
|
||||
public void stopMotor() {
|
||||
if (m_frontLeftMotor != null) {
|
||||
m_frontLeftMotor.set(0.0);
|
||||
}
|
||||
if (m_frontRightMotor != null) {
|
||||
m_frontRightMotor.set(0.0);
|
||||
}
|
||||
if (m_rearLeftMotor != null) {
|
||||
m_rearLeftMotor.set(0.0);
|
||||
}
|
||||
if (m_rearRightMotor != null) {
|
||||
m_rearRightMotor.set(0.0);
|
||||
}
|
||||
}
|
||||
|
||||
private void setupMotorSafety() {
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setExpiration(kDefaultExpirationTime);
|
||||
m_safetyHelper.setSafetyEnabled(true);
|
||||
}
|
||||
|
||||
protected int getNumMotors() {
|
||||
int motors = 0;
|
||||
if (m_frontLeftMotor != null) motors++;
|
||||
if (m_frontRightMotor != null) motors++;
|
||||
if (m_rearLeftMotor != null) motors++;
|
||||
if (m_rearRightMotor != null) motors++;
|
||||
return motors;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,215 @@
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.HALLibrary;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.hal.SPIJNI;
|
||||
|
||||
/**
|
||||
*
|
||||
* Represents a SPI bus port
|
||||
|
||||
* @author koconnor
|
||||
*/
|
||||
public class SPI extends SensorBase {
|
||||
|
||||
public enum Port {
|
||||
kOnboardCS0(0),
|
||||
kOnboardCS1(1),
|
||||
kOnboardCS2(2),
|
||||
kOnboardCS3(3),
|
||||
kMXP(4);
|
||||
|
||||
private int value;
|
||||
|
||||
private Port(int value){
|
||||
this.value = value;
|
||||
}
|
||||
|
||||
public int getValue(){
|
||||
return this.value;
|
||||
}
|
||||
};
|
||||
|
||||
private static int devices = 0;
|
||||
|
||||
private byte m_port;
|
||||
private int bitOrder;
|
||||
private int clockPolarity;
|
||||
private int dataOnTrailing;
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*
|
||||
* @param SPIport the physical SPI port
|
||||
*/
|
||||
public SPI(Port port) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
m_port = (byte)port.getValue();
|
||||
devices++;
|
||||
|
||||
SPIJNI.spiInitialize(m_port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
UsageReporting.report(tResourceType.kResourceType_SPI, devices);
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the resources used by this object
|
||||
*/
|
||||
public void free(){
|
||||
SPIJNI.spiClose(m_port);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the rate of the generated clock signal.
|
||||
* The default and maximum value is 500,000 Hz.
|
||||
*
|
||||
* @param hz The clock rate in Hertz.
|
||||
*/
|
||||
public final void setClockRate(int hz) {
|
||||
SPIJNI.spiSetSpeed(m_port, hz);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the order that bits are sent and received on the wire
|
||||
* to be most significant bit first.
|
||||
*/
|
||||
public final void setMSBFirst() {
|
||||
this.bitOrder = 1;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the order that bits are sent and received on the wire
|
||||
* to be least significant bit first.
|
||||
*/
|
||||
public final void setLSBFirst() {
|
||||
this.bitOrder = 0;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the clock output line to be active low.
|
||||
* This is sometimes called clock polarity high or clock idle high.
|
||||
*/
|
||||
public final void setClockActiveLow() {
|
||||
this.clockPolarity = 1;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the clock output line to be active high.
|
||||
* This is sometimes called clock polarity low or clock idle low.
|
||||
*/
|
||||
public final void setClockActiveHigh() {
|
||||
this.clockPolarity = 0;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure that the data is stable on the falling edge and the data
|
||||
* changes on the rising edge.
|
||||
*/
|
||||
public final void setSampleDataOnFalling() {
|
||||
this.dataOnTrailing = 1;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure that the data is stable on the rising edge and the data
|
||||
* changes on the falling edge.
|
||||
*/
|
||||
public final void setSampleDataOnRising() {
|
||||
this.dataOnTrailing = 0;
|
||||
SPIJNI.spiSetOpts(m_port, this.bitOrder, this.dataOnTrailing, this.clockPolarity);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the chip select line to be active high.
|
||||
*/
|
||||
public final void setChipSelectActiveHigh() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
SPIJNI.spiSetChipSelectActiveHigh(m_port, status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the chip select line to be active low.
|
||||
*/
|
||||
public final void setChipSelectActiveLow() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
SPIJNI.spiSetChipSelectActiveLow(m_port, status.asIntBuffer());
|
||||
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Write data to the slave device. Blocks until there is space in the
|
||||
* output FIFO.
|
||||
*
|
||||
* If not running in output only mode, also saves the data received
|
||||
* on the MISO input during the transfer into the receive FIFO.
|
||||
*/
|
||||
public int write(byte[] dataToSend, int size) {
|
||||
int retVal = 0;
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(size);
|
||||
dataToSendBuffer.put(dataToSend);
|
||||
retVal = SPIJNI.spiWrite(m_port, dataToSendBuffer, (byte) size);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read a word from the receive FIFO.
|
||||
*
|
||||
* Waits for the current transfer to complete if the receive FIFO is empty.
|
||||
*
|
||||
* If the receive FIFO is empty, there is no active transfer, and initiate
|
||||
* is false, errors.
|
||||
*
|
||||
* @param initiate If true, this function pushes "0" into the
|
||||
* transmit buffer and initiates a transfer.
|
||||
* If false, this function assumes that data is
|
||||
* already in the receive FIFO from a previous write.
|
||||
*/
|
||||
public int read(boolean initiate, byte[] dataReceived, int size) {
|
||||
int retVal = 0;
|
||||
ByteBuffer dataReceivedBuffer = ByteBuffer.allocateDirect(size);
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(size);
|
||||
if(initiate)
|
||||
retVal = SPIJNI.spiTransaction(m_port, dataToSendBuffer, dataReceivedBuffer, (byte) size);
|
||||
else
|
||||
retVal = SPIJNI.spiRead(m_port, dataReceivedBuffer, (byte) size);
|
||||
dataReceivedBuffer.get(dataReceived);
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform a simultaneous read/write transaction with the device
|
||||
*
|
||||
* @param dataToSend The data to be written out to the device
|
||||
* @param dataReceived Buffer to receive data from the device
|
||||
* @param size The length of the transaction, in bytes
|
||||
*/
|
||||
public int transaction(byte[] dataToSend, byte[] dataReceived, int size) {
|
||||
int retVal = 0;
|
||||
ByteBuffer dataToSendBuffer = ByteBuffer.allocateDirect(size);
|
||||
dataToSendBuffer.put(dataToSend);
|
||||
ByteBuffer dataReceivedBuffer = ByteBuffer.allocateDirect(size);
|
||||
retVal = SPIJNI.spiTransaction(m_port, dataToSendBuffer, dataReceivedBuffer, (byte) size);
|
||||
dataReceivedBuffer.get(dataReceived);
|
||||
return retVal;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,99 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author brad
|
||||
*/
|
||||
public class SafePWM extends PWM implements MotorSafety {
|
||||
|
||||
private MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
/**
|
||||
* Initialize a SafePWM object by setting defaults
|
||||
*/
|
||||
void initSafePWM() {
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setExpiration(0.0);
|
||||
m_safetyHelper.setSafetyEnabled(false);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Constructor for a SafePWM object taking a channel number
|
||||
* @param channel The channel number to be used for the underlying PWM object
|
||||
*/
|
||||
public SafePWM(final int channel) {
|
||||
super(channel);
|
||||
initSafePWM();
|
||||
}
|
||||
|
||||
/*
|
||||
* Set the expiration time for the PWM object
|
||||
* @param timeout The timeout (in seconds) for this motor object
|
||||
*/
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the expiration time for the PWM object.
|
||||
* @return The expiration time value.
|
||||
*/
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if the PWM object is currently alive or stopped due to a timeout.
|
||||
* @return a bool value that is true if the motor has NOT timed out and should still
|
||||
* be running.
|
||||
*/
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the motor associated with this PWM object.
|
||||
* This is called by the MotorSafetyHelper object when it has a timeout for this PWM and needs to
|
||||
* stop it from running.
|
||||
*/
|
||||
public void stopMotor() {
|
||||
disable();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if motor safety is enabled for this object
|
||||
* @return True if motor safety is enforced for this object
|
||||
*/
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Feed the MotorSafety timer.
|
||||
* This method is called by the subclass motor whenever it updates its speed, thereby reseting
|
||||
* the timeout value.
|
||||
*/
|
||||
public void Feed() {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
public String getDescription() {
|
||||
return "PWM "+getChannel();
|
||||
}
|
||||
|
||||
public void disable() {
|
||||
setRaw(kPwmDisabled);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,193 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
|
||||
/**
|
||||
* Base class for all sensors.
|
||||
* Stores most recent status information as well as containing utility functions for checking
|
||||
* channels and error processing.
|
||||
*/
|
||||
public abstract class SensorBase { // TODO: Refactor
|
||||
|
||||
// TODO: Move this to the HAL
|
||||
|
||||
/**
|
||||
* Ticks per microsecond
|
||||
*/
|
||||
public static final int kSystemClockTicksPerMicrosecond = 40;
|
||||
/**
|
||||
* Number of digital channels per digital sidecar
|
||||
*/
|
||||
public static final int kDigitalChannels = 26;
|
||||
/**
|
||||
* Number of analog input channels
|
||||
*/
|
||||
public static final int kAnalogInputChannels = 8;
|
||||
/**
|
||||
* Number of analog output channels
|
||||
*/
|
||||
public static final int kAnalogOutputChannels = 2;
|
||||
/**
|
||||
* Number of solenoid channels per module
|
||||
*/
|
||||
public static final int kSolenoidChannels = 8;
|
||||
/**
|
||||
* Number of solenoid modules
|
||||
*/
|
||||
public static final int kSolenoidModules = 2;
|
||||
/**
|
||||
* Number of PWM channels per sidecar
|
||||
*/
|
||||
public static final int kPwmChannels = 20;
|
||||
/**
|
||||
* Number of relay channels per sidecar
|
||||
*/
|
||||
public static final int kRelayChannels = 4;
|
||||
/**
|
||||
* Number of power distribution channels
|
||||
*/
|
||||
public static final int kPDPChannels = 16;
|
||||
|
||||
private static int m_defaultSolenoidModule = 0;
|
||||
|
||||
/**
|
||||
* Creates an instance of the sensor base and gets an FPGA handle
|
||||
*/
|
||||
public SensorBase() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the default location for the Solenoid module.
|
||||
*
|
||||
* @param moduleNumber The number of the solenoid module to use.
|
||||
*/
|
||||
public static void setDefaultSolenoidModule(final int moduleNumber) {
|
||||
checkSolenoidModule(moduleNumber);
|
||||
SensorBase.m_defaultSolenoidModule = moduleNumber;
|
||||
}
|
||||
|
||||
/**
|
||||
* Verify that the solenoid module is correct.
|
||||
* Module numbers are 1 or 2 (they are no longer real cRIO slots).
|
||||
*
|
||||
* @param moduleNumber The solenoid module module number to check.
|
||||
*/
|
||||
protected static void checkSolenoidModule(final int moduleNumber) {
|
||||
// if(HALLibrary.checkSolenoidModule((byte) (moduleNumber - 1)) != 0) {
|
||||
// System.err.println("Solenoid module " + moduleNumber + " is not present.");
|
||||
// }
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the digital channel number is valid.
|
||||
* Verify that the channel number is one of the legal channel numbers. Channel numbers are
|
||||
* 1-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkDigitalChannel(final int channel) {
|
||||
if (channel < 0 || channel >= kDigitalChannels) {
|
||||
System.err.println("Requested digital channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the digital channel number is valid.
|
||||
* Verify that the channel number is one of the legal channel numbers. Channel numbers are
|
||||
* 1-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkRelayChannel(final int channel) {
|
||||
if (channel < 0 || channel >= kRelayChannels) {
|
||||
System.err.println("Requested relay channel number is out of range.");
|
||||
throw new IndexOutOfBoundsException("Requested relay channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the digital channel number is valid.
|
||||
* Verify that the channel number is one of the legal channel numbers. Channel numbers are
|
||||
* 1-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkPWMChannel(final int channel) {
|
||||
if (channel < 0 || channel >= kPwmChannels) {
|
||||
System.err.println("Requested PWM channel number is out of range.");
|
||||
throw new IndexOutOfBoundsException("Requested PWM channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the analog input number is value.
|
||||
* Verify that the analog input number is one of the legal channel numbers. Channel numbers
|
||||
* are 0-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkAnalogInputChannel(final int channel) {
|
||||
if (channel <= 0 || channel > kAnalogInputChannels) {
|
||||
System.err.println("Requested analog channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check that the analog input number is value.
|
||||
* Verify that the analog input number is one of the legal channel numbers. Channel numbers
|
||||
* are 0-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkAnalogOutputChannel(final int channel) {
|
||||
if (channel <= 0 || channel > kAnalogOutputChannels) {
|
||||
System.err.println("Requested analog channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Verify that the solenoid channel number is within limits. Channel numbers
|
||||
* are 1-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkSolenoidChannel(final int channel) {
|
||||
if (channel < 0 || channel >= kSolenoidChannels) {
|
||||
System.err.println("Requested solenoid channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Verify that the power distribution channel number is within limits.
|
||||
* Channel numbers are 1-based.
|
||||
*
|
||||
* @param channel The channel number to check.
|
||||
*/
|
||||
protected static void checkPDPChannel(final int channel) {
|
||||
if (channel < 0 || channel >= kPDPChannels) {
|
||||
System.err.println("Requested solenoid channel number is out of range.");
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of the default solenoid module.
|
||||
*
|
||||
* @return The number of the default analog module.
|
||||
*/
|
||||
public static int getDefaultSolenoidModule() {
|
||||
return SensorBase.m_defaultSolenoidModule;
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the resources used by this object
|
||||
*/
|
||||
public void free() {}
|
||||
}
|
||||
@@ -0,0 +1,431 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.io.UnsupportedEncodingException;
|
||||
|
||||
import edu.wpi.first.wpilibj.visa.Visa;
|
||||
import edu.wpi.first.wpilibj.visa.VisaException;
|
||||
|
||||
/**
|
||||
* Driver for the RS-232 serial port on the cRIO.
|
||||
*
|
||||
* The current implementation uses the VISA formatted I/O mode. This means that
|
||||
* all traffic goes through the formatted buffers. This allows the intermingled
|
||||
* use of print(), readString(), and the raw buffer accessors read() and write().
|
||||
*
|
||||
* More information can be found in the NI-VISA User Manual here:
|
||||
* http://www.ni.com/pdf/manuals/370423a.pdf
|
||||
* and the NI-VISA Programmer's Reference Manual here:
|
||||
* http://www.ni.com/pdf/manuals/370132c.pdf
|
||||
*/
|
||||
public class SerialPort {
|
||||
|
||||
private int m_resourceManagerHandle;
|
||||
private int m_portHandle;
|
||||
|
||||
/**
|
||||
* Represents the parity to use for serial communications
|
||||
*/
|
||||
public static class Parity {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kNone_val = 0;
|
||||
static final int kOdd_val = 1;
|
||||
static final int kEven_val = 2;
|
||||
static final int kMark_val = 3;
|
||||
static final int kSpace_val = 4;
|
||||
/**
|
||||
* parity: Use no parity
|
||||
*/
|
||||
public static final Parity kNone = new Parity(kNone_val);
|
||||
/**
|
||||
* parity: Use odd parity
|
||||
*/
|
||||
public static final Parity kOdd = new Parity(kOdd_val);
|
||||
/**
|
||||
* parity: Use even parity
|
||||
*/
|
||||
public static final Parity kEven = new Parity(kEven_val);
|
||||
/**
|
||||
* parity: Use mark parity
|
||||
*/
|
||||
public static final Parity kMark = new Parity(kMark_val);
|
||||
/**
|
||||
* parity: Use space parity
|
||||
*/
|
||||
public static final Parity kSpace = new Parity((kSpace_val));
|
||||
|
||||
private Parity(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Represents the number of stop bits to use for Serial Communication
|
||||
*/
|
||||
public static class StopBits {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kOne_val = 10;
|
||||
static final int kOnePointFive_val = 15;
|
||||
static final int kTwo_val = 20;
|
||||
/**
|
||||
* stopBits: use 1
|
||||
*/
|
||||
public static final StopBits kOne = new StopBits(kOne_val);
|
||||
/**
|
||||
* stopBits: use 1.5
|
||||
*/
|
||||
public static final StopBits kOnePointFive = new StopBits(kOnePointFive_val);
|
||||
/**
|
||||
* stopBits: use 2
|
||||
*/
|
||||
public static final StopBits kTwo = new StopBits(kTwo_val);
|
||||
|
||||
private StopBits(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Represents what type of flow control to use for serial communication
|
||||
*/
|
||||
public static class FlowControl {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kNone_val = 0;
|
||||
static final int kXonXoff_val = 1;
|
||||
static final int kRtsCts_val = 2;
|
||||
static final int kDtrDsr_val = 4;
|
||||
/**
|
||||
* flowControl: use none
|
||||
*/
|
||||
public static final FlowControl kNone = new FlowControl(kNone_val);
|
||||
/**
|
||||
* flowcontrol: use on/off
|
||||
*/
|
||||
public static final FlowControl kXonXoff = new FlowControl(kXonXoff_val);
|
||||
/**
|
||||
* flowcontrol: use rts cts
|
||||
*/
|
||||
public static final FlowControl kRtsCts = new FlowControl(kRtsCts_val);
|
||||
/**
|
||||
* flowcontrol: use dts dsr
|
||||
*/
|
||||
public static final FlowControl kDtrDsr = new FlowControl(kDtrDsr_val);
|
||||
|
||||
private FlowControl(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Represents which type of buffer mode to use when writing to a serial port
|
||||
*/
|
||||
public static class WriteBufferMode {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kFlushOnAccess_val = 1;
|
||||
static final int kFlushWhenFull_val = 2;
|
||||
/**
|
||||
* Flush on access
|
||||
*/
|
||||
public static final WriteBufferMode kFlushOnAccess = new WriteBufferMode(kFlushOnAccess_val);
|
||||
/**
|
||||
* Flush when full
|
||||
*/
|
||||
public static final WriteBufferMode kFlushWhenFull = new WriteBufferMode(kFlushWhenFull_val);
|
||||
|
||||
private WriteBufferMode(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Serial Port class.
|
||||
*
|
||||
* @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
|
||||
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
|
||||
* @param parity Select the type of parity checking to use.
|
||||
* @param stopBits The number of stop bits to use as defined by the enum StopBits.
|
||||
*/
|
||||
public SerialPort(final int baudRate, final int dataBits, Parity parity, StopBits stopBits) throws VisaException {
|
||||
m_resourceManagerHandle = 0;
|
||||
m_portHandle = 0;
|
||||
|
||||
m_resourceManagerHandle = Visa.viOpenDefaultRM();
|
||||
|
||||
m_portHandle = Visa.viOpen(m_resourceManagerHandle, "ASRL1::INSTR", 0, 0);
|
||||
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_BAUD, baudRate);
|
||||
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_DATA_BITS, dataBits);
|
||||
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_PARITY, parity.value);
|
||||
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_STOP_BITS, stopBits.value);
|
||||
|
||||
// Set the default read buffer size to 1 to return bytes immediately
|
||||
setReadBufferSize(1);
|
||||
|
||||
// Set the default timeout to 5 seconds.
|
||||
setTimeout(5.0f);
|
||||
|
||||
// Don't wait until the buffer is full to transmit.
|
||||
setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
|
||||
|
||||
disableTermination();
|
||||
|
||||
//viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler, this);
|
||||
//viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
|
||||
|
||||
// XXX: Resource Reporting Fixes
|
||||
// UsageReporting.report(UsageReporting.kResourceType_SerialPort,0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Serial Port class. Defaults to one stop bit.
|
||||
*
|
||||
* @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
|
||||
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
|
||||
* @param parity Select the type of parity checking to use.
|
||||
*/
|
||||
public SerialPort(final int baudRate, final int dataBits, Parity parity) throws VisaException {
|
||||
this(baudRate, dataBits, parity, StopBits.kOne);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Serial Port class. Defaults to no parity and one
|
||||
* stop bit.
|
||||
*
|
||||
* @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
|
||||
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
|
||||
*/
|
||||
public SerialPort(final int baudRate, final int dataBits) throws VisaException {
|
||||
this(baudRate, dataBits, Parity.kNone, StopBits.kOne);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of a Serial Port class. Defaults to 8 databits,
|
||||
* no parity, and one stop bit.
|
||||
*
|
||||
* @param baudRate The baud rate to configure the serial port. The cRIO-9074 supports up to 230400 Baud.
|
||||
*/
|
||||
public SerialPort(final int baudRate) throws VisaException {
|
||||
this(baudRate, 8, Parity.kNone, StopBits.kOne);
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
public void free() {
|
||||
//viUninstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler, this);
|
||||
Visa.viClose(m_portHandle);
|
||||
Visa.viClose(m_resourceManagerHandle);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the type of flow control to enable on this port.
|
||||
*
|
||||
* By default, flow control is disabled.
|
||||
* @param flowControl
|
||||
*/
|
||||
public void setFlowControl(FlowControl flowControl) throws VisaException {
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_FLOW_CNTRL, flowControl.value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable termination and specify the termination character.
|
||||
*
|
||||
* Termination is currently only implemented for receive.
|
||||
* When the the terminator is received, the read() or readString() will return
|
||||
* fewer bytes than requested, stopping after the terminator.
|
||||
*
|
||||
* @param terminator The character to use for termination.
|
||||
*/
|
||||
public void enableTermination(char terminator) throws VisaException {
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_TERMCHAR_EN, true);
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_TERMCHAR, terminator);
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_END_IN, Visa.VI_ASRL_END_TERMCHAR);
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable termination and specify the termination character.
|
||||
*
|
||||
* Termination is currently only implemented for receive.
|
||||
* When the the terminator is received, the read() or readString() will return
|
||||
* fewer bytes than requested, stopping after the terminator.
|
||||
*
|
||||
* The default terminator is '\n'
|
||||
*/
|
||||
public void enableTermination() throws VisaException {
|
||||
this.enableTermination('\n');
|
||||
}
|
||||
|
||||
/**
|
||||
* Disable termination behavior.
|
||||
*/
|
||||
public void disableTermination() throws VisaException {
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_TERMCHAR_EN, false);
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_END_IN, Visa.VI_ASRL_END_NONE);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the number of bytes currently available to read from the serial port.
|
||||
*
|
||||
* @return The number of bytes available to read.
|
||||
*/
|
||||
public int getBytesReceived() throws VisaException {
|
||||
return Visa.viGetAttribute(m_portHandle, Visa.VI_ATTR_ASRL_AVAIL_NUM);
|
||||
}
|
||||
|
||||
/**
|
||||
* Output formatted text to the serial port.
|
||||
*
|
||||
* @deprecated use write(string.getBytes()) instead
|
||||
* @bug All pointer-based parameters seem to return an error.
|
||||
*
|
||||
* @param write A string to write
|
||||
*/
|
||||
public void print(String write) throws VisaException {
|
||||
Visa.viVPrintf(m_portHandle, write);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read a string out of the buffer. Reads the entire contents of the buffer
|
||||
*
|
||||
* @return The read string
|
||||
*/
|
||||
public String readString() throws VisaException {
|
||||
return readString(getBytesReceived());
|
||||
}
|
||||
|
||||
/**
|
||||
* Read a string out of the buffer. Reads the entire contents of the buffer
|
||||
*
|
||||
* @param count the number of characters to read into the string
|
||||
* @return The read string
|
||||
*/
|
||||
public String readString(int count) throws VisaException {
|
||||
byte[] out = Visa.viBufRead(m_portHandle, count);
|
||||
try {
|
||||
return new String(out, 0, count, "US-ASCII");
|
||||
} catch (UnsupportedEncodingException ex) {
|
||||
ex.printStackTrace();
|
||||
return new String();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read raw bytes out of the buffer.
|
||||
*
|
||||
* @param count The maximum number of bytes to read.
|
||||
* @return An array of the read bytes
|
||||
*/
|
||||
public byte[] read(final int count) throws VisaException {
|
||||
return Visa.viBufRead(m_portHandle, count);
|
||||
}
|
||||
|
||||
/**
|
||||
* Write raw bytes to the buffer.
|
||||
*
|
||||
* @param buffer the buffer to read the bytes from.
|
||||
* @param count The maximum number of bytes to write.
|
||||
* @return The number of bytes actually written into the port.
|
||||
*/
|
||||
public int write(byte[] buffer, int count) throws VisaException {
|
||||
return Visa.viBufWrite(m_portHandle, buffer, count);
|
||||
}
|
||||
|
||||
/**
|
||||
* Configure the timeout of the serial port.
|
||||
*
|
||||
* This defines the timeout for transactions with the hardware.
|
||||
* It will affect reads if less bytes are available than the
|
||||
* read buffer size (defaults to 1) and very large writes.
|
||||
*
|
||||
* @param timeout The number of seconds to to wait for I/O.
|
||||
*/
|
||||
public void setTimeout(double timeout) throws VisaException {
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_TMO_VALUE, (int) (timeout * 1e3));
|
||||
}
|
||||
|
||||
/**
|
||||
* Specify the size of the input buffer.
|
||||
*
|
||||
* Specify the amount of data that can be stored before data
|
||||
* from the device is returned to Read. If you want
|
||||
* data that is received to be returned immediately, set this to 1.
|
||||
*
|
||||
* It the buffer is not filled before the read timeout expires, all
|
||||
* data that has been received so far will be returned.
|
||||
*
|
||||
* @param size The read buffer size.
|
||||
*/
|
||||
void setReadBufferSize(int size) throws VisaException {
|
||||
Visa.viSetBuf(m_portHandle, Visa.VI_READ_BUF, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Specify the size of the output buffer.
|
||||
*
|
||||
* Specify the amount of data that can be stored before being
|
||||
* transmitted to the device.
|
||||
*
|
||||
* @param size The write buffer size.
|
||||
*/
|
||||
void setWriteBufferSize(int size) throws VisaException {
|
||||
Visa.viSetBuf(m_portHandle, Visa.VI_WRITE_BUF, size);
|
||||
}
|
||||
|
||||
/**
|
||||
* Specify the flushing behavior of the output buffer.
|
||||
*
|
||||
* When set to kFlushOnAccess, data is synchronously written to the serial port
|
||||
* after each call to either print() or write().
|
||||
*
|
||||
* When set to kFlushWhenFull, data will only be written to the serial port when
|
||||
* the buffer is full or when flush() is called.
|
||||
*
|
||||
* @param mode The write buffer mode.
|
||||
*/
|
||||
public void setWriteBufferMode(WriteBufferMode mode) throws VisaException {
|
||||
Visa.viSetAttribute(m_portHandle, Visa.VI_ATTR_WR_BUF_OPER_MODE, mode.value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Force the output buffer to be written to the port.
|
||||
*
|
||||
* This is used when setWriteBufferMode() is set to kFlushWhenFull to force a
|
||||
* flush before the buffer is full.
|
||||
*/
|
||||
public void flush() throws VisaException {
|
||||
Visa.viFlush(m_portHandle, Visa.VI_WRITE_BUF);
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the serial port driver to a known state.
|
||||
*
|
||||
* Empty the transmit and receive buffers in the device and formatted I/O.
|
||||
*/
|
||||
public void reset() throws VisaException {
|
||||
Visa.viClear(m_portHandle);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,162 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDevice;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Standard hobby style servo.
|
||||
*
|
||||
* The range parameters default to the appropriate values for the Hitec HS-322HD servo provided
|
||||
* in the FIRST Kit of Parts in 2008.
|
||||
*/
|
||||
public class Servo extends PWM implements IDevice {
|
||||
|
||||
private static final double kMaxServoAngle = 180.0;
|
||||
private static final double kMinServoAngle = 0.0;
|
||||
|
||||
private static final double kDefaultMaxServoPWM = 2.4;
|
||||
private static final double kDefaultMinServoPWM = .6;
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
*
|
||||
* InitServo() assigns defaults for the period multiplier for the servo PWM control signal, as
|
||||
* well as the minimum and maximum PWM values supported by the servo.
|
||||
*
|
||||
*/
|
||||
private void initServo() {
|
||||
setBounds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
|
||||
setPeriodMultiplier(PeriodMultiplier.k4X);
|
||||
|
||||
LiveWindow.addActuator("Servo", getChannel(), this);
|
||||
UsageReporting.report(tResourceType.kResourceType_Servo, getChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.<br>
|
||||
*
|
||||
* By default {@value #kDefaultMaxServoPWM} ms is used as the maxPWM value<br>
|
||||
* By default {@value #kDefaultMinServoPWM} ms is used as the minPWM value<br>
|
||||
*
|
||||
* @param channel The PWM channel to which the servo is attached.
|
||||
*/
|
||||
public Servo(final int channel) {
|
||||
super(channel);
|
||||
initServo();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Set the servo position.
|
||||
*
|
||||
* Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
|
||||
*
|
||||
* @param value Position from 0.0 to 1.0.
|
||||
*/
|
||||
public void set(double value) {
|
||||
setPosition(value);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the servo position.
|
||||
*
|
||||
* Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
|
||||
*
|
||||
* @return Position from 0.0 to 1.0.
|
||||
*/
|
||||
public double get() {
|
||||
return getPosition();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the servo angle.
|
||||
*
|
||||
* Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
|
||||
*
|
||||
* Servo angles that are out of the supported range of the servo simply "saturate" in that direction
|
||||
* In other words, if the servo has a range of (X degrees to Y degrees) than angles of less than X
|
||||
* result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set.
|
||||
*
|
||||
* @param degrees The angle in degrees to set the servo.
|
||||
*/
|
||||
public void setAngle(double degrees) {
|
||||
if (degrees < kMinServoAngle) {
|
||||
degrees = kMinServoAngle;
|
||||
} else if (degrees > kMaxServoAngle) {
|
||||
degrees = kMaxServoAngle;
|
||||
}
|
||||
|
||||
setPosition(((degrees - kMinServoAngle)) / getServoAngleRange());
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the servo angle.
|
||||
*
|
||||
* Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
|
||||
* @return The angle in degrees to which the servo is set.
|
||||
*/
|
||||
public double getAngle() {
|
||||
return getPosition() * getServoAngleRange() + kMinServoAngle;
|
||||
}
|
||||
|
||||
private double getServoAngleRange() {
|
||||
return kMaxServoAngle - kMinServoAngle;
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Servo";
|
||||
}
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value, boolean bln) {
|
||||
set(((Double) value).doubleValue());
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,157 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
|
||||
/**
|
||||
* A simple robot base class that knows the standard FRC competition states (disabled, autonomous, or operator controlled).
|
||||
*
|
||||
* You can build a simple robot program off of this by overriding the
|
||||
* robotinit(), disabled(), autonomous() and operatorControl() methods. The startCompetition() method will calls these methods
|
||||
* (sometimes repeatedly).
|
||||
* depending on the state of the competition.
|
||||
*
|
||||
* Alternatively you can override the robotMain() method and manage all aspects of the robot yourself.
|
||||
*/
|
||||
public class SimpleRobot extends RobotBase {
|
||||
|
||||
private boolean m_robotMainOverridden;
|
||||
|
||||
/**
|
||||
* Create a new SimpleRobot
|
||||
*/
|
||||
public SimpleRobot() {
|
||||
super();
|
||||
m_robotMainOverridden = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Robot-wide initialization code should go here.
|
||||
*
|
||||
* Users should override this method for default Robot-wide initialization which will
|
||||
* be called when the robot is first powered on.
|
||||
*
|
||||
* Called exactly 1 time when the competition starts.
|
||||
*/
|
||||
protected void robotInit() {
|
||||
System.out.println("Default robotInit() method running, consider providing your own");
|
||||
}
|
||||
|
||||
/**
|
||||
* Disabled should go here.
|
||||
* Users should overload this method to run code that should run while the field is
|
||||
* disabled.
|
||||
*
|
||||
* Called once each time the robot enters the disabled state.
|
||||
*/
|
||||
protected void disabled() {
|
||||
System.out.println("Default disabled() method running, consider providing your own");
|
||||
}
|
||||
|
||||
/**
|
||||
* Autonomous should go here.
|
||||
* Users should add autonomous code to this method that should run while the field is
|
||||
* in the autonomous period.
|
||||
*
|
||||
* Called once each time the robot enters the autonomous state.
|
||||
*/
|
||||
public void autonomous() {
|
||||
System.out.println("Default autonomous() method running, consider providing your own");
|
||||
}
|
||||
|
||||
/**
|
||||
* Operator control (tele-operated) code should go here.
|
||||
* Users should add Operator Control code to this method that should run while the field is
|
||||
* in the Operator Control (tele-operated) period.
|
||||
*
|
||||
* Called once each time the robot enters the operator-controlled state.
|
||||
*/
|
||||
public void operatorControl() {
|
||||
System.out.println("Default operatorControl() method running, consider providing your own");
|
||||
}
|
||||
|
||||
/**
|
||||
* Test code should go here.
|
||||
* Users should add test code to this method that should run while the robot is in test mode.
|
||||
*/
|
||||
public void test() {
|
||||
System.out.println("Default test() method running, consider providing your own");
|
||||
}
|
||||
|
||||
/**
|
||||
* Robot main program for free-form programs.
|
||||
*
|
||||
* This should be overridden by user subclasses if the intent is to not use the autonomous() and
|
||||
* operatorControl() methods. In that case, the program is responsible for sensing when to run
|
||||
* the autonomous and operator control functions in their program.
|
||||
*
|
||||
* This method will be called immediately after the constructor is called. If it has not been
|
||||
* overridden by a user subclass (i.e. the default version runs), then the robotInit(), disabled(), autonomous() and
|
||||
* operatorControl() methods will be called.
|
||||
*/
|
||||
public void robotMain() {
|
||||
m_robotMainOverridden = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Start a competition.
|
||||
* This code tracks the order of the field starting to ensure that everything happens
|
||||
* in the right order. Repeatedly run the correct method, either Autonomous or OperatorControl
|
||||
* when the robot is enabled. After running the correct method, wait for some state to change,
|
||||
* either the other mode starts or the robot is disabled. Then go back and wait for the robot
|
||||
* to be enabled again.
|
||||
*/
|
||||
public void startCompetition() {
|
||||
UsageReporting.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Simple);
|
||||
|
||||
robotMain();
|
||||
if (!m_robotMainOverridden) {
|
||||
// first and one-time initialization
|
||||
LiveWindow.setEnabled(false);
|
||||
robotInit();
|
||||
|
||||
while (true) {
|
||||
if (isDisabled()) {
|
||||
m_ds.InDisabled(true);
|
||||
disabled();
|
||||
m_ds.InDisabled(false);
|
||||
while (isDisabled()) {
|
||||
Timer.delay(0.01);
|
||||
}
|
||||
} else if (isAutonomous()) {
|
||||
m_ds.InAutonomous(true);
|
||||
autonomous();
|
||||
m_ds.InAutonomous(false);
|
||||
while (isAutonomous() && !isDisabled()) {
|
||||
Timer.delay(0.01);
|
||||
}
|
||||
} else if (isTest()) {
|
||||
LiveWindow.setEnabled(true);
|
||||
m_ds.InTest(true);
|
||||
test();
|
||||
m_ds.InTest(false);
|
||||
while (isTest() && isEnabled())
|
||||
Timer.delay(0.01);
|
||||
LiveWindow.setEnabled(false);
|
||||
} else {
|
||||
m_ds.InOperatorControl(true);
|
||||
operatorControl();
|
||||
m_ds.InOperatorControl(false);
|
||||
while (isOperatorControl() && !isDisabled()) {
|
||||
Timer.delay(0.01);
|
||||
}
|
||||
}
|
||||
} /* while loop */
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,163 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.hal.SolenoidJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
import edu.wpi.first.wpilibj.util.CheckedAllocationException;
|
||||
|
||||
/**
|
||||
* Solenoid class for running high voltage Digital Output.
|
||||
*
|
||||
* The Solenoid class is typically used for pneumatics solenoids, but could be used
|
||||
* for any device within the current spec of the PCM.
|
||||
*/
|
||||
public class Solenoid extends SolenoidBase implements LiveWindowSendable {
|
||||
|
||||
private int m_channel; ///< The channel to control.
|
||||
private ByteBuffer m_solenoid_port;
|
||||
|
||||
/**
|
||||
* Common function to implement constructor behavior.
|
||||
*/
|
||||
private synchronized void initSolenoid() {
|
||||
checkSolenoidModule(m_moduleNumber);
|
||||
checkSolenoidChannel(m_channel);
|
||||
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
ByteBuffer port = SolenoidJNI.getPortWithModule((byte) m_moduleNumber, (byte) m_channel);
|
||||
m_solenoid_port = SolenoidJNI.initializeSolenoidPort(port, status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
|
||||
LiveWindow.addActuator("Solenoid", m_moduleNumber, m_channel, this);
|
||||
UsageReporting.report(tResourceType.kResourceType_Solenoid, m_channel, m_moduleNumber);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The channel on the module to control.
|
||||
*/
|
||||
public Solenoid(final int channel) {
|
||||
super(getDefaultSolenoidModule());
|
||||
m_channel = channel;
|
||||
initSolenoid();
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param moduleNumber The module number of the solenoid module to use.
|
||||
* @param channel The channel on the module to control.
|
||||
*/
|
||||
public Solenoid(final int moduleNumber, final int channel) {
|
||||
super(moduleNumber);
|
||||
m_channel = channel;
|
||||
initSolenoid();
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
public synchronized void free() {
|
||||
// m_allocated.free((m_moduleNumber - 1) * kSolenoidChannels + m_channel - 1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the value of a solenoid.
|
||||
*
|
||||
* @param on Turn the solenoid output off or on.
|
||||
*/
|
||||
public void set(boolean on) {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
SolenoidJNI.setSolenoid(m_solenoid_port, (byte) (on ? 1 : 0), status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the current value of the solenoid.
|
||||
*
|
||||
* @return The current value of the solenoid.
|
||||
*/
|
||||
public boolean get() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
boolean value = SolenoidJNI.getSolenoid(m_solenoid_port, status.asIntBuffer()) != 0;
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Solenoid";
|
||||
}
|
||||
private ITable m_table;
|
||||
private ITableListener m_table_listener;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Value", get());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
set(false); // Stop for safety
|
||||
m_table_listener = new ITableListener() {
|
||||
public void valueChanged(ITable itable, String key, Object value, boolean bln) {
|
||||
set(((Boolean) value).booleanValue());
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_table_listener, true);
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
set(false); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_table_listener);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,94 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* SolenoidBase class is the common base class for the Solenoid and
|
||||
* DoubleSolenoid classes.
|
||||
*/
|
||||
public abstract class SolenoidBase extends SensorBase implements IDeviceController {
|
||||
|
||||
private ByteBuffer[] m_ports;
|
||||
protected int m_moduleNumber; ///< The number of the solenoid module being used.
|
||||
// XXX: Move this to be both HAL calls
|
||||
//protected Resource m_allocated = new Resource(SolenoidJNI.getModuleCount() * SensorBase.kSolenoidChannels);
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param moduleNumber The number of the solenoid module to use.
|
||||
*/
|
||||
public SolenoidBase(final int moduleNumber) {
|
||||
m_moduleNumber = moduleNumber;
|
||||
// m_ports = new ByteBuffer[SensorBase.kSolenoidChannels];
|
||||
// for (int i = 0; i < SensorBase.kSolenoidChannels; i++) {
|
||||
// ByteBuffer port = SolenoidJNI.getPortWithModule((byte) moduleNumber, (byte) (i+1));
|
||||
// IntBuffer status = IntBuffer.allocate(1);
|
||||
// m_ports[i] = SolenoidJNI.initializeSolenoidPort(port, status);
|
||||
// HALUtil.checkStatus(status);
|
||||
// }
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the value of a solenoid.
|
||||
*
|
||||
* @param value The value you want to set on the module.
|
||||
* @param mask The channels you want to be affected.
|
||||
*/
|
||||
protected synchronized void set(int value, int mask) {
|
||||
// IntBuffer status = IntBuffer.allocate(1);
|
||||
// for (int i = 0; i < SensorBase.kSolenoidChannels; i++) {
|
||||
// int local_mask = 1 << i;
|
||||
// if ((mask & local_mask) != 0)
|
||||
// SolenoidJNI.setSolenoid(m_ports[i], (byte) (value & local_mask), status);
|
||||
// }
|
||||
// HALUtil.checkStatus(status);
|
||||
}
|
||||
|
||||
/**
|
||||
* Read all 8 solenoids from the module used by this solenoid as a single byte
|
||||
*
|
||||
* @return The current value of all 8 solenoids on this module.
|
||||
*/
|
||||
public byte getAll() {
|
||||
byte value = 0;
|
||||
// IntBuffer status = IntBuffer.allocate(1);
|
||||
// for (int i = 0; i < SensorBase.kSolenoidChannels; i++) {
|
||||
// value |= SolenoidJNI.getSolenoid(m_ports[i], status) << i;
|
||||
// }
|
||||
// HALUtil.checkStatus(status);
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read all 8 solenoids in the default solenoid module as a single byte
|
||||
*
|
||||
* @return The current value of all 8 solenoids on the default module.
|
||||
*/
|
||||
public static byte getAllFromDefaultModule() {
|
||||
return getAllFromModule(getDefaultSolenoidModule());
|
||||
}
|
||||
|
||||
/**
|
||||
* Read all 8 solenoids in the specified solenoid module as a single byte
|
||||
*
|
||||
* @return The current value of all 8 solenoids on the specified module.
|
||||
*/
|
||||
public static byte getAllFromModule(int moduleNumber) {
|
||||
byte value = 0;
|
||||
// checkSolenoidModule(moduleNumber);
|
||||
// throw new RuntimeException("Not supported right now.");
|
||||
return value;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,41 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
/**
|
||||
* Interface for speed controlling devices.
|
||||
*/
|
||||
public interface SpeedController extends PIDOutput {
|
||||
|
||||
/**
|
||||
* Common interface for getting the current set speed of a speed controller.
|
||||
*
|
||||
* @return The current set speed. Value is between -1.0 and 1.0.
|
||||
*/
|
||||
double get();
|
||||
|
||||
/**
|
||||
* Common interface for setting the speed of a speed controller.
|
||||
*
|
||||
* @param speed The speed to set. Value should be between -1.0 and 1.0.
|
||||
* @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
|
||||
*/
|
||||
void set(double speed, byte syncGroup);
|
||||
|
||||
/**
|
||||
* Common interface for setting the speed of a speed controller.
|
||||
*
|
||||
* @param speed The speed to set. Value should be between -1.0 and 1.0.
|
||||
*/
|
||||
void set(double speed);
|
||||
|
||||
/**
|
||||
* Disable the speed controller
|
||||
*/
|
||||
void disable();
|
||||
}
|
||||
@@ -0,0 +1,99 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* CTRE Talon Speed Controller
|
||||
*/
|
||||
public class Talon extends SafePWM implements SpeedController, IDeviceController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
*
|
||||
* Note that the Talon uses the following bounds for PWM values. These values should work reasonably well for
|
||||
* most controllers, but if users experience issues such as asymmetric behavior around
|
||||
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
|
||||
* The calibration procedure can be found in the Talon User Manual available from CTRE.
|
||||
*
|
||||
* - 2.037ms = full "forward"
|
||||
* - 1.539ms = the "high end" of the deadband range
|
||||
* - 1.513ms = center of the deadband range (off)
|
||||
* - 1.487ms = the "low end" of the deadband range
|
||||
* - .989ms = full "reverse"
|
||||
*/
|
||||
private void initTalon() {
|
||||
setBounds(2.037, 1.539, 1.513, 1.487, .989);
|
||||
setPeriodMultiplier(PeriodMultiplier.k2X);
|
||||
setRaw(m_centerPwm);
|
||||
|
||||
LiveWindow.addActuator("Talon", getChannel(), this);
|
||||
UsageReporting.report(tResourceType.kResourceType_Talon, getChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the Talon is attached to.
|
||||
*/
|
||||
public Talon(final int channel) {
|
||||
super(channel);
|
||||
initTalon();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* @deprecated For compatibility with CANJaguar
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed to set. Value should be between -1.0 and 1.0.
|
||||
* @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
|
||||
*/
|
||||
public void set(double speed, byte syncGroup) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed value between -1.0 and 1.0 to set.
|
||||
*/
|
||||
public void set(double speed) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the recently set value of the PWM.
|
||||
*
|
||||
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
||||
*/
|
||||
public double get() {
|
||||
return getSpeed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Write out the PID value as seen in the PIDOutput base object.
|
||||
*
|
||||
* @param output Write out the PWM value as was found in the PIDController
|
||||
*/
|
||||
public void pidWrite(double output) {
|
||||
set(output);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,466 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Ultrasonic rangefinder class. The Ultrasonic rangefinder measures absolute
|
||||
* distance based on the round-trip time of a ping generated by the controller.
|
||||
* These sensors use two transducers, a speaker and a microphone both tuned to
|
||||
* the ultrasonic range. A common ultrasonic sensor, the Daventech SRF04
|
||||
* requires a short pulse to be generated on a digital channel. This causes the
|
||||
* chirp to be emmitted. A second line becomes high as the ping is transmitted
|
||||
* and goes low when the echo is received. The time that the line is high
|
||||
* determines the round trip distance (time of flight).
|
||||
*/
|
||||
public class Ultrasonic extends SensorBase implements PIDSource, ISensor,
|
||||
LiveWindowSendable {
|
||||
|
||||
/**
|
||||
* The units to return when PIDGet is called
|
||||
*/
|
||||
public static class Unit {
|
||||
|
||||
/**
|
||||
* The integer value representing this enumeration
|
||||
*/
|
||||
public final int value;
|
||||
static final int kInches_val = 0;
|
||||
static final int kMillimeters_val = 1;
|
||||
/**
|
||||
* Use inches for PIDGet
|
||||
*/
|
||||
public static final Unit kInches = new Unit(kInches_val);
|
||||
/**
|
||||
* Use millimeters for PIDGet
|
||||
*/
|
||||
public static final Unit kMillimeter = new Unit(kMillimeters_val);
|
||||
|
||||
private Unit(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
private static final double kPingTime = 10 * 1e-6; // /< Time (sec) for the
|
||||
// ping trigger pulse.
|
||||
private static final int kPriority = 90; // /< Priority that the ultrasonic
|
||||
// round robin task runs.
|
||||
private static final double kMaxUltrasonicTime = 0.1; // /< Max time (ms)
|
||||
// between readings.
|
||||
private static final double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
|
||||
private static Ultrasonic m_firstSensor = null; // head of the ultrasonic
|
||||
// sensor list
|
||||
private static boolean m_automaticEnabled = false; // automatic round robin
|
||||
// mode
|
||||
private DigitalInput m_echoChannel = null;
|
||||
private DigitalOutput m_pingChannel = null;
|
||||
private boolean m_allocatedChannels;
|
||||
private boolean m_enabled = false;
|
||||
private Counter m_counter = null;
|
||||
private Ultrasonic m_nextSensor = null;
|
||||
private static Thread m_task = null; // task doing the round-robin automatic
|
||||
// sensing
|
||||
private Unit m_units;
|
||||
private static int m_instances = 0;
|
||||
|
||||
/**
|
||||
* Background task that goes through the list of ultrasonic sensors and
|
||||
* pings each one in turn. The counter is configured to read the timing of
|
||||
* the returned echo pulse.
|
||||
*
|
||||
* DANGER WILL ROBINSON, DANGER WILL ROBINSON: This code runs as a task and
|
||||
* assumes that none of the ultrasonic sensors will change while it's
|
||||
* running. If one does, then this will certainly break. Make sure to
|
||||
* disable automatic mode before changing anything with the sensors!!
|
||||
*/
|
||||
private class UltrasonicChecker extends Thread {
|
||||
|
||||
public synchronized void run() {
|
||||
Ultrasonic u = null;
|
||||
while (m_automaticEnabled) {
|
||||
if (u == null) {
|
||||
u = m_firstSensor;
|
||||
}
|
||||
if (u == null) {
|
||||
return;
|
||||
}
|
||||
if (u.isEnabled()) {
|
||||
u.m_pingChannel.pulse(m_pingChannel.m_channel,
|
||||
(float) kPingTime); // do the ping
|
||||
}
|
||||
u = u.m_nextSensor;
|
||||
Timer.delay(.1); // wait for ping to return
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the Ultrasonic Sensor. This is the common code that
|
||||
* initializes the ultrasonic sensor given that there are two digital I/O
|
||||
* channels allocated. If the system was running in automatic mode (round
|
||||
* robin) when the new sensor is added, it is stopped, the sensor is added,
|
||||
* then automatic mode is restored.
|
||||
*/
|
||||
private synchronized void initialize() {
|
||||
if (m_task == null) {
|
||||
m_task = new UltrasonicChecker();
|
||||
}
|
||||
boolean originalMode = m_automaticEnabled;
|
||||
setAutomaticMode(false); // kill task when adding a new sensor
|
||||
m_nextSensor = m_firstSensor;
|
||||
m_firstSensor = this;
|
||||
|
||||
m_counter = new Counter(m_echoChannel); // set up counter for this
|
||||
// sensor
|
||||
m_counter.setMaxPeriod(1.0);
|
||||
m_counter.setSemiPeriodMode(true);
|
||||
m_counter.reset();
|
||||
m_counter.start();
|
||||
m_enabled = true; // make it available for round robin scheduling
|
||||
setAutomaticMode(originalMode);
|
||||
|
||||
m_instances++;
|
||||
UsageReporting.report(tResourceType.kResourceType_Ultrasonic,
|
||||
m_instances);
|
||||
LiveWindow.addSensor("Ultrasonic", m_echoChannel.getChannel(), this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of the Ultrasonic Sensor.
|
||||
* This is designed to supchannel the Daventech SRF04 and Vex ultrasonic
|
||||
* sensors.
|
||||
*
|
||||
* @param pingChannel
|
||||
* The digital output channel that sends the pulse to initiate
|
||||
* the sensor sending the ping.
|
||||
* @param echoChannel
|
||||
* The digital input channel that receives the echo. The length
|
||||
* of time that the echo is high represents the round trip time
|
||||
* of the ping, and the distance.
|
||||
* @param units
|
||||
* The units returned in either kInches or kMilliMeters
|
||||
*/
|
||||
public Ultrasonic(final int pingChannel, final int echoChannel, Unit units) {
|
||||
m_pingChannel = new DigitalOutput(pingChannel);
|
||||
m_echoChannel = new DigitalInput(echoChannel);
|
||||
m_allocatedChannels = true;
|
||||
m_units = units;
|
||||
initialize();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of the Ultrasonic Sensor.
|
||||
* This is designed to supchannel the Daventech SRF04 and Vex ultrasonic
|
||||
* sensors. Default unit is inches.
|
||||
*
|
||||
* @param pingChannel
|
||||
* The digital output channel that sends the pulse to initiate
|
||||
* the sensor sending the ping.
|
||||
* @param echoChannel
|
||||
* The digital input channel that receives the echo. The length
|
||||
* of time that the echo is high represents the round trip time
|
||||
* of the ping, and the distance.
|
||||
*/
|
||||
public Ultrasonic(final int pingChannel, final int echoChannel) {
|
||||
this(pingChannel, echoChannel, Unit.kInches);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the
|
||||
* echo channel and a DigitalOutput for the ping channel.
|
||||
*
|
||||
* @param pingChannel
|
||||
* The digital output object that starts the sensor doing a ping.
|
||||
* Requires a 10uS pulse to start.
|
||||
* @param echoChannel
|
||||
* The digital input object that times the return pulse to
|
||||
* determine the range.
|
||||
* @param units
|
||||
* The units returned in either kInches or kMilliMeters
|
||||
*/
|
||||
public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel,
|
||||
Unit units) {
|
||||
if (pingChannel == null || echoChannel == null) {
|
||||
throw new NullPointerException("Null Channel Provided");
|
||||
}
|
||||
m_allocatedChannels = false;
|
||||
m_pingChannel = pingChannel;
|
||||
m_echoChannel = echoChannel;
|
||||
m_units = units;
|
||||
initialize();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create an instance of an Ultrasonic Sensor from a DigitalInput for the
|
||||
* echo channel and a DigitalOutput for the ping channel. Default unit is
|
||||
* inches.
|
||||
*
|
||||
* @param pingChannel
|
||||
* The digital output object that starts the sensor doing a ping.
|
||||
* Requires a 10uS pulse to start.
|
||||
* @param echoChannel
|
||||
* The digital input object that times the return pulse to
|
||||
* determine the range.
|
||||
*/
|
||||
public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
|
||||
this(pingChannel, echoChannel, Unit.kInches);
|
||||
}
|
||||
|
||||
/**
|
||||
* Destructor for the ultrasonic sensor. Delete the instance of the
|
||||
* ultrasonic sensor by freeing the allocated digital channels. If the
|
||||
* system was in automatic mode (round robin), then it is stopped, then
|
||||
* started again after this sensor is removed (provided this wasn't the last
|
||||
* sensor).
|
||||
*/
|
||||
public synchronized void free() {
|
||||
boolean wasAutomaticMode = m_automaticEnabled;
|
||||
setAutomaticMode(false);
|
||||
if (m_allocatedChannels) {
|
||||
if (m_pingChannel != null) {
|
||||
m_pingChannel.free();
|
||||
}
|
||||
if (m_echoChannel != null) {
|
||||
m_echoChannel.free();
|
||||
}
|
||||
}
|
||||
|
||||
if (m_counter != null) {
|
||||
m_counter.free();
|
||||
m_counter = null;
|
||||
}
|
||||
|
||||
m_pingChannel = null;
|
||||
m_echoChannel = null;
|
||||
|
||||
if (this == m_firstSensor) {
|
||||
m_firstSensor = m_nextSensor;
|
||||
if (m_firstSensor == null) {
|
||||
setAutomaticMode(false);
|
||||
}
|
||||
} else {
|
||||
for (Ultrasonic s = m_firstSensor; s != null; s = s.m_nextSensor) {
|
||||
if (this == s.m_nextSensor) {
|
||||
s.m_nextSensor = s.m_nextSensor.m_nextSensor;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (m_firstSensor != null && wasAutomaticMode) {
|
||||
setAutomaticMode(true);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn Automatic mode on/off. When in Automatic mode, all sensors will fire
|
||||
* in round robin, waiting a set time between each sensor.
|
||||
*
|
||||
* @param enabling
|
||||
* Set to true if round robin scheduling should start for all the
|
||||
* ultrasonic sensors. This scheduling method assures that the
|
||||
* sensors are non-interfering because no two sensors fire at the
|
||||
* same time. If another scheduling algorithm is preffered, it
|
||||
* can be implemented by pinging the sensors manually and waiting
|
||||
* for the results to come back.
|
||||
*/
|
||||
public void setAutomaticMode(boolean enabling) {
|
||||
if (enabling == m_automaticEnabled) {
|
||||
return; // ignore the case of no change
|
||||
}
|
||||
m_automaticEnabled = enabling;
|
||||
|
||||
if (enabling) {
|
||||
// enabling automatic mode.
|
||||
// Clear all the counters so no data is valid
|
||||
for (Ultrasonic u = m_firstSensor; u != null; u = u.m_nextSensor) {
|
||||
u.m_counter.reset();
|
||||
}
|
||||
// Start round robin task
|
||||
m_task.start();
|
||||
} else {
|
||||
// disabling automatic mode. Wait for background task to stop
|
||||
// running.
|
||||
while (m_task.isAlive()) {
|
||||
Timer.delay(.15); // just a little longer than the ping time for
|
||||
// round-robin to stop
|
||||
}
|
||||
// clear all the counters (data now invalid) since automatic mode is
|
||||
// stopped
|
||||
for (Ultrasonic u = m_firstSensor; u != null; u = u.m_nextSensor) {
|
||||
u.m_counter.reset();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Single ping to ultrasonic sensor. Send out a single ping to the
|
||||
* ultrasonic sensor. This only works if automatic (round robin) mode is
|
||||
* disabled. A single ping is sent out, and the counter should count the
|
||||
* semi-period when it comes in. The counter is reset to make the current
|
||||
* value invalid.
|
||||
*/
|
||||
public void ping() {
|
||||
setAutomaticMode(false); // turn off automatic round robin if pinging
|
||||
// single sensor
|
||||
m_counter.reset(); // reset the counter to zero (invalid data now)
|
||||
m_pingChannel.pulse(m_pingChannel.m_channel, (float) kPingTime); // do
|
||||
// the
|
||||
// ping
|
||||
// to
|
||||
// start
|
||||
// getting
|
||||
// a
|
||||
// single
|
||||
// range
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there is a valid range measurement. The ranges are accumulated
|
||||
* in a counter that will increment on each edge of the echo (return)
|
||||
* signal. If the count is not at least 2, then the range has not yet been
|
||||
* measured, and is invalid.
|
||||
*
|
||||
* @return true if the range is valid
|
||||
*/
|
||||
public boolean isRangeValid() {
|
||||
return m_counter.get() > 1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the range in inches from the ultrasonic sensor.
|
||||
*
|
||||
* @return double Range in inches of the target returned from the ultrasonic
|
||||
* sensor. If there is no valid value yet, i.e. at least one
|
||||
* measurement hasn't completed, then return 0.
|
||||
*/
|
||||
public double getRangeInches() {
|
||||
if (isRangeValid()) {
|
||||
return m_counter.getPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the range in millimeters from the ultrasonic sensor.
|
||||
*
|
||||
* @return double Range in millimeters of the target returned by the
|
||||
* ultrasonic sensor. If there is no valid value yet, i.e. at least
|
||||
* one measurement hasn't complted, then return 0.
|
||||
*/
|
||||
public double getRangeMM() {
|
||||
return getRangeInches() * 25.4;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the range in the current DistanceUnit for the PIDSource base object.
|
||||
*
|
||||
* @return The range in DistanceUnit
|
||||
*/
|
||||
public double pidGet() {
|
||||
switch (m_units.value) {
|
||||
case Unit.kInches_val:
|
||||
return getRangeInches();
|
||||
case Unit.kMillimeters_val:
|
||||
return getRangeMM();
|
||||
default:
|
||||
return 0.0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the current DistanceUnit that should be used for the PIDSource base
|
||||
* object.
|
||||
*
|
||||
* @param units
|
||||
* The DistanceUnit that should be used.
|
||||
*/
|
||||
public void setDistanceUnits(Unit units) {
|
||||
m_units = units;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current DistanceUnit that is used for the PIDSource base object.
|
||||
*
|
||||
* @return The type of DistanceUnit that is being used.
|
||||
*/
|
||||
public Unit getDistanceUnits() {
|
||||
return m_units;
|
||||
}
|
||||
|
||||
/**
|
||||
* Is the ultrasonic enabled
|
||||
*
|
||||
* @return true if the ultrasonic is enabled
|
||||
*/
|
||||
public boolean isEnabled() {
|
||||
return m_enabled;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set if the ultrasonic is enabled
|
||||
*
|
||||
* @param enable
|
||||
* set to true to enable the ultrasonic
|
||||
*/
|
||||
public void setEnabled(boolean enable) {
|
||||
m_enabled = enable;
|
||||
}
|
||||
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
public String getSmartDashboardType() {
|
||||
return "Ultrasonic";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void initTable(ITable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public ITable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getRangeInches());
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void startLiveWindowMode() {
|
||||
}
|
||||
|
||||
/**
|
||||
* {@inheritDoc}
|
||||
*/
|
||||
public void stopLiveWindowMode() {
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,85 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.HALLibrary;
|
||||
import edu.wpi.first.wpilibj.hal.HALUtil;
|
||||
import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Contains global utility functions
|
||||
*/
|
||||
public class Utility implements IUtility {
|
||||
|
||||
private Utility() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the FPGA Version number. For now, expect this to be 2009.
|
||||
*
|
||||
* @return FPGA Version number.
|
||||
*/
|
||||
int getFPGAVersion() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = HALUtil.getFPGAVersion(status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the FPGA Revision number. The format of the revision is 3 numbers.
|
||||
* The 12 most significant bits are the Major Revision. the next 8 bits are
|
||||
* the Minor Revision. The 12 least significant bits are the Build Number.
|
||||
*
|
||||
* @return FPGA Revision number.
|
||||
*/
|
||||
long getFPGARevision() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
int value = HALUtil.getFPGARevision(status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return (long) value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the microsecond timer from the FPGA.
|
||||
*
|
||||
* @return The current time in microseconds according to the FPGA.
|
||||
*/
|
||||
public static long getFPGATime() {
|
||||
ByteBuffer status = ByteBuffer.allocateDirect(4);
|
||||
// set the byte order
|
||||
status.order(ByteOrder.LITTLE_ENDIAN);
|
||||
|
||||
long value = HALUtil.getFPGATime(status.asIntBuffer());
|
||||
HALUtil.checkStatus(status.asIntBuffer());
|
||||
return value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Control whether to send System.err output to the driver station's error
|
||||
* pane.
|
||||
*
|
||||
* @param enabled
|
||||
* if true, send error stream to driver station, otherwise
|
||||
* disable sending error stream
|
||||
*/
|
||||
public static void sendErrorStreamToDriverStation(boolean enabled) {
|
||||
final String url = "dserror:edu.wpi.first.wpilibj.Utility"; // the path
|
||||
// is just a
|
||||
// comment.
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,101 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.parsing.IDeviceController;
|
||||
|
||||
/**
|
||||
* VEX Robotics Victor Speed Controller
|
||||
*/
|
||||
public class Victor extends SafePWM implements SpeedController, IDeviceController {
|
||||
|
||||
/**
|
||||
* Common initialization code called by all constructors.
|
||||
*
|
||||
* Note that the Victor uses the following bounds for PWM values. These values were determined
|
||||
* empirically and optimized for the Victor 888. These values should work reasonably well for
|
||||
* Victor 884 controllers also but if users experience issues such as asymmetric behavior around
|
||||
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
|
||||
* The calibration procedure can be found in the Victor 884 User Manual available from VEX Robotics:
|
||||
* http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf
|
||||
*
|
||||
* - 2.027ms = full "forward"
|
||||
* - 1.525ms = the "high end" of the deadband range
|
||||
* - 1.507ms = center of the deadband range (off)
|
||||
* - 1.49ms = the "low end" of the deadband range
|
||||
* - 1.026ms = full "reverse"
|
||||
*/
|
||||
private void initVictor() {
|
||||
setBounds(2.027, 1.525, 1.507, 1.49, 1.026);
|
||||
setPeriodMultiplier(PeriodMultiplier.k2X);
|
||||
setRaw(m_centerPwm);
|
||||
|
||||
LiveWindow.addActuator("Victor", getChannel(), this);
|
||||
UsageReporting.report(tResourceType.kResourceType_Victor, getChannel());
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the Victor is attached to.
|
||||
*/
|
||||
public Victor(final int channel) {
|
||||
super(channel);
|
||||
initVictor();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* @deprecated For compatibility with CANJaguar
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed to set. Value should be between -1.0 and 1.0.
|
||||
* @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately.
|
||||
*/
|
||||
public void set(double speed, byte syncGroup) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
||||
* scaling the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed value between -1.0 and 1.0 to set.
|
||||
*/
|
||||
public void set(double speed) {
|
||||
setSpeed(speed);
|
||||
Feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the recently set value of the PWM.
|
||||
*
|
||||
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
||||
*/
|
||||
public double get() {
|
||||
return getSpeed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Write out the PID value as seen in the PIDOutput base object.
|
||||
*
|
||||
* @param output Write out the PWM value as was found in the PIDController
|
||||
*/
|
||||
public void pidWrite(double output) {
|
||||
set(output);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,489 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.camera;
|
||||
|
||||
import com.sun.jna.BlockingFunction;
|
||||
import com.sun.jna.Function;
|
||||
import com.sun.jna.NativeLibrary;
|
||||
import com.sun.jna.Pointer;
|
||||
import com.sun.jna.TaskExecutor;
|
||||
import com.sun.squawk.VM;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
import edu.wpi.first.wpilibj.image.ColorImage;
|
||||
import edu.wpi.first.wpilibj.image.HSLImage;
|
||||
import edu.wpi.first.wpilibj.image.NIVisionException;
|
||||
import edu.wpi.first.wpilibj.parsing.ISensor;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
//TODO figure out where to use finally to free resources
|
||||
//TODO go through old camera code and make sure all features are implemented
|
||||
//TODO make work with all three passwords
|
||||
//TODO get images of different types
|
||||
//TODO continue attempting to connect until succesful
|
||||
//TODO optimize and use Pointers in all locations which make sense - possibly JNA memcpy?
|
||||
/**
|
||||
* This class is a singleton used to configure and get images from the axis camera.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class AxisCamera implements ISensor {
|
||||
|
||||
private static AxisCamera m_instance = null;
|
||||
|
||||
/**
|
||||
* Enumaration representing the different values which exposure may be set to.
|
||||
*/
|
||||
public static class ExposureT {
|
||||
|
||||
/**
|
||||
* The integer value of the enumeration.
|
||||
*/
|
||||
public final int value;
|
||||
static final ExposureT[] allValues = new ExposureT[4];
|
||||
/**
|
||||
* The Axis camera automatically determines what exposure level to use.
|
||||
*/
|
||||
public static final ExposureT automatic = new ExposureT(0);
|
||||
/**
|
||||
* Hold the current exposure level.
|
||||
*/
|
||||
public static final ExposureT hold = new ExposureT(1);
|
||||
/**
|
||||
* Set exposure for flicker free 50 hz.
|
||||
*/
|
||||
public static final ExposureT flickerfree50 = new ExposureT(2);
|
||||
/**
|
||||
* Set exposure for flicker free 60 hz.
|
||||
*/
|
||||
public static final ExposureT flickerfree60 = new ExposureT(3);
|
||||
|
||||
private ExposureT(int value) {
|
||||
this.value = value;
|
||||
allValues[value] = this;
|
||||
}
|
||||
|
||||
private static ExposureT get(int val) {
|
||||
return allValues[val];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enumeration representing the different values which white balence may be
|
||||
* set to.
|
||||
*/
|
||||
public static class WhiteBalanceT {
|
||||
|
||||
/**
|
||||
* The integer value of the enumeration.
|
||||
*/
|
||||
public final int value;
|
||||
static final WhiteBalanceT[] allValues = new WhiteBalanceT[7];
|
||||
/**
|
||||
* The axis camera automatically adjusts the whit balance.
|
||||
*/
|
||||
public static final WhiteBalanceT automatic = new WhiteBalanceT(0);
|
||||
/**
|
||||
* Hold the current white balance.
|
||||
*/
|
||||
public static final WhiteBalanceT hold = new WhiteBalanceT(1);
|
||||
/**
|
||||
* White balance for outdoors.
|
||||
*/
|
||||
public static final WhiteBalanceT fixedOutdoor1 = new WhiteBalanceT(2);
|
||||
/**
|
||||
* White balance for outdoors.
|
||||
*/
|
||||
public static final WhiteBalanceT fixedOutdoor2 = new WhiteBalanceT(3);
|
||||
/**
|
||||
* White balance for indoors.
|
||||
*/
|
||||
public static final WhiteBalanceT fixedIndoor = new WhiteBalanceT(4);
|
||||
/**
|
||||
* White balance for fourescent lighting.
|
||||
*/
|
||||
public static final WhiteBalanceT fixedFlour1 = new WhiteBalanceT(5);
|
||||
/**
|
||||
* White balance for fourescent lighting.
|
||||
*/
|
||||
public static final WhiteBalanceT fixedFlour2 = new WhiteBalanceT(6);
|
||||
|
||||
private WhiteBalanceT(int value) {
|
||||
this.value = value;
|
||||
allValues[value] = this;
|
||||
}
|
||||
|
||||
private static WhiteBalanceT get(int value) {
|
||||
return allValues[value];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enumeration representing the image resoultion provided by the camera.
|
||||
*/
|
||||
public static class ResolutionT {
|
||||
|
||||
/**
|
||||
* The integer value of the enumeration.
|
||||
*/
|
||||
public final int value;
|
||||
/**
|
||||
* Number of pixels wide.
|
||||
*/
|
||||
public final int width;
|
||||
/**
|
||||
* Number of pixels tall.
|
||||
*/
|
||||
public final int height;
|
||||
static final ResolutionT[] allValues = new ResolutionT[4];
|
||||
/**
|
||||
* Image is 640 pixels wide by 480 tall
|
||||
*/
|
||||
public static final ResolutionT k640x480 = new ResolutionT(0, 640, 480);
|
||||
/**
|
||||
* Image is 640 pixels wide by 360 tall
|
||||
*/
|
||||
public static final ResolutionT k640x360 = new ResolutionT(1, 640, 360);
|
||||
/**
|
||||
* Image is 320 pixels wide by 240 tall
|
||||
*/
|
||||
public static final ResolutionT k320x240 = new ResolutionT(2, 320, 240);
|
||||
/**
|
||||
* Image is 160 pixels wide by 120 tall
|
||||
*/
|
||||
public static final ResolutionT k160x120 = new ResolutionT(3, 160, 120);
|
||||
|
||||
private ResolutionT(int value, int horizontal, int vertical) {
|
||||
this.value = value;
|
||||
this.width = horizontal;
|
||||
this.height = vertical;
|
||||
allValues[value] = this;
|
||||
}
|
||||
|
||||
private static ResolutionT get(int value) {
|
||||
return allValues[value];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enumeration representing the orientation of the picture.
|
||||
*/
|
||||
public static class RotationT {
|
||||
|
||||
/**
|
||||
* The integer value of the enumeration.
|
||||
*/
|
||||
public final int value;
|
||||
static final RotationT[] allValues = new RotationT[2];
|
||||
/**
|
||||
* Picture is right side up.
|
||||
*/
|
||||
public static final RotationT k0 = new RotationT(0);
|
||||
/**
|
||||
* Picture is rotated 180 degrees.
|
||||
*/
|
||||
public static final RotationT k180 = new RotationT(1);
|
||||
|
||||
private RotationT(int value) {
|
||||
this.value = value;
|
||||
allValues[value] = this;
|
||||
}
|
||||
|
||||
private static RotationT get(int value) {
|
||||
return allValues[value];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enumeration representing the exposure priority.
|
||||
*/
|
||||
public static class ExposurePriorityT {
|
||||
|
||||
/**
|
||||
* The integer value of the enumeration.
|
||||
*/
|
||||
public final int value;
|
||||
static final ExposurePriorityT[] allValues = new ExposurePriorityT[3];
|
||||
/**
|
||||
* Prioritize image quality.
|
||||
*/
|
||||
public static final ExposurePriorityT imageQuality = new ExposurePriorityT(0);
|
||||
/**
|
||||
* No prioritization.
|
||||
*/
|
||||
public static final ExposurePriorityT none = new ExposurePriorityT(50);
|
||||
/**
|
||||
* Prioritize frame rate.
|
||||
*/
|
||||
public static final ExposurePriorityT frameRate = new ExposurePriorityT(100);
|
||||
|
||||
private ExposurePriorityT(int value) {
|
||||
this.value = value;
|
||||
allValues[value / 50] = this;
|
||||
}
|
||||
|
||||
private static ExposurePriorityT get(int value) {
|
||||
return allValues[value / 50];
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a reference to the AxisCamera, or initialize the AxisCamera if it
|
||||
* has not yet been initialized. If the camera is connected to the
|
||||
* Ethernet switch on the robot, then this address should be 10.x.y.11
|
||||
* where x.y are your team number subnet address (same as the other IP
|
||||
* addresses on the robot network).
|
||||
* @param address A string containing the IP address for the camera in the
|
||||
* form "10.x.y.2" for cameras on the Ethernet switch or "192.168.0.90"
|
||||
* for cameras connected to the 2nd Ethernet port on an 8-slot cRIO.
|
||||
* @return A reference to the AxisCamera.
|
||||
*/
|
||||
public static synchronized AxisCamera getInstance(String address) {
|
||||
if (m_instance == null) {
|
||||
m_instance = new AxisCamera(address);
|
||||
// XXX: Resource Reporting Fixes
|
||||
// UsageReporting.report(UsageReporting.kResourceType_AxisCamera, 2);
|
||||
}
|
||||
return m_instance;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a reference to the AxisCamera, or initialize the AxisCamera if it
|
||||
* has not yet been initialized. By default this will connect to a camera
|
||||
* with an IP address of 10.x.y.11 with the preference that the camera be
|
||||
* connected to the Ethernet switch on the robot rather than port 2 of the
|
||||
* 8-slot cRIO.
|
||||
* @return A reference to the AxisCamera.
|
||||
*/
|
||||
public static synchronized AxisCamera getInstance() {
|
||||
if (m_instance == null) {
|
||||
DriverStation.getInstance().waitForData();
|
||||
int teamNumber = DriverStation.getInstance().getTeamNumber();
|
||||
String address = "10."+(teamNumber/100)+"."+(teamNumber%100)+".11";
|
||||
m_instance = new AxisCamera(address);
|
||||
UsageReporting.report(UsageReporting.kResourceType_AxisCamera, 1);
|
||||
}
|
||||
|
||||
return m_instance;
|
||||
}
|
||||
private static final Function cameraStartFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraStart");
|
||||
|
||||
/**
|
||||
* Axis camera constructor that calls the C++ library to actually create the instance.
|
||||
* @param IPAddress
|
||||
*/
|
||||
AxisCamera(String IPAddress) {
|
||||
Pointer ptr = Pointer.createStringBuffer(IPAddress);
|
||||
cameraStartFn.call1(ptr);
|
||||
}
|
||||
private static final TaskExecutor cameraTaskExecutor = new TaskExecutor("camera task executor");
|
||||
private static final BlockingFunction getImageFn = NativeLibrary.getDefaultInstance().getBlockingFunction("AxisCameraGetImage");
|
||||
|
||||
static {
|
||||
getImageFn.setTaskExecutor(cameraTaskExecutor);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get an image from the camera. Be sure to free the image when you are done with it.
|
||||
* @return A new image from the camera.
|
||||
*/
|
||||
public ColorImage getImage() throws AxisCameraException, NIVisionException {
|
||||
ColorImage image = new HSLImage();
|
||||
if (getImageFn.call1(image.image) == 0) {
|
||||
image.free();
|
||||
throw new AxisCameraException("No image available");
|
||||
}
|
||||
return image;
|
||||
}
|
||||
// Mid-stream gets & writes
|
||||
private static final Function writeBrightnessFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteBrightness");
|
||||
|
||||
/**
|
||||
* Write the brightness for the camera to use.
|
||||
* @param brightness This must be an integer between 0 and 100, with 100 being the brightest
|
||||
*/
|
||||
public void writeBrightness(int brightness) {
|
||||
BoundaryException.assertWithinBounds(brightness, 0, 100);
|
||||
writeBrightnessFn.call1(brightness);
|
||||
}
|
||||
private static final Function getBrightnessFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetBrightness");
|
||||
|
||||
/**
|
||||
* Get the current brightness of the AxisCamera
|
||||
* @return An integer representing the current brightness of the axis
|
||||
* camera with 0 being the darkest and 100 being the brightest.
|
||||
*/
|
||||
public int getBrightness() {
|
||||
return getBrightnessFn.call0();
|
||||
}
|
||||
private static final Function writeWhiteBalenceFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteWhiteBalance");
|
||||
|
||||
/**
|
||||
* Write the WhiteBalance for the camera to use.
|
||||
* @param whiteBalance The value to set the white balance to on the camera.
|
||||
*/
|
||||
public void writeWhiteBalance(WhiteBalanceT whiteBalance) {
|
||||
writeWhiteBalenceFn.call1(whiteBalance.value);
|
||||
}
|
||||
private static final Function getWhiteBalanceFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetWhiteBalance");
|
||||
|
||||
/**
|
||||
* Get the white balance set on the camera.
|
||||
* @return The white balance currently set on the camera.
|
||||
*/
|
||||
public WhiteBalanceT getWhiteBalance() {
|
||||
return WhiteBalanceT.get(getWhiteBalanceFn.call0());
|
||||
}
|
||||
private static final Function writeColorLevelFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteColorLevel");
|
||||
|
||||
/**
|
||||
* Set the color level of images returned from the camera.
|
||||
* @param value This must be an integer from 0 to 100 with 0 being black and white.
|
||||
*/
|
||||
public void writeColorLevel(int value) {
|
||||
BoundaryException.assertWithinBounds(value, 0, 100);
|
||||
writeColorLevelFn.call1(value);
|
||||
}
|
||||
private static final Function getColorLevelFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetColorLevel");
|
||||
|
||||
/**
|
||||
* Get the color level of images being retunred from the camera.
|
||||
* @return The color level of images being returned from the camera. 0 is black and white.
|
||||
*/
|
||||
public int getColorLevel() {
|
||||
return getColorLevelFn.call0();
|
||||
}
|
||||
private static final Function writeExposureControlFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteExposureControl");
|
||||
|
||||
/**
|
||||
* Write the exposure mode for the camera to use.
|
||||
* @param value The expsure mode for the camera to use.
|
||||
*/
|
||||
public void writeExposureControl(ExposureT value) {
|
||||
writeExposureControlFn.call1(value.value);
|
||||
}
|
||||
private static final Function getExposureControlFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetExposureControl");
|
||||
|
||||
/**
|
||||
* Get the exposure mode that the camera is using.
|
||||
* @return The exposure mode that the camera is using.
|
||||
*/
|
||||
public ExposureT getExposureControl() {
|
||||
return ExposureT.get(getExposureControlFn.call0());
|
||||
}
|
||||
private static final Function writeExposurePriorityFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteExposurePriority");
|
||||
|
||||
/**
|
||||
* Write the exposure priority for the camera to use.
|
||||
* @param value The exposure priority to use.
|
||||
*/
|
||||
public void writeExposurePriority(ExposurePriorityT value) {
|
||||
writeExposurePriorityFn.call1(value.value);
|
||||
}
|
||||
private static final Function getExposurePriorityFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetExposurePriority");
|
||||
|
||||
/**
|
||||
* Get the exposure priority that the camera is using.
|
||||
* @return The exposure priority that the camera is using
|
||||
*/
|
||||
public ExposurePriorityT getExposurePriority() {
|
||||
return ExposurePriorityT.get(getExposurePriorityFn.call0());
|
||||
}
|
||||
// New-Stream gets & writes
|
||||
private static final Function writeResolutionFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteResolution");
|
||||
|
||||
/**
|
||||
* Set the resolution of the images to return.
|
||||
* @param value The resolution imaga for the camera to return.
|
||||
*/
|
||||
public void writeResolution(ResolutionT value) {
|
||||
writeResolutionFn.call1(value.value);
|
||||
}
|
||||
private static final Function getResolutionFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetResolution");
|
||||
|
||||
/**
|
||||
* Get the resolution fo the images that the camera is returning.
|
||||
* @return The resolution of the images that the camera is returning.
|
||||
*/
|
||||
public ResolutionT getResolution() {
|
||||
return ResolutionT.get(getResolutionFn.call0());
|
||||
}
|
||||
private static final Function writeCompressionFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteCompression");
|
||||
|
||||
/**
|
||||
* Write the level of JPEG compression to use on images returned from the camera.
|
||||
* @param value The level of JPEG compression to use from 0 to 100 with 0 being the least compression.
|
||||
*/
|
||||
public void writeCompression(int value) {
|
||||
BoundaryException.assertWithinBounds(value, 0, 100);
|
||||
writeCompressionFn.call1(value);
|
||||
}
|
||||
private static final Function getCompressionFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetCompression");
|
||||
|
||||
/**
|
||||
* Get the compression of the images eing returned by the camera.
|
||||
* @return The level of compression of the image being returned from the
|
||||
* camera with 0 being the least and 100 being the greatest.
|
||||
*/
|
||||
public int getCompression() {
|
||||
return getCompressionFn.call0();
|
||||
}
|
||||
private static final Function writeRotationFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteRotation");
|
||||
|
||||
/**
|
||||
* Write the rotation of images for the camera to return.
|
||||
* @param value The rotation to be applied to images from the camera.
|
||||
*/
|
||||
public void writeRotation(RotationT value) {
|
||||
writeRotationFn.call1(value.value);
|
||||
}
|
||||
private static final Function getRotationFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetRotation");
|
||||
|
||||
/**
|
||||
* Get the rotation of the images returned from the camera.
|
||||
* @return The rotation of the images returned from the camera.
|
||||
*/
|
||||
public RotationT getRotation() {
|
||||
return RotationT.get(getRotationFn.call0());
|
||||
}
|
||||
private static final Function freshImageFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraFreshImage");
|
||||
|
||||
/**
|
||||
* Has the current image from the camera been retrieved yet.
|
||||
* @return true if the latest image from the camera has not been retrieved yet.
|
||||
*/
|
||||
public boolean freshImage() {
|
||||
return freshImageFn.call0() == 0 ? false : true;
|
||||
}
|
||||
private static final Function getMaxFPSFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraGetMaxFPS");
|
||||
|
||||
/**
|
||||
* Get the maximum frames per second that the camera will generate.
|
||||
* @return the max fps.
|
||||
*/
|
||||
public int getMaxFPS() {
|
||||
return getMaxFPSFn.call0();
|
||||
}
|
||||
private static final Function writeMaxFPSFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraWriteMaxFPS");
|
||||
|
||||
/**
|
||||
* Set the maximum frames per second that the camera will generate.
|
||||
* @param value the new max fps
|
||||
*/
|
||||
public void writeMaxFPS(int value) {
|
||||
writeMaxFPSFn.call1(value);
|
||||
}
|
||||
private static final Function deleteInstanceFn = NativeLibrary.getDefaultInstance().getFunction("AxisCameraDeleteInstance");
|
||||
|
||||
static {
|
||||
VM.addShutdownHook(new Thread() {
|
||||
|
||||
public void run() {
|
||||
deleteInstanceFn.call0();
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,22 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.camera;
|
||||
|
||||
/**
|
||||
* An exception representing a problem with communicating with the camera.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class AxisCameraException extends Exception {
|
||||
/**
|
||||
* Create a new AxisCameraException.
|
||||
* @param msg The message to pass with the AxisCameraException.
|
||||
*/
|
||||
public AxisCameraException(String msg) {
|
||||
super(msg);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,11 @@
|
||||
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
|
||||
<html>
|
||||
<head>
|
||||
<title>FRC Camera Library</title>
|
||||
<meta http-equiv="Content-Type" content="text/html; charset=MacRoman">
|
||||
</head>
|
||||
<body>
|
||||
Provides classes for interfacing to the camera.
|
||||
</ul>
|
||||
</body>
|
||||
</html>
|
||||
@@ -0,0 +1,43 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
import edu.wpi.first.wpilibj.communication.NIRioStatus;
|
||||
import edu.wpi.first.wpilibj.util.UncleanStatusException;
|
||||
|
||||
public class CANExceptionFactory {
|
||||
// FRC Error codes
|
||||
static final int ERR_CANSessionMux_InvalidBuffer = -44086;
|
||||
static final int ERR_CANSessionMux_MessageNotFound = -44087;
|
||||
static final int ERR_CANSessionMux_NotAllowed = -44088;
|
||||
static final int ERR_CANSessionMux_NotInitialized = -44089;
|
||||
|
||||
public static void checkStatus(int status, int messageID) throws
|
||||
CANInvalidBufferException, CANMessageNotAllowedException,
|
||||
CANNotInitializedException, UncleanStatusException {
|
||||
switch (status) {
|
||||
case NIRioStatus.kRioStatusSuccess:
|
||||
// Everything is ok... don't throw.
|
||||
return;
|
||||
case ERR_CANSessionMux_InvalidBuffer:
|
||||
case NIRioStatus.kRIOStatusBufferInvalidSize:
|
||||
throw new CANInvalidBufferException();
|
||||
case ERR_CANSessionMux_MessageNotFound:
|
||||
case NIRioStatus.kRIOStatusOperationTimedOut:
|
||||
throw new CANMessageNotFoundException();
|
||||
case ERR_CANSessionMux_NotAllowed:
|
||||
case NIRioStatus.kRIOStatusFeatureNotSupported:
|
||||
throw new CANMessageNotAllowedException("MessageID = " + Integer.toString(messageID));
|
||||
case ERR_CANSessionMux_NotInitialized:
|
||||
case NIRioStatus.kRIOStatusResourceNotInitialized:
|
||||
throw new CANNotInitializedException();
|
||||
default:
|
||||
throw new UncleanStatusException("Fatal status code detected: " + Integer.toString(status));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,19 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
/**
|
||||
* Exception indicating that a CAN driver library entry-point
|
||||
* was passed an invalid buffer. Typically, this is due to a
|
||||
* buffer being too small to include the needed safety token.
|
||||
*/
|
||||
public class CANInvalidBufferException extends RuntimeException {
|
||||
public CANInvalidBufferException() {
|
||||
super();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,459 @@
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
//import com.ochafik.lang.jnaerator.runtime.LibraryExtractor;
|
||||
//import com.ochafik.lang.jnaerator.runtime.MangledFunctionMapper;
|
||||
//import com.sun.jna.Library;
|
||||
//import com.sun.jna.Native;
|
||||
//import com.sun.jna.NativeLibrary;
|
||||
//import com.sun.jna.Pointer;
|
||||
//import com.sun.jna.ptr.IntByReference;
|
||||
import edu.wpi.first.wpilibj.hal.JNIWrapper;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
/**
|
||||
* JNA Wrapper for library <b>CAN</b><br>
|
||||
* This file was autogenerated by <a href="http://jnaerator.googlecode.com/">JNAerator</a>,<br>
|
||||
* a tool written by <a href="http://ochafik.com/">Olivier Chafik</a> that <a href="http://code.google.com/p/jnaerator/wiki/CreditsAndLicense">uses a few opensource projects.</a>.<br>
|
||||
* For help, please visit <a href="http://nativelibs4java.googlecode.com/">NativeLibs4Java</a> , <a href="http://rococoa.dev.java.net/">Rococoa</a>, or <a href="http://jna.dev.java.net/">JNA</a>.
|
||||
*/
|
||||
public class CANJNI extends JNIWrapper{
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_REV = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_MAX_VOUT = ((0x00020000 | 0x02000000 | 0x00001c00) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_CANERR_B0 = 30;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_DIS = ((0x00020000 | 0x02000000 | 0x00000400) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_ACCEL = 0x05000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_FAULT = ((0x00020000 | 0x02000000 | 0x00001400) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_FIRMVER = 0x00000200;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_EN = ((0x00020000 | 0x02000000 | 0x00001000) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_ENUMERATE = 0x00000240;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_EN = ((0x00020000 | 0x02000000 | 0x00000400) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_LIMIT_REV = ((0x00020000 | 0x02000000 | 0x00001c00) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_POS_B2 = 11;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_POS_B3 = 12;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_EN = ((0x00020000 | 0x02000000 | 0x00000800) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_POS_B0 = 9;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_POS_B1 = 10;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_HWVER = ((0x00020000 | 0x1f000000) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_FAULT_ILIMIT = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_DC = ((0x00020000 | 0x02000000 | 0x00001000) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT = (0x00020000 | 0x02000000 | 0x00000000);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_VCOMP = 0x00000800;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_END = 0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_LIMIT_FWD = ((0x00020000 | 0x02000000 | 0x00001c00) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_M = 0x1f000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_ICTRL = 0x00001000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_CFG = 0x00001c00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_MFR_DEKA = 0x00030000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_SYSRST = 0x00000040;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_REF_QUAD_ENCODER = 0x03;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SYNC_PEND_NOW = 0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_CMODE_CURRENT = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_TEMP = ((0x00020000 | 0x02000000 | 0x00001400) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_DC = ((0x00020000 | 0x02000000 | 0x00000400) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_POS = 0x00000c00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_SFWD = 0x04;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_DIS = ((0x00020000 | 0x02000000 | 0x00001000) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_SET = ((0x00020000 | 0x02000000 | 0x00000000) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_HEARTBEAT = 0x00000140;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_FAULT_CURRENT = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_GYRO = 0x04000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_FAULT_TLIMIT = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_MFR_S = 16;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_T_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000400) | (10 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_MFR_M = 0x00ff0000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_CMODE_POS = 0x03;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_REF_POT = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_HWVER_UNKNOWN = 0x00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_BRAKE_COAST = ((0x00020000 | 0x02000000 | 0x00001c00) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_HWVER_JAG_1_0 = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DEVNO_BCAST = 0x00000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_T_SET = ((0x00020000 | 0x02000000 | 0x00000000) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_STKY_SREV = 0x80;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_IC = ((0x00020000 | 0x02000000 | 0x00001000) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_FAULT_COMM = 0x10;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_T_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00001000) | (9 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_SPD_B2 = 15;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_SPD_B1 = 14;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_STKY_FLT_CLR = 21;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_SPD_B3 = 16;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_MFG_S = 16;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000400) | (11 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_LIMIT = ((0x00020000 | 0x02000000 | 0x00001400) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_EN = ((0x00020000 | 0x02000000 | 0x00000000) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_RAMP_DIS = 0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_TEMP_B0 = 7;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_TEMP_B1 = 8;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_IC = ((0x00020000 | 0x02000000 | 0x00000c00) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_MOTOR = 0x02000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_T_EN = ((0x00020000 | 0x02000000 | 0x00000400) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DEVNO_M = 0x0000003f;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOLTBUS_B1 = 4;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_PING = ((0x00020000 | 0x1f000000) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_T_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000c00) | (10 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DEVNO_S = 0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_TRUST_HEARTBEAT = ((0x00020000 | 0x1f000000) | (13 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOLTBUS_B0 = 3;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_SPD_B0 = 13;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG = (0x00020000 | 0x02000000 | 0x00001c00);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FLT_COUNT_COMM = 28;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_SYSHALT = 0x00000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_DOWNLOAD = ((0x00020000 | 0x1f000000) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_CMODE = ((0x00020000 | 0x02000000 | 0x00001400) | (9 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_IN_RAMP = ((0x00020000 | 0x02000000 | 0x00000800) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_FAULT_VLIMIT = 0x04;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_SREV = 0x08;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_S = 24;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FLT_COUNT_VOLTBUS = 26;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_STATUS = 0x00001400;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_T_EN = ((0x00020000 | 0x02000000 | 0x00000000) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_VOLTBUS = ((0x00020000 | 0x02000000 | 0x00001400) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD = (0x00020000 | 0x1f000000);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_REQUEST = ((0x00020000 | 0x1f000000) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_VOLTAGE = 0x00000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_PER_EN_S3 = ((0x00020000 | 0x02000000 | 0x00001800) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_PER_EN_S2 = ((0x00020000 | 0x02000000 | 0x00001800) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_PSTAT = 0x00001800;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_CANERR_B1 = 31;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_PER_EN_S1 = ((0x00020000 | 0x02000000 | 0x00001800) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_REF_ENCODER = 0x00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_PER_EN_S0 = ((0x00020000 | 0x02000000 | 0x00001800) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_CURRENT = ((0x00020000 | 0x02000000 | 0x00001400) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_SET = ((0x00020000 | 0x02000000 | 0x00000c00) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_STKY_FWD = 0x10;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL = (0x00020000 | 0x02000000 | 0x00001000);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_HWVER_JAG_2_0 = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_MFG_M = 0x00ff0000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_LIMIT_CLR = 18;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_POT_TURNS = ((0x00020000 | 0x02000000 | 0x00001c00) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_REF = ((0x00020000 | 0x02000000 | 0x00000c00) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_PC = ((0x00020000 | 0x02000000 | 0x00000400) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_VOUT = ((0x00020000 | 0x02000000 | 0x00001400) | (10 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_SYSRESUME = 0x00000280;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UNTRUST_EN = ((0x00020000 | 0x1f000000) | (11 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_CANSTS = 29;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_DC = ((0x00020000 | 0x02000000 | 0x00000c00) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_POS = ((0x00020000 | 0x02000000 | 0x00001400) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_SET = ((0x00020000 | 0x02000000 | 0x00000400) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_FULL_M = 0x1fffffff;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_SPD = ((0x00020000 | 0x02000000 | 0x00001400) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_STKY_FLT_NCLR = 20;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS = (0x00020000 | 0x02000000 | 0x00001400);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_TRUST_EN = ((0x00020000 | 0x1f000000) | (12 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_T_SET = ((0x00020000 | 0x02000000 | 0x00001000) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_CODE_M = 0x0000ffff;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_CODE_S = 0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_T_EN = ((0x00020000 | 0x02000000 | 0x00000c00) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT = (0x00020000 | 0x02000000 | 0x00001800);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FAULT = 19;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FLT_COUNT_GATE = 27;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_T_EN = ((0x00020000 | 0x02000000 | 0x00001000) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_DEVQUERY = 0x000000c0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_USONIC = 0x06000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_CMODE_VCOMP = 0x04;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_T_SET = ((0x00020000 | 0x02000000 | 0x00000400) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_EN = ((0x00020000 | 0x02000000 | 0x00000c00) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_DIS = ((0x00020000 | 0x02000000 | 0x00000000) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_FWD = 0x01;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_DIS = ((0x00020000 | 0x02000000 | 0x00000800) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_REF_INV_ENCODER = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_NUM_BRUSHES = ((0x00020000 | 0x02000000 | 0x00001c00) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_RELAY = 0x03000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_DEVASSIGN = 0x00000080;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_T_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000000) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_SPD = 0x00000400;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_ENC_LINES = ((0x00020000 | 0x02000000 | 0x00001c00) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_REF_NONE = 0xff;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_FAULT_VBUS = 0x04;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_SET_RAMP = ((0x00020000 | 0x02000000 | 0x00000000) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_REF = ((0x00020000 | 0x02000000 | 0x00000400) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_POWER = ((0x00020000 | 0x02000000 | 0x00001400) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOLTOUT_B1 = 2;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000800) | (9 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOLTOUT_B0 = 1;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_LIMIT_MODE = ((0x00020000 | 0x02000000 | 0x00001c00) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOUT_B1 = 23;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_SEND_DATA = ((0x00020000 | 0x1f000000) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FLT_COUNT_CURRENT = 24;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_VOUT_B0 = 22;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_CFG_S0 = ((0x00020000 | 0x02000000 | 0x00001800) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_LIMIT_NCLR = 17;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_CFG_S1 = ((0x00020000 | 0x02000000 | 0x00001800) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_CFG_S2 = ((0x00020000 | 0x02000000 | 0x00001800) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_CFG_S3 = ((0x00020000 | 0x02000000 | 0x00001800) | (7 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_SET = ((0x00020000 | 0x02000000 | 0x00000800) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_UPDATE = 0x000001c0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_CFG_FAULT_TIME = ((0x00020000 | 0x02000000 | 0x00001c00) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_VOLTOUT = ((0x00020000 | 0x02000000 | 0x00001400) | (0 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_SET = ((0x00020000 | 0x02000000 | 0x00001000) | (2 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_M = 0x0000ffc0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_CMODE_SPEED = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_CLASS_M = 0x0000fc00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_DATA_S3 = ((0x00020000 | 0x02000000 | 0x00001800) | (11 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_S = 6;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_FLT_COUNT = ((0x00020000 | 0x02000000 | 0x00001400) | (12 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_DATA_S2 = ((0x00020000 | 0x02000000 | 0x00001800) | (10 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_DATA_S1 = ((0x00020000 | 0x02000000 | 0x00001800) | (9 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_PSTAT_DATA_S0 = ((0x00020000 | 0x02000000 | 0x00001800) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_PC = ((0x00020000 | 0x02000000 | 0x00001000) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_PC = ((0x00020000 | 0x02000000 | 0x00000c00) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_MFR_LM = 0x00020000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_DIS = ((0x00020000 | 0x02000000 | 0x00000c00) | (1 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_BCAST = 0x00000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_CMODE_VOLT = 0x00;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_DTYPE_S = 24;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000c00) | (11 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_FAULT_GATE_DRIVE = 0x08;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_STATUS_DTYPE_M = 0x1f000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_STKY_REV = 0x20;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_ROBOT = 0x01000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_API_MC_ACK = 0x00002000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP = (0x00020000 | 0x02000000 | 0x00000800);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_ACK = ((0x00020000 | 0x1f000000) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_COMP_RAMP = ((0x00020000 | 0x02000000 | 0x00000800) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_T_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000800) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS = (0x00020000 | 0x02000000 | 0x00000c00);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_SYNC = 0x00000180;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ICTRL_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00001000) | (10 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_CURRENT_B1 = 6;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD = (0x00020000 | 0x02000000 | 0x00000400);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_CURRENT_B0 = 5;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_UPDATE = 0x1f000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_SPD_IC = ((0x00020000 | 0x02000000 | 0x00000400) | (4 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_ACK = (0x00020000 | 0x02000000 | 0x00002000);
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_FAULT_TEMP = 0x02;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_T_SET = ((0x00020000 | 0x02000000 | 0x00000800) | (6 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_PSTAT_FLT_COUNT_TEMP = 25;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VOLT_SET_NO_ACK = ((0x00020000 | 0x02000000 | 0x00000000) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_DTYPE_GEART = 0x07000000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_MFR_NI = 0x00010000;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_POS_T_SET = ((0x00020000 | 0x02000000 | 0x00000c00) | (8 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_STATUS_STKY_FLT = ((0x00020000 | 0x02000000 | 0x00001400) | (11 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_UPD_RESET = ((0x00020000 | 0x1f000000) | (3 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int CAN_MSGID_API_ID_M = 0x000003c0;
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_API_VCOMP_T_EN = ((0x00020000 | 0x02000000 | 0x00000800) | (5 << 6));
|
||||
/** <i>native declaration : src\main\include\CAN\can_proto.h</i> */
|
||||
public static final int LM_STATUS_LIMIT_STKY_SFWD = 0x40;
|
||||
|
||||
public static final int CAN_SEND_PERIOD_NO_REPEAT = 0;
|
||||
public static final int CAN_SEND_PERIOD_STOP_REPEATING = -1;
|
||||
|
||||
/* Flags in the upper bits of the messageID */
|
||||
public static final int CAN_IS_FRAME_REMOTE = 0x80000000;
|
||||
public static final int CAN_IS_FRAME_11BIT = 0x40000000;
|
||||
|
||||
public static native void FRCNetworkCommunicationCANSessionMuxSendMessage(int messageID, ByteBuffer data, int periodMs, IntBuffer status);
|
||||
public static native ByteBuffer FRCNetworkCommunicationCANSessionMuxReceiveMessage(IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,41 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
/**
|
||||
* Exception indicating that the CAN driver layer has not been initialized.
|
||||
* This happens when an entry-point is called before a CAN driver plugin
|
||||
* has been installed.
|
||||
*/
|
||||
public class CANJaguarVersionException extends RuntimeException {
|
||||
|
||||
public static final int kMinLegalFIRSTFirmwareVersion = 101;
|
||||
// 3330 was the first shipping RDK firmware version for the Jaguar
|
||||
public static final int kMinRDKFirmwareVersion = 3330;
|
||||
|
||||
public CANJaguarVersionException(int deviceNumber, int fwVersion) {
|
||||
super(getString(deviceNumber, fwVersion));
|
||||
System.out.println("fwVersion[" + deviceNumber + "]: " + fwVersion);
|
||||
}
|
||||
|
||||
static String getString(int deviceNumber, int fwVersion) {
|
||||
String msg;
|
||||
if (fwVersion < kMinRDKFirmwareVersion) {
|
||||
msg = "Jaguar " + deviceNumber +
|
||||
" firmware is too old. It must be updated to at least version " +
|
||||
Integer.toString(kMinLegalFIRSTFirmwareVersion) +
|
||||
" of the FIRST approved firmware!";
|
||||
} else {
|
||||
msg = "Jaguar " + deviceNumber +
|
||||
" firmware is not FIRST approved. It must be updated to at least version " +
|
||||
Integer.toString(kMinLegalFIRSTFirmwareVersion) +
|
||||
" of the FIRST approved firmware!";
|
||||
}
|
||||
return msg;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,18 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
/**
|
||||
* Exception indicating that the Jaguar CAN Driver layer refused to send a
|
||||
* restricted message ID to the CAN bus.
|
||||
*/
|
||||
public class CANMessageNotAllowedException extends RuntimeException {
|
||||
public CANMessageNotAllowedException(String msg) {
|
||||
super(msg);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,19 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
/**
|
||||
* Exception indicating that a can message is not available from Network
|
||||
* Communications. This usually just means we already have the most recent
|
||||
* value cached locally.
|
||||
*/
|
||||
public class CANMessageNotFoundException extends RuntimeException {
|
||||
public CANMessageNotFoundException() {
|
||||
super();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,19 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.can;
|
||||
|
||||
/**
|
||||
* Exception indicating that the CAN driver layer has not been initialized.
|
||||
* This happens when an entry-point is called before a CAN driver plugin
|
||||
* has been installed.
|
||||
*/
|
||||
public class CANNotInitializedException extends RuntimeException {
|
||||
public CANNotInitializedException() {
|
||||
super();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,440 @@
|
||||
package edu.wpi.first.wpilibj.communication;
|
||||
//import com.ochafik.lang.jnaerator.runtime.Structure;
|
||||
//import com.ochafik.lang.jnaerator.runtime.Union;
|
||||
//import com.sun.jna.Pointer;
|
||||
import java.util.Arrays;
|
||||
import java.util.List;
|
||||
/**
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:11</i><br>
|
||||
* This file was autogenerated by <a href="http://jnaerator.googlecode.com/">JNAerator</a>,<br>
|
||||
* a tool written by <a href="http://ochafik.com/">Olivier Chafik</a> that <a href="http://code.google.com/p/jnaerator/wiki/CreditsAndLicense">uses a few opensource projects.</a>.<br>
|
||||
* For help, please visit <a href="http://nativelibs4java.googlecode.com/">NativeLibs4Java</a> , <a href="http://rococoa.dev.java.net/">Rococoa</a>, or <a href="http://jna.dev.java.net/">JNA</a>.
|
||||
*/
|
||||
public class FRCCommonControlData /*extends Structure<FRCCommonControlData, FRCCommonControlData.ByValue, FRCCommonControlData.ByReference >*/ {
|
||||
public short packetIndex;
|
||||
/** C type : field1_union */
|
||||
public byte control;
|
||||
public byte dsDigitalIn;
|
||||
public short teamID;
|
||||
public byte dsID_Alliance;
|
||||
public byte dsID_Position;
|
||||
public byte[] stick0Axes = new byte[6];
|
||||
/** Left-most 4 bits are unused */
|
||||
public short stick0Buttons;
|
||||
public byte[] stick1Axes = new byte[6];
|
||||
/** Left-most 4 bits are unused */
|
||||
public short stick1Buttons;
|
||||
public byte[] stick2Axes = new byte[6];
|
||||
/** Left-most 4 bits are unused */
|
||||
public short stick2Buttons;
|
||||
public byte[] stick3Axes = new byte[6];
|
||||
/** Left-most 4 bits are unused */
|
||||
public short stick3Buttons;
|
||||
/** Analog inputs are 10 bit right-justified */
|
||||
public short analog1;
|
||||
public short analog2;
|
||||
public short analog3;
|
||||
public short analog4;
|
||||
public long cRIOChecksum;
|
||||
public int FPGAChecksum0;
|
||||
public int FPGAChecksum1;
|
||||
public int FPGAChecksum2;
|
||||
public int FPGAChecksum3;
|
||||
/** C type : char[8] */
|
||||
public byte[] versionData = new byte[8];
|
||||
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:13</i> */
|
||||
public static class field1_union /*extends Union<field1_union, field1_union.ByValue, field1_union.ByReference >*/ {
|
||||
public byte control;
|
||||
/** C type : field1_struct */
|
||||
public field1_struct field1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:16</i> */
|
||||
public static abstract class field1_struct /*extends Structure<field1_struct, field1_struct.ByValue, field1_struct.ByReference >*/ {
|
||||
/** Conversion Error : checkVersions:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : test:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : resync:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : fmsAttached:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : autonomous:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : enabled:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : notEStop:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
/** Conversion Error : reset:1 (This runtime does not support bit fields : JNAerator (based on JNA) (please use BridJ instead)) */
|
||||
public field1_struct() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList();
|
||||
}
|
||||
//public field1_struct(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//public static abstract class ByReference extends field1_struct implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static abstract class ByValue extends field1_struct implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
public field1_union() {
|
||||
super();
|
||||
}
|
||||
/** @param field1 C type : field1_struct */
|
||||
public field1_union(field1_struct field1) {
|
||||
super();
|
||||
this.field1 = field1;
|
||||
//setType(field1_struct.class);
|
||||
}
|
||||
public field1_union(byte control) {
|
||||
super();
|
||||
this.control = control;
|
||||
//setType(Byte.TYPE);
|
||||
}
|
||||
//public field1_union(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field1_union newInstance() { return new field1_union(); }
|
||||
//public static field1_union[] newArray(int arrayLength) {
|
||||
// return Union.newArray(field1_union.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field1_union implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field1_union implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:45</i> */
|
||||
public static class field2_union /*extends Union<field2_union, field2_union.ByValue, field2_union.ByReference >*/ {
|
||||
/** C type : int8_t[6] */
|
||||
public byte[] stick0Axes = new byte[6];
|
||||
/** C type : field1_struct */
|
||||
public field1_struct field1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:47</i> */
|
||||
public static class field1_struct /*extends Structure<field1_struct, field1_struct.ByValue, field1_struct.ByReference >*/ {
|
||||
public byte stick0Axis1;
|
||||
public byte stick0Axis2;
|
||||
public byte stick0Axis3;
|
||||
public byte stick0Axis4;
|
||||
public byte stick0Axis5;
|
||||
public byte stick0Axis6;
|
||||
public field1_struct() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList("stick0Axis1", "stick0Axis2", "stick0Axis3", "stick0Axis4", "stick0Axis5", "stick0Axis6");
|
||||
}
|
||||
public field1_struct(byte stick0Axis1, byte stick0Axis2, byte stick0Axis3, byte stick0Axis4, byte stick0Axis5, byte stick0Axis6) {
|
||||
super();
|
||||
this.stick0Axis1 = stick0Axis1;
|
||||
this.stick0Axis2 = stick0Axis2;
|
||||
this.stick0Axis3 = stick0Axis3;
|
||||
this.stick0Axis4 = stick0Axis4;
|
||||
this.stick0Axis5 = stick0Axis5;
|
||||
this.stick0Axis6 = stick0Axis6;
|
||||
}
|
||||
//public field1_struct(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field1_struct newInstance() { return new field1_struct(); }
|
||||
//public static field1_struct[] newArray(int arrayLength) {
|
||||
// return Structure.newArray(field1_struct.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field1_struct implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field1_struct implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
public field2_union() {
|
||||
super();
|
||||
}
|
||||
/** @param field1 C type : field1_struct */
|
||||
public field2_union(field1_struct field1) {
|
||||
super();
|
||||
this.field1 = field1;
|
||||
//setType(field1_struct.class);
|
||||
}
|
||||
/** @param stick0Axes C type : int8_t[6] */
|
||||
public field2_union(byte stick0Axes[]) {
|
||||
super();
|
||||
if ((stick0Axes.length != this.stick0Axes.length))
|
||||
throw new IllegalArgumentException("Wrong array size !");
|
||||
this.stick0Axes = stick0Axes;
|
||||
//setType(byte[].class);
|
||||
}
|
||||
//public field2_union(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field2_union newInstance() { return new field2_union(); }
|
||||
//public static field2_union[] newArray(int arrayLength) {
|
||||
// return Union.newArray(field2_union.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field2_union implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field2_union implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:58</i> */
|
||||
public static class field3_union /*extends Union<field3_union, field3_union.ByValue, field3_union.ByReference >*/ {
|
||||
/** C type : int8_t[6] */
|
||||
public byte[] stick1Axes = new byte[6];
|
||||
/** C type : field1_struct */
|
||||
public field1_struct field1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:60</i> */
|
||||
public static class field1_struct /* extends Structure<field1_struct, field1_struct.ByValue, field1_struct.ByReference >*/ {
|
||||
public byte stick1Axis1;
|
||||
public byte stick1Axis2;
|
||||
public byte stick1Axis3;
|
||||
public byte stick1Axis4;
|
||||
public byte stick1Axis5;
|
||||
public byte stick1Axis6;
|
||||
public field1_struct() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList("stick1Axis1", "stick1Axis2", "stick1Axis3", "stick1Axis4", "stick1Axis5", "stick1Axis6");
|
||||
}
|
||||
public field1_struct(byte stick1Axis1, byte stick1Axis2, byte stick1Axis3, byte stick1Axis4, byte stick1Axis5, byte stick1Axis6) {
|
||||
super();
|
||||
this.stick1Axis1 = stick1Axis1;
|
||||
this.stick1Axis2 = stick1Axis2;
|
||||
this.stick1Axis3 = stick1Axis3;
|
||||
this.stick1Axis4 = stick1Axis4;
|
||||
this.stick1Axis5 = stick1Axis5;
|
||||
this.stick1Axis6 = stick1Axis6;
|
||||
}
|
||||
//public field1_struct(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field1_struct newInstance() { return new field1_struct(); }
|
||||
//public static field1_struct[] newArray(int arrayLength) {
|
||||
// return Structure.newArray(field1_struct.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field1_struct implements Structure.ByReference {
|
||||
//
|
||||
//};
|
||||
//public static class ByValue extends field1_struct implements Structure.ByValue {
|
||||
//
|
||||
//};
|
||||
};
|
||||
public field3_union() {
|
||||
super();
|
||||
}
|
||||
/** @param field1 C type : field1_struct */
|
||||
public field3_union(field1_struct field1) {
|
||||
super();
|
||||
this.field1 = field1;
|
||||
//setType(field1_struct.class);
|
||||
}
|
||||
/** @param stick1Axes C type : int8_t[6] */
|
||||
public field3_union(byte stick1Axes[]) {
|
||||
super();
|
||||
if ((stick1Axes.length != this.stick1Axes.length))
|
||||
throw new IllegalArgumentException("Wrong array size !");
|
||||
this.stick1Axes = stick1Axes;
|
||||
//setType(byte[].class);
|
||||
}
|
||||
//public field3_union(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field3_union newInstance() { return new field3_union(); }
|
||||
//public static field3_union[] newArray(int arrayLength) {
|
||||
// return Union.newArray(field3_union.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field3_union implements Structure.ByReference {
|
||||
//
|
||||
//};
|
||||
//public static class ByValue extends field3_union implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:71</i> */
|
||||
public static class field4_union /*extends Union<field4_union, field4_union.ByValue, field4_union.ByReference >*/ {
|
||||
/** C type : int8_t[6] */
|
||||
public byte[] stick2Axes = new byte[6];
|
||||
/** C type : field1_struct */
|
||||
public field1_struct field1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:73</i> */
|
||||
public static class field1_struct /* extends Structure<field1_struct, field1_struct.ByValue, field1_struct.ByReference >*/ {
|
||||
public byte stick2Axis1;
|
||||
public byte stick2Axis2;
|
||||
public byte stick2Axis3;
|
||||
public byte stick2Axis4;
|
||||
public byte stick2Axis5;
|
||||
public byte stick2Axis6;
|
||||
public field1_struct() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList("stick2Axis1", "stick2Axis2", "stick2Axis3", "stick2Axis4", "stick2Axis5", "stick2Axis6");
|
||||
}
|
||||
public field1_struct(byte stick2Axis1, byte stick2Axis2, byte stick2Axis3, byte stick2Axis4, byte stick2Axis5, byte stick2Axis6) {
|
||||
super();
|
||||
this.stick2Axis1 = stick2Axis1;
|
||||
this.stick2Axis2 = stick2Axis2;
|
||||
this.stick2Axis3 = stick2Axis3;
|
||||
this.stick2Axis4 = stick2Axis4;
|
||||
this.stick2Axis5 = stick2Axis5;
|
||||
this.stick2Axis6 = stick2Axis6;
|
||||
}
|
||||
//public field1_struct(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field1_struct newInstance() { return new field1_struct(); }
|
||||
//public static field1_struct[] newArray(int arrayLength) {
|
||||
// return Structure.newArray(field1_struct.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field1_struct implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field1_struct implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
public field4_union() {
|
||||
super();
|
||||
}
|
||||
/** @param field1 C type : field1_struct */
|
||||
public field4_union(field1_struct field1) {
|
||||
super();
|
||||
this.field1 = field1;
|
||||
//setType(field1_struct.class);
|
||||
}
|
||||
/** @param stick2Axes C type : int8_t[6] */
|
||||
public field4_union(byte stick2Axes[]) {
|
||||
super();
|
||||
if ((stick2Axes.length != this.stick2Axes.length))
|
||||
throw new IllegalArgumentException("Wrong array size !");
|
||||
this.stick2Axes = stick2Axes;
|
||||
//setType(byte[].class);
|
||||
}
|
||||
//public field4_union(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field4_union newInstance() { return new field4_union(); }
|
||||
//public static field4_union[] newArray(int arrayLength) {
|
||||
// return Union.newArray(field4_union.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field4_union implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field4_union implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:84</i> */
|
||||
public static class field5_union /* extends Union<field5_union, field5_union.ByValue, field5_union.ByReference >*/ {
|
||||
/** C type : int8_t[6] */
|
||||
public byte[] stick3Axes = new byte[6];
|
||||
/** C type : field1_struct */
|
||||
public field1_struct field1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:86</i> */
|
||||
public static class field1_struct /*extends Structure<field1_struct, field1_struct.ByValue, field1_struct.ByReference >*/ {
|
||||
public byte stick3Axis1;
|
||||
public byte stick3Axis2;
|
||||
public byte stick3Axis3;
|
||||
public byte stick3Axis4;
|
||||
public byte stick3Axis5;
|
||||
public byte stick3Axis6;
|
||||
public field1_struct() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList("stick3Axis1", "stick3Axis2", "stick3Axis3", "stick3Axis4", "stick3Axis5", "stick3Axis6");
|
||||
}
|
||||
public field1_struct(byte stick3Axis1, byte stick3Axis2, byte stick3Axis3, byte stick3Axis4, byte stick3Axis5, byte stick3Axis6) {
|
||||
super();
|
||||
this.stick3Axis1 = stick3Axis1;
|
||||
this.stick3Axis2 = stick3Axis2;
|
||||
this.stick3Axis3 = stick3Axis3;
|
||||
this.stick3Axis4 = stick3Axis4;
|
||||
this.stick3Axis5 = stick3Axis5;
|
||||
this.stick3Axis6 = stick3Axis6;
|
||||
}
|
||||
//public field1_struct(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field1_struct newInstance() { return new field1_struct(); }
|
||||
//public static field1_struct[] newArray(int arrayLength) {
|
||||
// return Structure.newArray(field1_struct.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field1_struct implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field1_struct implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
public field5_union() {
|
||||
super();
|
||||
}
|
||||
/** @param field1 C type : field1_struct */
|
||||
public field5_union(field1_struct field1) {
|
||||
super();
|
||||
this.field1 = field1;
|
||||
//setType(field1_struct.class);
|
||||
}
|
||||
/** @param stick3Axes C type : int8_t[6] */
|
||||
public field5_union(byte stick3Axes[]) {
|
||||
super();
|
||||
if ((stick3Axes.length != this.stick3Axes.length))
|
||||
throw new IllegalArgumentException("Wrong array size !");
|
||||
this.stick3Axes = stick3Axes;
|
||||
//setType(byte[].class);
|
||||
}
|
||||
//public field5_union(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected field5_union newInstance() { return new field5_union(); }
|
||||
//public static field5_union[] newArray(int arrayLength) {
|
||||
// return Union.newArray(field5_union.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends field5_union implements Structure.ByReference {
|
||||
|
||||
//};
|
||||
//public static class ByValue extends field5_union implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
};
|
||||
public FRCCommonControlData() {
|
||||
super();
|
||||
}
|
||||
protected List<? > getFieldOrder() {
|
||||
return Arrays.asList("packetIndex", "field1", "dsDigitalIn", "teamID", "dsID_Alliance", "dsID_Position", "field2", "stick0Buttons", "field3", "stick1Buttons", "field4", "stick2Buttons", "field5", "stick3Buttons", "analog1", "analog2", "analog3", "analog4", "cRIOChecksum", "FPGAChecksum0", "FPGAChecksum1", "FPGAChecksum2", "FPGAChecksum3", "versionData");
|
||||
}
|
||||
//public FRCCommonControlData(Pointer peer) {
|
||||
// super(peer);
|
||||
//}
|
||||
//protected ByReference newByReference() { return new ByReference(); }
|
||||
//protected ByValue newByValue() { return new ByValue(); }
|
||||
protected FRCCommonControlData newInstance() { return new FRCCommonControlData(); }
|
||||
//public static FRCCommonControlData[] newArray(int arrayLength) {
|
||||
// return Structure.newArray(FRCCommonControlData.class, arrayLength);
|
||||
//}
|
||||
//public static class ByReference extends FRCCommonControlData implements Structure.ByReference {
|
||||
//
|
||||
//};
|
||||
//public static class ByValue extends FRCCommonControlData implements Structure.ByValue {
|
||||
|
||||
//};
|
||||
}
|
||||
@@ -0,0 +1,12 @@
|
||||
package edu.wpi.first.wpilibj.communication;
|
||||
|
||||
public class FRCCommonControlMasks {
|
||||
public static byte CHECK_VERSIONS = 1 << 0;
|
||||
public static byte TEST = 1 << 1;
|
||||
public static byte RESYNC = 1 << 2;
|
||||
public static byte FMS_ATTATCHED = 1 << 3;
|
||||
public static byte AUTONOMOUS = 1 << 4;
|
||||
public static byte ENABLED = 1 << 5;
|
||||
public static byte NOT_ESTOP = 1 << 6;
|
||||
public static byte RESET = (byte) (1 << 7);
|
||||
}
|
||||
@@ -0,0 +1,545 @@
|
||||
package edu.wpi.first.wpilibj.communication;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ShortBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.hal.JNIWrapper;
|
||||
/**
|
||||
* JNA Wrapper for library <b>FRC_NetworkCommunications</b><br>
|
||||
* This file was autogenerated by <a href="http://jnaerator.googlecode.com/">JNAerator</a>,<br>
|
||||
* a tool written by <a href="http://ochafik.com/">Olivier Chafik</a> that <a href="http://code.google.com/p/jnaerator/wiki/CreditsAndLicense">uses a few opensource projects.</a>.<br>
|
||||
* For help, please visit <a href="http://nativelibs4java.googlecode.com/">NativeLibs4Java</a> , <a href="http://rococoa.dev.java.net/">Rococoa</a>, or <a href="http://jna.dev.java.net/">JNA</a>.
|
||||
*/
|
||||
public class FRCNetworkCommunicationsLibrary extends JNIWrapper {
|
||||
//public static final String JNA_LIBRARY_NAME = LibraryExtractor.getLibraryPath("FRC_NetworkCommunications", true, FRC_NetworkCommunicationsLibrary.class);
|
||||
//public static final NativeLibrary JNA_NATIVE_LIB = NativeLibrary.getInstance(FRC_NetworkCommunicationsLibrary.JNA_LIBRARY_NAME, MangledFunctionMapper.DEFAULT_OPTIONS);
|
||||
//static {
|
||||
//System.loadLibrary("JNIWrappers");
|
||||
//Native.register(FRC_NetworkCommunicationsLibrary.class, FRC_NetworkCommunicationsLibrary.JNA_NATIVE_LIB);
|
||||
//}
|
||||
/**
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tModuleType {
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:9</i> */
|
||||
public static final int kModuleType_Unknown = 0x00;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:10</i> */
|
||||
public static final int kModuleType_Analog = 0x01;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:11</i> */
|
||||
public static final int kModuleType_Digital = 0x02;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:12</i> */
|
||||
public static final int kModuleType_Solenoid = 0x03;
|
||||
};
|
||||
/**
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tTargetClass {
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:16</i> */
|
||||
public static final int kTargetClass_Unknown = 0x00;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:17</i> */
|
||||
public static final int kTargetClass_FRC1 = 0x10;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:18</i> */
|
||||
public static final int kTargetClass_FRC2 = 0x20;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:19</i> */
|
||||
public static final int kTargetClass_FRC2_Analog = (int)FRCNetworkCommunicationsLibrary.tTargetClass.kTargetClass_FRC2 | (int)FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Analog;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:20</i> */
|
||||
public static final int kTargetClass_FRC2_Digital = (int)FRCNetworkCommunicationsLibrary.tTargetClass.kTargetClass_FRC2 | (int)FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Digital;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:21</i> */
|
||||
public static final int kTargetClass_FRC2_Solenoid = (int)FRCNetworkCommunicationsLibrary.tTargetClass.kTargetClass_FRC2 | (int)FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Solenoid;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:22</i> */
|
||||
public static final int kTargetClass_FamilyMask = 0xF0;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:23</i> */
|
||||
public static final int kTargetClass_ModuleMask = 0x0F;
|
||||
};
|
||||
/**
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tResourceType {
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:10</i> */
|
||||
public static final int kResourceType_Controller = 0;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:11</i> */
|
||||
public static final int kResourceType_Module = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:12</i> */
|
||||
public static final int kResourceType_Language = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:13</i> */
|
||||
public static final int kResourceType_CANPlugin = 3;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:14</i> */
|
||||
public static final int kResourceType_Accelerometer = 4;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:15</i> */
|
||||
public static final int kResourceType_ADXL345 = 5;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:16</i> */
|
||||
public static final int kResourceType_AnalogChannel = 6;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:17</i> */
|
||||
public static final int kResourceType_AnalogTrigger = 7;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:18</i> */
|
||||
public static final int kResourceType_AnalogTriggerOutput = 8;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:19</i> */
|
||||
public static final int kResourceType_CANJaguar = 9;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:20</i> */
|
||||
public static final int kResourceType_Compressor = 10;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:21</i> */
|
||||
public static final int kResourceType_Counter = 11;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:22</i> */
|
||||
public static final int kResourceType_Dashboard = 12;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:23</i> */
|
||||
public static final int kResourceType_DigitalInput = 13;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:24</i> */
|
||||
public static final int kResourceType_DigitalOutput = 14;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:25</i> */
|
||||
public static final int kResourceType_DriverStationCIO = 15;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:26</i> */
|
||||
public static final int kResourceType_DriverStationEIO = 16;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:27</i> */
|
||||
public static final int kResourceType_DriverStationLCD = 17;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:28</i> */
|
||||
public static final int kResourceType_Encoder = 18;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:29</i> */
|
||||
public static final int kResourceType_GearTooth = 19;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:30</i> */
|
||||
public static final int kResourceType_Gyro = 20;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:31</i> */
|
||||
public static final int kResourceType_I2C = 21;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:32</i> */
|
||||
public static final int kResourceType_Framework = 22;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:33</i> */
|
||||
public static final int kResourceType_Jaguar = 23;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:34</i> */
|
||||
public static final int kResourceType_Joystick = 24;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:35</i> */
|
||||
public static final int kResourceType_Kinect = 25;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:36</i> */
|
||||
public static final int kResourceType_KinectStick = 26;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:37</i> */
|
||||
public static final int kResourceType_PIDController = 27;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:38</i> */
|
||||
public static final int kResourceType_Preferences = 28;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:39</i> */
|
||||
public static final int kResourceType_PWM = 29;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:40</i> */
|
||||
public static final int kResourceType_Relay = 30;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:41</i> */
|
||||
public static final int kResourceType_RobotDrive = 31;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:42</i> */
|
||||
public static final int kResourceType_SerialPort = 32;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:43</i> */
|
||||
public static final int kResourceType_Servo = 33;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:44</i> */
|
||||
public static final int kResourceType_Solenoid = 34;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:45</i> */
|
||||
public static final int kResourceType_SPI = 35;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:46</i> */
|
||||
public static final int kResourceType_Task = 36;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:47</i> */
|
||||
public static final int kResourceType_Ultrasonic = 37;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:48</i> */
|
||||
public static final int kResourceType_Victor = 38;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:49</i> */
|
||||
public static final int kResourceType_Button = 39;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:50</i> */
|
||||
public static final int kResourceType_Command = 40;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:51</i> */
|
||||
public static final int kResourceType_AxisCamera = 41;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:52</i> */
|
||||
public static final int kResourceType_PCVideoServer = 42;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:53</i> */
|
||||
public static final int kResourceType_SmartDashboard = 43;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:54</i> */
|
||||
public static final int kResourceType_Talon = 44;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:55</i> */
|
||||
public static final int kResourceType_HiTechnicColorSensor = 45;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:56</i> */
|
||||
public static final int kResourceType_HiTechnicAccel = 46;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:57</i> */
|
||||
public static final int kResourceType_HiTechnicCompass = 47;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:58</i> */
|
||||
public static final int kResourceType_SRF08 = 48;
|
||||
};
|
||||
/**
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tInstances {
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:63</i> */
|
||||
public static final int kLanguage_LabVIEW = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:64</i> */
|
||||
public static final int kLanguage_CPlusPlus = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:65</i> */
|
||||
public static final int kLanguage_Java = 3;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:66</i> */
|
||||
public static final int kLanguage_Python = 4;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:68</i> */
|
||||
public static final int kCANPlugin_BlackJagBridge = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:69</i> */
|
||||
public static final int kCANPlugin_2CAN = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:71</i> */
|
||||
public static final int kFramework_Iterative = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:72</i> */
|
||||
public static final int kFramework_Simple = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:74</i> */
|
||||
public static final int kRobotDrive_ArcadeStandard = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:75</i> */
|
||||
public static final int kRobotDrive_ArcadeButtonSpin = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:76</i> */
|
||||
public static final int kRobotDrive_ArcadeRatioCurve = 3;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:77</i> */
|
||||
public static final int kRobotDrive_Tank = 4;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:78</i> */
|
||||
public static final int kRobotDrive_MecanumPolar = 5;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:79</i> */
|
||||
public static final int kRobotDrive_MecanumCartesian = 6;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:81</i> */
|
||||
public static final int kDriverStationCIO_Analog = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:82</i> */
|
||||
public static final int kDriverStationCIO_DigitalIn = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:83</i> */
|
||||
public static final int kDriverStationCIO_DigitalOut = 3;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:85</i> */
|
||||
public static final int kDriverStationEIO_Acceleration = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:86</i> */
|
||||
public static final int kDriverStationEIO_AnalogIn = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:87</i> */
|
||||
public static final int kDriverStationEIO_AnalogOut = 3;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:88</i> */
|
||||
public static final int kDriverStationEIO_Button = 4;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:89</i> */
|
||||
public static final int kDriverStationEIO_LED = 5;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:90</i> */
|
||||
public static final int kDriverStationEIO_DigitalIn = 6;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:91</i> */
|
||||
public static final int kDriverStationEIO_DigitalOut = 7;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:92</i> */
|
||||
public static final int kDriverStationEIO_FixedDigitalOut = 8;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:93</i> */
|
||||
public static final int kDriverStationEIO_PWM = 9;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:94</i> */
|
||||
public static final int kDriverStationEIO_Encoder = 10;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:95</i> */
|
||||
public static final int kDriverStationEIO_TouchSlider = 11;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:97</i> */
|
||||
public static final int kADXL345_SPI = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:98</i> */
|
||||
public static final int kADXL345_I2C = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:100</i> */
|
||||
public static final int kCommand_Scheduler = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:102</i> */
|
||||
public static final int kSmartDashboard_Instance = 1;
|
||||
};
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input = 17;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Vertices1 = 21;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int SYS_STATUS_DATA_SIZE = 44;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Custom = 25;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Vertices2 = 23;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Header = 19;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Joystick = 24;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int IO_CONFIG_DATA_SIZE = 32;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h</i> */
|
||||
public static final int kMaxModuleNumber = 2;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output = 18;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Extra2 = 22;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int kFRC_NetworkCommunication_DynamicType_Kinect_Extra1 = 20;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int USER_DS_LCD_DATA_SIZE = 128;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h</i> */
|
||||
public static final int kUsageReporting_version = 1;
|
||||
/** <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h</i> */
|
||||
public static final int USER_STATUS_DATA_SIZE = (984 - 32 - 44);
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nAICalibration_getLSBWeight(const uint32_t, const uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\AICalibration.h:7</i><br>
|
||||
* @deprecated use the safer methods {@link #FRC_NetworkCommunication_nAICalibration_getLSBWeight(int, int, java.nio.IntBuffer)} and {@link #FRC_NetworkCommunication_nAICalibration_getLSBWeight(int, int, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int FRC_NetworkCommunication_nAICalibration_getLSBWeight(int aiSystemIndex, int channel, Integer status);
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nAICalibration_getLSBWeight(const uint32_t, const uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\AICalibration.h:7</i>
|
||||
*/
|
||||
public static native int FRCNetworkCommunicationAICalibrationGetLSBWeight(int aiSystemIndex, int channel, Integer status);
|
||||
/**
|
||||
* Original signature : <code>int32_t FRC_NetworkCommunication_nAICalibration_getOffset(const uint32_t, const uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\AICalibration.h:8</i><br>
|
||||
* @deprecated use the safer methods {@link #FRC_NetworkCommunication_nAICalibration_getOffset(int, int, java.nio.IntBuffer)} and {@link #FRC_NetworkCommunication_nAICalibration_getOffset(int, int, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int FRC_NetworkCommunication_nAICalibration_getOffset(int aiSystemIndex, int channel, Integer status);
|
||||
/**
|
||||
* Original signature : <code>int32_t FRC_NetworkCommunication_nAICalibration_getOffset(const uint32_t, const uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\AICalibration.h:8</i>
|
||||
*/
|
||||
public static native int FRCNetworkCommunicationAICalibrationGetOffset(int aiSystemIndex, int channel, Integer status);
|
||||
/**
|
||||
* Original signature : <code>bool getModulePresence(tModuleType, uint8_t)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:14</i>
|
||||
*/
|
||||
public static native byte getModulePresence(int moduleType, byte moduleNumber);
|
||||
/**
|
||||
* Original signature : <code>tTargetClass getTargetClass()</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:25</i>
|
||||
*/
|
||||
public static native int getTargetClass();
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nLoadOut_getModulePresence(uint32_t, uint8_t)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:32</i>
|
||||
*/
|
||||
public static native int FRCNetworkCommunicationLoadOutGetModulePresence(int moduleType, byte moduleNumber);
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nLoadOut_getTargetClass()</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\LoadOut.h:33</i>
|
||||
*/
|
||||
public static native int FRCNetworkCommunicationLoadOutGetTargetClass();
|
||||
/**
|
||||
* Original signature : <code>STATUS moduleNameFindBySymbolName(const char*, char*)</code><br>
|
||||
* @param symbol symbol name to look for<br>
|
||||
* @param module where to return module name<br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\symModuleLink.h:6</i><br>
|
||||
* @deprecated use the safer methods {@link #moduleNameFindBySymbolName(java.lang.String, java.nio.ByteBuffer)} and {@link #moduleNameFindBySymbolName(com.sun.jna.Pointer, com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native FRC_NetworkCommunicationsLibrary.STATUS moduleNameFindBySymbolName(Pointer symbol, Pointer module);
|
||||
/**
|
||||
* Original signature : <code>STATUS moduleNameFindBySymbolName(const char*, char*)</code><br>
|
||||
* @param symbol symbol name to look for<br>
|
||||
* @param module where to return module name<br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\symModuleLink.h:6</i>
|
||||
*/
|
||||
//public static native FRC_NetworkCommunicationsLibrary.STATUS moduleNameFindBySymbolName(String symbol, ByteBuffer module);
|
||||
/**
|
||||
* Report the usage of a resource of interest.
|
||||
<br>
|
||||
*
|
||||
<br>
|
||||
* @param resource one of the values in the tResourceType above (max value 51).
|
||||
<br>
|
||||
* @param instanceNumber an index that identifies the resource instance.
|
||||
<br>
|
||||
* @param context an optional additional context number for some cases (such as module number). Set to 0 to omit.
|
||||
<br>
|
||||
* @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string.<br>
|
||||
* Original signature : <code>uint32_t report(tResourceType, uint8_t, uint8_t, const char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:113</i><br>
|
||||
* @deprecated use the safer methods {@link #report(int, byte, byte, java.lang.String)} and {@link #report(int, byte, byte, com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int report(int resource, byte instanceNumber, byte context, Pointer feature);
|
||||
/**
|
||||
* Report the usage of a resource of interest.
|
||||
<br>
|
||||
*
|
||||
<br>
|
||||
* @param resource one of the values in the tResourceType above (max value 51).
|
||||
<br>
|
||||
* @param instanceNumber an index that identifies the resource instance.
|
||||
<br>
|
||||
* @param context an optional additional context number for some cases (such as module number). Set to 0 to omit.
|
||||
<br>
|
||||
* @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string.<br>
|
||||
* Original signature : <code>uint32_t report(tResourceType, uint8_t, uint8_t, const char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:113</i>
|
||||
*/
|
||||
public static native int report(int resource, byte instanceNumber, byte context, String feature);
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nUsageReporting_report(uint8_t, uint8_t, uint8_t, const char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:120</i><br>
|
||||
* @deprecated use the safer methods {@link #FRC_NetworkCommunication_nUsageReporting_report(byte, byte, byte, java.lang.String)} and {@link #FRC_NetworkCommunication_nUsageReporting_report(byte, byte, byte, com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int FRC_NetworkCommunication_nUsageReporting_report(byte resource, byte instanceNumber, byte context, Pointer feature);
|
||||
/**
|
||||
* Original signature : <code>uint32_t FRC_NetworkCommunication_nUsageReporting_report(uint8_t, uint8_t, uint8_t, const char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\UsageReporting.h:120</i>
|
||||
*/
|
||||
public static native int FRCNetworkCommunicationUsageReportingReport(byte resource, byte instanceNumber, byte context, String feature);
|
||||
/**
|
||||
* Original signature : <code>void getFPGAHardwareVersion(uint16_t*, uint32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:124</i><br>
|
||||
* @deprecated use the safer methods {@link #getFPGAHardwareVersion(java.nio.ShortBuffer, java.nio.IntBuffer)} and {@link #getFPGAHardwareVersion(com.sun.jna.ptr.ShortByReference, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void getFPGAHardwareVersion(ShortByReference fpgaVersion, IntByReference fpgaRevision);
|
||||
/**
|
||||
* Original signature : <code>void getFPGAHardwareVersion(uint16_t*, uint32_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:124</i>
|
||||
*/
|
||||
public static native void getFPGAHardwareVersion(ShortBuffer fpgaVersion, IntBuffer fpgaRevision);
|
||||
/**
|
||||
* Original signature : <code>int getCommonControlData(FRCCommonControlData*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:126</i>
|
||||
*/
|
||||
public static native int getCommonControlData(FRCCommonControlData data);
|
||||
/**
|
||||
* Original signature : <code>int getRecentCommonControlData(FRCCommonControlData*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:127</i>
|
||||
*/
|
||||
public static native int getRecentCommonControlData(FRCCommonControlData commonData, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int getRecentStatusData(uint8_t*, uint8_t*, uint8_t*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:128</i><br>
|
||||
* @deprecated use the safer methods {@link #getRecentStatusData(java.nio.ByteBuffer, java.nio.ByteBuffer, java.nio.ByteBuffer, int)} and {@link #getRecentStatusData(com.sun.jna.Pointer, com.sun.jna.Pointer, com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getRecentStatusData(Pointer batteryInt, Pointer batteryDec, Pointer dsDigitalOut, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int getRecentStatusData(uint8_t*, uint8_t*, uint8_t*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:128</i>
|
||||
*/
|
||||
public static native int getRecentStatusData(ByteBuffer batteryInt, ByteBuffer batteryDec, ByteBuffer dsDigitalOut, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int getDynamicControlData(uint8_t, char*, int32_t, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:129</i><br>
|
||||
* @deprecated use the safer methods {@link #getDynamicControlData(byte, java.nio.ByteBuffer, int, int)} and {@link #getDynamicControlData(byte, com.sun.jna.Pointer, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getDynamicControlData(byte type, Pointer dynamicData, int maxLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int getDynamicControlData(uint8_t, char*, int32_t, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:129</i>
|
||||
*/
|
||||
public static native int getDynamicControlData(byte type, ByteBuffer dynamicData, int maxLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setStatusData(float, uint8_t, uint8_t, const char*, int, const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:130</i><br>
|
||||
* @deprecated use the safer methods {@link #setStatusData(float, byte, byte, java.lang.String, int, java.lang.String, int, int)} and {@link #setStatusData(float, byte, byte, com.sun.jna.Pointer, int, com.sun.jna.Pointer, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int setStatusData(float battery, byte dsDigitalOut, byte updateNumber, Pointer userDataHigh, int userDataHighLength, Pointer userDataLow, int userDataLowLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setStatusData(float, uint8_t, uint8_t, const char*, int, const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:130</i>
|
||||
*/
|
||||
public static native int setStatusData(float battery, byte dsDigitalOut, byte updateNumber, String userDataHigh, int userDataHighLength, String userDataLow, int userDataLowLength);
|
||||
/**
|
||||
* Original signature : <code>int setStatusDataFloatAsInt(int, uint8_t, uint8_t, const char*, int, const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:133</i><br>
|
||||
* @deprecated use the safer methods {@link #setStatusDataFloatAsInt(int, byte, byte, java.lang.String, int, java.lang.String, int, int)} and {@link #setStatusDataFloatAsInt(int, byte, byte, com.sun.jna.Pointer, int, com.sun.jna.Pointer, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int setStatusDataFloatAsInt(int battery, byte dsDigitalOut, byte updateNumber, Pointer userDataHigh, int userDataHighLength, Pointer userDataLow, int userDataLowLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setStatusDataFloatAsInt(int, uint8_t, uint8_t, const char*, int, const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:133</i>
|
||||
*/
|
||||
public static native int setStatusDataFloatAsInt(int battery, byte dsDigitalOut, byte updateNumber, String userDataHigh, int userDataHighLength, String userDataLow, int userDataLowLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setErrorData(const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:136</i><br>
|
||||
* @deprecated use the safer methods {@link #setErrorData(java.lang.String, int, int)} and {@link #setErrorData(com.sun.jna.Pointer, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int setErrorData(Pointer errors, int errorsLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setErrorData(const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:136</i>
|
||||
*/
|
||||
public static native int setErrorData(String errors, int errorsLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setUserDsLcdData(const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:137</i><br>
|
||||
* @deprecated use the safer methods {@link #setUserDsLcdData(java.lang.String, int, int)} and {@link #setUserDsLcdData(com.sun.jna.Pointer, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int setUserDsLcdData(Pointer userDsLcdData, int userDsLcdDataLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int setUserDsLcdData(const char*, int, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:137</i>
|
||||
*/
|
||||
public static native int setUserDsLcdData(String userDsLcdData, int userDsLcdDataLength, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int overrideIOConfig(const char*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:138</i><br>
|
||||
* @deprecated use the safer methods {@link #overrideIOConfig(java.lang.String, int)} and {@link #overrideIOConfig(com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int overrideIOConfig(String ioConfig, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>int overrideIOConfig(const char*, int)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:138</i>
|
||||
*/
|
||||
public static native int overrideIOConfig(String ioConfig, int wait_ms);
|
||||
/**
|
||||
* Original signature : <code>void setNewDataSem(pthread_mutex_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:147</i>
|
||||
*/
|
||||
public static native void setNewDataSem(ByteBuffer mutexId);
|
||||
/**
|
||||
* Original signature : <code>void setResyncSem(pthread_mutex_t*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:148</i>
|
||||
*/
|
||||
//public static native void setResyncSem(FRC_NetworkCommunicationsLibrary.pthread_mutex_t pthread_mutex_tPtr1);
|
||||
/**
|
||||
* Original signature : <code>void signalResyncActionDone()</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:150</i>
|
||||
*/
|
||||
public static native void signalResyncActionDone();
|
||||
/**
|
||||
* this uint32_t is really a LVRefNum<br>
|
||||
* Original signature : <code>void setNewDataOccurRef(uint32_t)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:154</i>
|
||||
*/
|
||||
public static native void setNewDataOccurRef(int refnum);
|
||||
/**
|
||||
* Original signature : <code>void setResyncOccurRef(uint32_t)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:156</i>
|
||||
*/
|
||||
public static native void setResyncOccurRef(int refnum);
|
||||
/**
|
||||
* Original signature : <code>void FRC_NetworkCommunication_getVersionString(char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:159</i><br>
|
||||
* @deprecated use the safer methods {@link #FRC_NetworkCommunication_getVersionString(java.nio.ByteBuffer)} and {@link #FRC_NetworkCommunication_getVersionString(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void FRC_NetworkCommunication_getVersionString(Pointer version);
|
||||
/**
|
||||
* Original signature : <code>void FRC_NetworkCommunication_getVersionString(char*)</code><br>
|
||||
* <i>native declaration : src\main\include\NetworkCommunication\FRCComm.h:159</i>
|
||||
*/
|
||||
public static native void FRCNetworkCommunicationGetVersionString(ByteBuffer version);
|
||||
public static native void FRCNetworkCommunicationObserveUserProgramStarting();
|
||||
public static native void FRCNetworkCommunicationObserveUserProgramDisabled();
|
||||
public static native void FRCNetworkCommunicationObserveUserProgramAutonomous();
|
||||
public static native void FRCNetworkCommunicationObserveUserProgramTeleop();
|
||||
public static native void FRCNetworkCommunicationObserveUserProgramTest();
|
||||
public static native void FRCNetworkCommunicationReserve();
|
||||
|
||||
/*
|
||||
public static class pthread_mutex_t extends PointerType {
|
||||
public pthread_mutex_t(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public pthread_mutex_t() {
|
||||
super();
|
||||
}
|
||||
};
|
||||
public static class STATUS extends PointerType {
|
||||
public STATUS(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public STATUS() {
|
||||
super();
|
||||
}
|
||||
};*/
|
||||
|
||||
//
|
||||
// JNI Testing
|
||||
//
|
||||
public static native void JNIValueParameterTest(boolean booleanValue, byte byteValue, char charValue, short shortValue, int intValue, long longValue, float floatValue, double doubleValue );
|
||||
public static native boolean JNIValueReturnBooleanTest(boolean booleanValue);
|
||||
public static native byte JNIValueReturnByteTest(byte byteValue);
|
||||
public static native char JNIValueReturnCharTest(char charValue);
|
||||
public static native short JNIValueReturnShortTest(short shortValue);
|
||||
public static native int JNIValueReturnIntTest(int intValue);
|
||||
public static native long JNIValueReturnLongTest(long longValue);
|
||||
@@ -0,0 +1,12 @@
|
||||
package edu.wpi.first.wpilibj.communication;
|
||||
|
||||
public class NIRioStatus {
|
||||
// TODO: Should this file be auto-generated?
|
||||
public static final int kRioStatusOffset = -63000;
|
||||
|
||||
public static final int kRioStatusSuccess = 0;
|
||||
public static final int kRIOStatusBufferInvalidSize = kRioStatusOffset - 80;
|
||||
public static final int kRIOStatusOperationTimedOut = -52007;
|
||||
public static final int kRIOStatusFeatureNotSupported = kRioStatusOffset - 193;
|
||||
public static final int kRIOStatusResourceNotInitialized = -52010;
|
||||
}
|
||||
@@ -0,0 +1,18 @@
|
||||
package edu.wpi.first.wpilibj.communication;
|
||||
|
||||
public class UsageReporting {
|
||||
|
||||
public static void report(int resource, int instanceNumber, int i) {
|
||||
report(resource, instanceNumber, i, "");
|
||||
}
|
||||
|
||||
public static void report(int resource, int instanceNumber) {
|
||||
report(resource, instanceNumber, 0, "");
|
||||
}
|
||||
|
||||
public static void report(int resource, int instanceNumber, int i,
|
||||
String string) {
|
||||
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationUsageReportingReport((byte)resource, (byte) instanceNumber, (byte) i, string);
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,9 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
public class AccelerometerJNI extends JNIWrapper {
|
||||
public static native void setAccelerometerActive(boolean active);
|
||||
public static native void setAccelerometerRange(int range);
|
||||
public static native double getAccelerometerX();
|
||||
public static native double getAccelerometerY();
|
||||
public static native double getAccelerometerZ();
|
||||
}
|
||||
@@ -0,0 +1,62 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.LongBuffer;
|
||||
|
||||
public class AnalogJNI extends JNIWrapper {
|
||||
/**
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:58</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface AnalogTriggerType {
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:54</i> */
|
||||
public static final int kInWindow = 0;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:55</i> */
|
||||
public static final int kState = 1;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:56</i> */
|
||||
public static final int kRisingPulse = 2;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:57</i> */
|
||||
public static final int kFallingPulse = 3;
|
||||
};
|
||||
|
||||
public static native ByteBuffer initializeAnalogInputPort(ByteBuffer port_pointer, IntBuffer status);
|
||||
public static native ByteBuffer initializeAnalogOutputPort(ByteBuffer port_pointer, IntBuffer status);
|
||||
public static native byte checkAnalogModule(byte module);
|
||||
public static native byte checkAnalogInputChannel(int pin);
|
||||
public static native byte checkAnalogOutputChannel(int pin);
|
||||
public static native void setAnalogOutput(ByteBuffer port_pointer, double voltage, IntBuffer status);
|
||||
public static native double getAnalogOutput(ByteBuffer port_pointer, IntBuffer status);
|
||||
public static native void setAnalogSampleRate(double samplesPerSecond, IntBuffer status);
|
||||
public static native double getAnalogSampleRate(IntBuffer status);
|
||||
public static native void setAnalogSampleRateWithModule(byte module, double samplesPerSecond, IntBuffer status);
|
||||
public static native double getAnalogSampleRateWithModule(byte module, IntBuffer status);
|
||||
public static native void setAnalogAverageBits(ByteBuffer analog_port_pointer, int bits, IntBuffer status);
|
||||
public static native int getAnalogAverageBits(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native void setAnalogOversampleBits(ByteBuffer analog_port_pointer, int bits, IntBuffer status);
|
||||
public static native int getAnalogOversampleBits(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native short getAnalogValue(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native int getAnalogAverageValue(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native int getAnalogVoltsToValue(ByteBuffer analog_port_pointer, double voltage, IntBuffer status);
|
||||
public static native double getAnalogVoltage(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native double getAnalogAverageVoltage(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native int getAnalogLSBWeight(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native int getAnalogOffset(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native byte isAccumulatorChannel(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native void initAccumulator(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native void resetAccumulator(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native void setAccumulatorCenter(ByteBuffer analog_port_pointer, int center, IntBuffer status);
|
||||
public static native void setAccumulatorDeadband(ByteBuffer analog_port_pointer, int deadband, IntBuffer status);
|
||||
public static native long getAccumulatorValue(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native int getAccumulatorCount(ByteBuffer analog_port_pointer, IntBuffer status);
|
||||
public static native void getAccumulatorOutput(ByteBuffer analog_port_pointer, LongBuffer value, IntBuffer count, IntBuffer status);
|
||||
public static native ByteBuffer initializeAnalogTrigger(ByteBuffer port_pointer, IntBuffer index, IntBuffer status);
|
||||
public static native void cleanAnalogTrigger(ByteBuffer analog_trigger_pointer, IntBuffer status);
|
||||
public static native void setAnalogTriggerLimitsRaw(ByteBuffer analog_trigger_pointer, int lower, int upper, IntBuffer status);
|
||||
public static native void setAnalogTriggerLimitsVoltage(ByteBuffer analog_trigger_pointer, double lower, double upper, IntBuffer status);
|
||||
public static native void setAnalogTriggerAveraged(ByteBuffer analog_trigger_pointer, byte useAveragedValue, IntBuffer status);
|
||||
public static native void setAnalogTriggerFiltered(ByteBuffer analog_trigger_pointer, byte useFilteredValue, IntBuffer status);
|
||||
public static native byte getAnalogTriggerInWindow(ByteBuffer analog_trigger_pointer, IntBuffer status);
|
||||
public static native byte getAnalogTriggerTriggerState(ByteBuffer analog_trigger_pointer, IntBuffer status);
|
||||
public static native byte getAnalogTriggerOutput(ByteBuffer analog_trigger_pointer, int type, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
public class CompressorJNI extends JNIWrapper {
|
||||
public static native ByteBuffer initializeCompressor(byte module);
|
||||
public static native boolean checkCompressorModule(byte module);
|
||||
|
||||
public static native boolean getCompressor(ByteBuffer pcm_pointer, IntBuffer status);
|
||||
|
||||
public static native void setClosedLoopControl(ByteBuffer pcm_pointer, boolean value, IntBuffer status);
|
||||
public static native boolean getClosedLoopControl(ByteBuffer pcm_pointer, IntBuffer status);
|
||||
|
||||
public static native boolean getPressureSwitch(ByteBuffer pcm_pointer, IntBuffer status);
|
||||
public static native float getCompressorCurrent(ByteBuffer pcm_pointer, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,32 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class CounterJNI extends JNIWrapper {
|
||||
public static native ByteBuffer initializeCounter(int mode, IntBuffer index, IntBuffer status);
|
||||
public static native void freeCounter(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterAverageSize(ByteBuffer counter_pointer, int size, IntBuffer status);
|
||||
public static native void setCounterUpSourceWithModule(ByteBuffer counter_pointer, byte module, int pin, byte analogTrigger, IntBuffer status);
|
||||
public static native void setCounterUpSourceEdge(ByteBuffer counter_pointer, byte risingEdge, byte fallingEdge, IntBuffer status);
|
||||
public static native void clearCounterUpSource(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterDownSourceWithModule(ByteBuffer counter_pointer, byte module, int pin, byte analogTrigger, IntBuffer status);
|
||||
public static native void setCounterDownSourceEdge(ByteBuffer counter_pointer, byte risingEdge, byte fallingEdge, IntBuffer status);
|
||||
public static native void clearCounterDownSource(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterUpDownMode(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterExternalDirectionMode(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterSemiPeriodMode(ByteBuffer counter_pointer, byte highSemiPeriod, IntBuffer status);
|
||||
public static native void setCounterPulseLengthMode(ByteBuffer counter_pointer, double threshold, IntBuffer status);
|
||||
public static native int getCounterSamplesToAverage(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterSamplesToAverage(ByteBuffer counter_pointer, int samplesToAverage, IntBuffer status);
|
||||
public static native void startCounter(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void stopCounter(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void resetCounter(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native int getCounter(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native double getCounterPeriod(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterMaxPeriod(ByteBuffer counter_pointer, double maxPeriod, IntBuffer status);
|
||||
public static native void setCounterUpdateWhenEmpty(ByteBuffer counter_pointer, byte enabled, IntBuffer status);
|
||||
public static native byte getCounterStopped(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native byte getCounterDirection(ByteBuffer counter_pointer, IntBuffer status);
|
||||
public static native void setCounterReverseDirection(ByteBuffer counter_pointer, byte reverseDirection, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,22 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class DIOJNI extends JNIWrapper {
|
||||
public static native ByteBuffer initializeDigitalPort(ByteBuffer port_pointer, IntBuffer status);
|
||||
public static native byte allocateDIO(ByteBuffer digital_port_pointer, byte input, IntBuffer status);
|
||||
public static native void freeDIO(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
public static native void setDIO(ByteBuffer digital_port_pointer, short value, IntBuffer status);
|
||||
public static native byte getDIO(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
public static native byte getDIODirection(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
//public static native byte remapDigitalChannel(int pin, IntBuffer status);
|
||||
//public static native byte unmapDigitalChannel(int pin, IntBuffer status);
|
||||
public static native byte checkDigitalModule(byte module);
|
||||
public static native void pulse(ByteBuffer digital_port_pointer, double pulseLength, IntBuffer status);
|
||||
public static native byte isPulsing(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
public static native byte isAnyPulsing(IntBuffer status);
|
||||
public static native byte isAnyPulsingWithModule(byte module, IntBuffer status);
|
||||
public static native short getLoopTiming(IntBuffer status);
|
||||
public static native short getLoopTimingWithModule(byte module, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,20 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class EncoderJNI extends JNIWrapper {
|
||||
public static native ByteBuffer initializeEncoder(byte port_a_module, int port_a_pin, byte port_a_analog_trigger, byte port_b_module, int port_b_pin, byte port_b_analog_trigger, byte reverseDirection, IntBuffer index, IntBuffer status);
|
||||
public static native void freeEncoder(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native void startEncoder(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native void stopEncoder(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native void resetEncoder(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native int getEncoder(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native double getEncoderPeriod(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native void setEncoderMaxPeriod(ByteBuffer encoder_pointer, double maxPeriod, IntBuffer status);
|
||||
public static native byte getEncoderStopped(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native byte getEncoderDirection(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
public static native void setEncoderReverseDirection(ByteBuffer encoder_pointer, byte reverseDirection, IntBuffer status);
|
||||
public static native void setEncoderSamplesToAverage(ByteBuffer encoder_pointer, int samplesToAverage, IntBuffer status);
|
||||
public static native int getEncoderSamplesToAverage(ByteBuffer encoder_pointer, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,571 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
//import com.ochafik.lang.jnaerator.runtime.LibraryExtractor;
|
||||
//import com.ochafik.lang.jnaerator.runtime.MangledFunctionMapper;
|
||||
//import com.ochafik.lang.jnaerator.runtime.globals.GlobalDouble;
|
||||
//import com.ochafik.lang.jnaerator.runtime.globals.GlobalInt;
|
||||
//import com.sun.jna.Callback;
|
||||
//import com.sun.jna.Library;
|
||||
//import com.sun.jna.Native;
|
||||
//import com.sun.jna.NativeLibrary;
|
||||
//import com.sun.jna.Pointer;
|
||||
//import com.sun.jna.PointerType;
|
||||
//import com.sun.jna.ptr.IntByReference;
|
||||
//import com.sun.jna.ptr.LongByReference;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
/**
|
||||
* JNA Wrapper for library <b>HAL</b><br>
|
||||
* This file was autogenerated by <a href="http://jnaerator.googlecode.com/">JNAerator</a>,<br>
|
||||
* a tool written by <a href="http://ochafik.com/">Olivier Chafik</a> that <a href="http://code.google.com/p/jnaerator/wiki/CreditsAndLicense">uses a few opensource projects.</a>.<br>
|
||||
* For help, please visit <a href="http://nativelibs4java.googlecode.com/">NativeLibs4Java</a> , <a href="http://rococoa.dev.java.net/">Rococoa</a>, or <a href="http://jna.dev.java.net/">JNA</a>.
|
||||
*/
|
||||
public class HALLibrary /* implements Library */ {
|
||||
//public static final String JNA_LIBRARY_NAME = LibraryExtractor.getLibraryPath("HALAthenaJava", true, HALLibrary.class);
|
||||
//public static final NativeLibrary JNA_NATIVE_LIB = NativeLibrary.getInstance(HALLibrary.JNA_LIBRARY_NAME, MangledFunctionMapper.DEFAULT_OPTIONS);
|
||||
static {
|
||||
System.loadLibrary("JNIWrappers");
|
||||
// Native.register(HALLibrary.class, HALLibrary.JNA_NATIVE_LIB);
|
||||
}
|
||||
/**
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:148</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface Mode {
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:144</i> */
|
||||
public static final int kTwoPulse = 0;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:145</i> */
|
||||
public static final int kSemiperiod = 1;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:146</i> */
|
||||
public static final int kPulseLength = 2;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:147</i> */
|
||||
public static final int kExternalDirection = 3;
|
||||
};
|
||||
/**
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:235</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tSPIConstants {
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:233</i> */
|
||||
public static final int kReceiveFIFODepth = 512;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:234</i> */
|
||||
public static final int kTransmitFIFODepth = 512;
|
||||
};
|
||||
/**
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:241</i><br>
|
||||
* enum values
|
||||
*/
|
||||
public static interface tFrameMode {
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:237</i> */
|
||||
public static final int kChipSelect = 0;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:238</i> */
|
||||
public static final int kPreLatchPulse = 1;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:239</i> */
|
||||
public static final int kPostLatchPulse = 2;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:240</i> */
|
||||
public static final int kPreAndPostLatchPulse = 3;
|
||||
};
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String NULL_PARAMETER_MESSAGE = "A pointer parameter to a method is NULL";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String NO_AVAILABLE_RESOURCES_MESSAGE = "No available resources to allocate";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String INCOMPATIBLE_STATE_MESSAGE = "Incompatible State: The operation cannot be completed";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE = "Attempted to read AnalogTrigger pulse output.";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final int ANALOG_TRIGGER_LIMIT_ORDER_ERROR = -10;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final int SPI_READ_NO_DATA = 14;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String VOLTAGE_OUT_OF_RANGE_MESSAGE = "Voltage to convert to raw value is out of range [-10; 10]";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE = "AnalogTrigger limits error. Lower limit > Upper Limit";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final int SPI_WRITE_NO_MOSI = 12;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String PARAMETER_OUT_OF_RANGE_MESSAGE = "A parameter is out of range.";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Task.h</i> */
|
||||
public static final int OK = 0;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Task.h</i> */
|
||||
public static final int ERROR = (-1);
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String SAMPLE_RATE_TOO_HIGH_MESSAGE = "Analog module sample rate is too high";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String SPI_WRITE_NO_MOSI_MESSAGE = "Cannot write to SPI port with no MOSI output";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final int SPI_READ_NO_MISO = 13;
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String SPI_READ_NO_DATA_MESSAGE = "No data available to read from SPI";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String SPI_READ_NO_MISO_MESSAGE = "Cannot read from SPI port with no MISO input";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Errors.h</i> */
|
||||
public static final String LOOP_TIMING_ERROR_MESSAGE = "Digital module loop timing is not the expected value";
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:339</i> */
|
||||
//public interface initializeNotifier_ProcessQueue_callback extends Callback {
|
||||
// void apply(int uint32_t1, Pointer voidPtr1);
|
||||
//};
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Interrupts.h:342</i> */
|
||||
/** <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:409</i> */
|
||||
//public interface FUNCPTR extends Callback {
|
||||
// int apply(Object... varargs);
|
||||
//};
|
||||
/**
|
||||
* Original signature : <code>bool checkPWMChannel(void*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:84</i>
|
||||
*/
|
||||
//public static native byte checkPWMChannel(Pointer digital_port_pointer);
|
||||
/**
|
||||
* Original signature : <code>bool checkRelayChannel(void*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Digital.h:86</i>
|
||||
*/
|
||||
//public static native byte checkRelayChannel(Pointer digital_port_pointer);
|
||||
/**
|
||||
* Original signature : <code>void* initializeNotifier(initializeNotifier_ProcessQueue_callback*, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:334</i><br>
|
||||
* @deprecated use the safer methods {@link #initializeNotifier(edu.wpi.first.wpilibj.hal.HALLibrary.initializeNotifier_ProcessQueue_callback, java.nio.IntBuffer)} and {@link #initializeNotifier(edu.wpi.first.wpilibj.hal.HALLibrary.initializeNotifier_ProcessQueue_callback, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native Pointer initializeNotifier(HALLibrary.initializeNotifier_ProcessQueue_callback ProcessQueue, IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>void* initializeNotifier(initializeNotifier_ProcessQueue_callback*, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:334</i>
|
||||
*/
|
||||
//public static native Pointer initializeNotifier(HALLibrary.initializeNotifier_ProcessQueue_callback ProcessQueue, IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>void cleanNotifier(void*, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:336</i><br>
|
||||
* @deprecated use the safer methods {@link #cleanNotifier(com.sun.jna.Pointer, java.nio.IntBuffer)} and {@link #cleanNotifier(com.sun.jna.Pointer, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void cleanNotifier(Pointer notifier_pointer, IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>void cleanNotifier(void*, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:336</i>
|
||||
*/
|
||||
//public static native void cleanNotifier(Pointer notifier_pointer, IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>void updateNotifierAlarm(void*, uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:338</i><br>
|
||||
* @deprecated use the safer methods {@link #updateNotifierAlarm(com.sun.jna.Pointer, int, java.nio.IntBuffer)} and {@link #updateNotifierAlarm(com.sun.jna.Pointer, int, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void updateNotifierAlarm(Pointer notifier_pointer, int triggerTime, IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>void updateNotifierAlarm(void*, uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Notifier.h:338</i>
|
||||
*/
|
||||
//public static native void updateNotifierAlarm(Pointer notifier_pointer, int triggerTime, IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>void delayTicks(int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Utilities.h:366</i>
|
||||
*/
|
||||
public static native void delayTicks(int ticks);
|
||||
/**
|
||||
* Original signature : <code>void delayMillis(double)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Utilities.h:368</i>
|
||||
*/
|
||||
public static native void delayMillis(double ms);
|
||||
/**
|
||||
* Original signature : <code>void delaySeconds(double)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Utilities.h:370</i>
|
||||
*/
|
||||
public static native void delaySeconds(double s);
|
||||
/**
|
||||
* Original signature : <code>MUTEX_ID initializeMutex(uint32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:385</i>
|
||||
*/
|
||||
public static native ByteBuffer initializeMutex(int flags);
|
||||
/**
|
||||
* Original signature : <code>void deleteMutex(MUTEX_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:387</i><br>
|
||||
* @deprecated use the safer methods {@link #deleteMutex(edu.wpi.first.wpilibj.hal.HALLibrary.MUTEX_ID)} and {@link #deleteMutex(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void deleteMutex(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>void deleteMutex(MUTEX_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:387</i>
|
||||
*/
|
||||
public static native void deleteMutex(ByteBuffer sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeMutex(MUTEX_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:389</i><br>
|
||||
* @deprecated use the safer methods {@link #takeMutex(edu.wpi.first.wpilibj.hal.HALLibrary.MUTEX_ID, int)} and {@link #takeMutex(com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte takeMutex(Pointer sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeMutex(MUTEX_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:389</i>
|
||||
*/
|
||||
public static native byte takeMutex(ByteBuffer sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveMutex(MUTEX_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:391</i><br>
|
||||
* @deprecated use the safer methods {@link #giveMutex(edu.wpi.first.wpilibj.hal.HALLibrary.MUTEX_ID)} and {@link #giveMutex(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte giveMutex(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveMutex(MUTEX_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:391</i>
|
||||
*/
|
||||
//public static native byte giveMutex(HALLibrary.MUTEX_ID sem);
|
||||
/**
|
||||
* Original signature : <code>SEMAPHORE_ID initializeSemaphore(uint32_t, uint32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:393</i>
|
||||
*/
|
||||
//public static native HALLibrary.SEMAPHORE_ID initializeSemaphore(int flags, int initial_value);
|
||||
/**
|
||||
* Original signature : <code>void deleteSemaphore(SEMAPHORE_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:395</i><br>
|
||||
* @deprecated use the safer methods {@link #deleteSemaphore(edu.wpi.first.wpilibj.hal.HALLibrary.SEMAPHORE_ID)} and {@link #deleteSemaphore(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void deleteSemaphore(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>void deleteSemaphore(SEMAPHORE_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:395</i>
|
||||
*/
|
||||
//public static native void deleteSemaphore(HALLibrary.SEMAPHORE_ID sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeSemaphore(SEMAPHORE_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:397</i><br>
|
||||
* @deprecated use the safer methods {@link #takeSemaphore(edu.wpi.first.wpilibj.hal.HALLibrary.SEMAPHORE_ID, int)} and {@link #takeSemaphore(com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte takeSemaphore(Pointer sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeSemaphore(SEMAPHORE_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:397</i>
|
||||
*/
|
||||
//public static native byte takeSemaphore(HALLibrary.SEMAPHORE_ID sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveSemaphore(SEMAPHORE_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:399</i><br>
|
||||
* @deprecated use the safer methods {@link #giveSemaphore(edu.wpi.first.wpilibj.hal.HALLibrary.SEMAPHORE_ID)} and {@link #giveSemaphore(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte giveSemaphore(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveSemaphore(SEMAPHORE_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:399</i>
|
||||
*/
|
||||
//public static native byte giveSemaphore(HALLibrary.SEMAPHORE_ID sem);
|
||||
/**
|
||||
* Original signature : <code>MULTIWAIT_ID initializeMultiWait()</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:401</i>
|
||||
*/
|
||||
//public static native HALLibrary.MULTIWAIT_ID initializeMultiWait();
|
||||
/**
|
||||
* Original signature : <code>void deleteMultiWait(MULTIWAIT_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:403</i><br>
|
||||
* @deprecated use the safer methods {@link #deleteMultiWait(edu.wpi.first.wpilibj.hal.HALLibrary.MULTIWAIT_ID)} and {@link #deleteMultiWait(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void deleteMultiWait(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>void deleteMultiWait(MULTIWAIT_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:403</i>
|
||||
*/
|
||||
//public static native void deleteMultiWait(HALLibrary.MULTIWAIT_ID sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeMultiWait(MULTIWAIT_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:405</i><br>
|
||||
* @deprecated use the safer methods {@link #takeMultiWait(edu.wpi.first.wpilibj.hal.HALLibrary.MULTIWAIT_ID, int)} and {@link #takeMultiWait(com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte takeMultiWait(Pointer sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t takeMultiWait(MULTIWAIT_ID, int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:405</i>
|
||||
*/
|
||||
//public static native byte takeMultiWait(HALLibrary.MULTIWAIT_ID sem, int timeout);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveMultiWait(MULTIWAIT_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:407</i><br>
|
||||
* @deprecated use the safer methods {@link #giveMultiWait(edu.wpi.first.wpilibj.hal.HALLibrary.MULTIWAIT_ID)} and {@link #giveMultiWait(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native byte giveMultiWait(Pointer sem);
|
||||
/**
|
||||
* Original signature : <code>int8_t giveMultiWait(MULTIWAIT_ID)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Semaphore.h:407</i>
|
||||
*/
|
||||
//public static native byte giveMultiWait(HALLibrary.MULTIWAIT_ID sem);
|
||||
/**
|
||||
* Original signature : <code>TASK spawnTask(char*, int, int, int, FUNCPTR, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:420</i><br>
|
||||
* @deprecated use the safer methods {@link #spawnTask(java.nio.ByteBuffer, int, int, int, edu.wpi.first.wpilibj.hal.HALLibrary.FUNCPTR, int, int, int, int, int, int, int, int, int, int)} and {@link #spawnTask(com.sun.jna.Pointer, int, int, int, edu.wpi.first.wpilibj.hal.HALLibrary.FUNCPTR, int, int, int, int, int, int, int, int, int, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native HALLibrary.TASK spawnTask(Pointer name, int priority, int options, int stackSize, HALLibrary.FUNCPTR entryPt, int arg0, int arg1, int arg2, int arg3, int arg4, int arg5, int arg6, int arg7, int arg8, int arg9);
|
||||
/**
|
||||
* Original signature : <code>TASK spawnTask(char*, int, int, int, FUNCPTR, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t, uint32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:420</i>
|
||||
*/
|
||||
//public static native HALLibrary.TASK spawnTask(ByteBuffer name, int priority, int options, int stackSize, HALLibrary.FUNCPTR entryPt, int arg0, int arg1, int arg2, int arg3, int arg4, int arg5, int arg6, int arg7, int arg8, int arg9);
|
||||
/**
|
||||
* Original signature : <code>STATUS restartTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:422</i><br>
|
||||
* @deprecated use the safer methods {@link #restartTask(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #restartTask(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int restartTask(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS restartTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:422</i>
|
||||
*/
|
||||
//public static native int restartTask(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS deleteTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:424</i><br>
|
||||
* @deprecated use the safer methods {@link #deleteTask(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #deleteTask(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int deleteTask(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS deleteTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:424</i>
|
||||
*/
|
||||
//public static native int deleteTask(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS isTaskReady(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:426</i><br>
|
||||
* @deprecated use the safer methods {@link #isTaskReady(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #isTaskReady(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int isTaskReady(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS isTaskReady(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:426</i>
|
||||
*/
|
||||
//public static native int isTaskReady(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS isTaskSuspended(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:428</i><br>
|
||||
* @deprecated use the safer methods {@link #isTaskSuspended(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #isTaskSuspended(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int isTaskSuspended(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS isTaskSuspended(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:428</i>
|
||||
*/
|
||||
//public static native int isTaskSuspended(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS suspendTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:430</i><br>
|
||||
* @deprecated use the safer methods {@link #suspendTask(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #suspendTask(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int suspendTask(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS suspendTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:430</i>
|
||||
*/
|
||||
//public static native int suspendTask(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS resumeTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:432</i><br>
|
||||
* @deprecated use the safer methods {@link #resumeTask(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #resumeTask(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int resumeTask(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS resumeTask(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:432</i>
|
||||
*/
|
||||
//public static native int resumeTask(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS verifyTaskID(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:434</i><br>
|
||||
* @deprecated use the safer methods {@link #verifyTaskID(edu.wpi.first.wpilibj.hal.HALLibrary.TASK)} and {@link #verifyTaskID(com.sun.jna.Pointer)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int verifyTaskID(Pointer task);
|
||||
/**
|
||||
* Original signature : <code>STATUS verifyTaskID(TASK)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:434</i>
|
||||
*/
|
||||
//public static native int verifyTaskID(HALLibrary.TASK task);
|
||||
/**
|
||||
* Original signature : <code>STATUS setTaskPriority(TASK, int)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:436</i><br>
|
||||
* @deprecated use the safer methods {@link #setTaskPriority(edu.wpi.first.wpilibj.hal.HALLibrary.TASK, int)} and {@link #setTaskPriority(com.sun.jna.Pointer, int)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int setTaskPriority(Pointer task, int priority);
|
||||
/**
|
||||
* Original signature : <code>STATUS setTaskPriority(TASK, int)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:436</i>
|
||||
*/
|
||||
//public static native int setTaskPriority(HALLibrary.TASK task, int priority);
|
||||
/**
|
||||
* Original signature : <code>STATUS getTaskPriority(TASK, int*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:438</i><br>
|
||||
* @deprecated use the safer methods {@link #getTaskPriority(edu.wpi.first.wpilibj.hal.HALLibrary.TASK, java.nio.IntBuffer)} and {@link #getTaskPriority(com.sun.jna.Pointer, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getTaskPriority(Pointer task, IntByReference priority);
|
||||
/**
|
||||
* Original signature : <code>STATUS getTaskPriority(TASK, int*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\Task.h:438</i>
|
||||
*/
|
||||
//public static native int getTaskPriority(HALLibrary.TASK task, IntBuffer priority);
|
||||
/**
|
||||
* Original signature : <code>void* getPort(uint8_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:446</i>
|
||||
*/
|
||||
//public static native Pointer getPort(byte pin);
|
||||
/**
|
||||
* Original signature : <code>uint16_t getFPGAVersion(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:452</i><br>
|
||||
* @deprecated use the safer methods {@link #getFPGAVersion(java.nio.IntBuffer)} and {@link #getFPGAVersion(com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native short getFPGAVersion(IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>uint16_t getFPGAVersion(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:452</i>
|
||||
*/
|
||||
//public static native short getFPGAVersion(IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>uint32_t getFPGARevision(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:454</i><br>
|
||||
* @deprecated use the safer methods {@link #getFPGARevision(java.nio.IntBuffer)} and {@link #getFPGARevision(com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getFPGARevision(IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>uint32_t getFPGARevision(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:454</i>
|
||||
*/
|
||||
//public static native int getFPGARevision(IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>uint32_t getFPGATime(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:456</i><br>
|
||||
* @deprecated use the safer methods {@link #getFPGATime(java.nio.IntBuffer)} and {@link #getFPGATime(com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getFPGATime(IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>uint32_t getFPGATime(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:456</i>
|
||||
*/
|
||||
//public static native int getFPGATime(IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>void setFPGALED(uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:458</i><br>
|
||||
* @deprecated use the safer methods {@link #setFPGALED(int, java.nio.IntBuffer)} and {@link #setFPGALED(int, com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native void setFPGALED(int state, IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>void setFPGALED(uint32_t, int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:458</i>
|
||||
*/
|
||||
public static native void setFPGALED(int state, IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>int32_t getFPGALED(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:460</i><br>
|
||||
* @deprecated use the safer methods {@link #getFPGALED(java.nio.IntBuffer)} and {@link #getFPGALED(com.sun.jna.ptr.IntByReference)} instead
|
||||
*/
|
||||
//@Deprecated
|
||||
//public static native int getFPGALED(IntByReference status);
|
||||
/**
|
||||
* Original signature : <code>int32_t getFPGALED(int32_t*)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:460</i>
|
||||
*/
|
||||
public static native int getFPGALED(IntBuffer status);
|
||||
/**
|
||||
* Original signature : <code>double testDouble(double)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:462</i>
|
||||
*/
|
||||
public static native double testDouble(double param);
|
||||
/**
|
||||
* Original signature : <code>int32_t testInt32(int32_t)</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:464</i>
|
||||
*/
|
||||
public static native int testInt32(int param);
|
||||
/**
|
||||
* Original signature : <code>void NumericArrayResize()</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:470</i>
|
||||
*/
|
||||
public static native void NumericArrayResize();
|
||||
/**
|
||||
* Original signature : <code>void RTSetCleanupProc()</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:472</i>
|
||||
*/
|
||||
public static native void RTSetCleanupProc();
|
||||
/**
|
||||
* Original signature : <code>void EDVR_CreateReference()</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:474</i>
|
||||
*/
|
||||
public static native void EDVR_CreateReference();
|
||||
/**
|
||||
* Original signature : <code>void Occur()</code><br>
|
||||
* <i>native declaration : AthenaJava\target\native\include\HAL\HAL.h:476</i>
|
||||
*/
|
||||
public static native void Occur();
|
||||
/*
|
||||
public static final GlobalDouble kDefaultWatchdogExpiration = new GlobalDouble(HALLibrary.JNA_NATIVE_LIB, "kDefaultWatchdogExpiration");
|
||||
public static final GlobalInt HAL_NO_WAIT = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_NO_WAIT");
|
||||
public static final GlobalInt HAL_WAIT_FOREVER = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_WAIT_FOREVER");
|
||||
public static final GlobalInt SEMAPHORE_Q_FIFO = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_Q_FIFO");
|
||||
*/
|
||||
/*
|
||||
public static final GlobalInt SEMAPHORE_DELETE_SAFE = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_DELETE_SAFE");
|
||||
public static final GlobalInt SEMAPHORE_INVERSION_SAFE = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_INVERSION_SAFE");
|
||||
public static final GlobalInt SEMAPHORE_NO_WAIT = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_NO_WAIT");
|
||||
*/
|
||||
/*
|
||||
public static final GlobalInt SEMAPHORE_EMPTY = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_EMPTY");
|
||||
public static final GlobalInt SEMAPHORE_FULL = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "SEMAPHORE_FULL");
|
||||
public static final GlobalInt VXWORKS_FP_TASK = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "VXWORKS_FP_TASK");
|
||||
public static final GlobalInt HAL_objLib_OBJ_ID_ERROR = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_objLib_OBJ_ID_ERROR");
|
||||
public static final GlobalInt HAL_objLib_OBJ_DELETED = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_objLib_OBJ_DELETED");
|
||||
public static final GlobalInt HAL_taskLib_ILLEGAL_OPTIONS = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_taskLib_ILLEGAL_OPTIONS");
|
||||
public static final GlobalInt HAL_memLib_NOT_ENOUGH_MEMORY = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_memLib_NOT_ENOUGH_MEMORY");
|
||||
public static final GlobalInt HAL_taskLib_ILLEGAL_PRIORITY = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "HAL_taskLib_ILLEGAL_PRIORITY");
|
||||
public static final GlobalInt dio_kNumSystems = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "dio_kNumSystems");
|
||||
public static final GlobalInt solenoid_kNumDO7_0Elements = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "solenoid_kNumDO7_0Elements");
|
||||
public static final GlobalInt interrupt_kNumSystems = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "interrupt_kNumSystems");
|
||||
public static final GlobalInt kSystemClockTicksPerMicrosecond = new GlobalInt(HALLibrary.JNA_NATIVE_LIB, "kSystemClockTicksPerMicrosecond");
|
||||
*/
|
||||
/*
|
||||
public static class TASK extends PointerType {
|
||||
public TASK(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public TASK() {
|
||||
super();
|
||||
}
|
||||
};
|
||||
public static class MUTEX_ID extends PointerType {
|
||||
public MUTEX_ID(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public MUTEX_ID() {
|
||||
super();
|
||||
}
|
||||
};
|
||||
public static class MULTIWAIT_ID extends PointerType {
|
||||
public MULTIWAIT_ID(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public MULTIWAIT_ID() {
|
||||
super();
|
||||
}
|
||||
};
|
||||
public static class SEMAPHORE_ID extends PointerType {
|
||||
public SEMAPHORE_ID(Pointer address) {
|
||||
super(address);
|
||||
}
|
||||
public SEMAPHORE_ID() {
|
||||
super();
|
||||
}
|
||||
};
|
||||
*/
|
||||
}
|
||||
@@ -0,0 +1,53 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class HALUtil extends JNIWrapper {
|
||||
public static final int NULL_PARAMETER = -5;
|
||||
public static final int SAMPLE_RATE_TOO_HIGH = 1;
|
||||
public static final int VOLTAGE_OUT_OF_RANGE = 2;
|
||||
public static final int LOOP_TIMING_ERROR = 4;
|
||||
public static final int INCOMPATIBLE_STATE = 15;
|
||||
public static final int ANALOG_TRIGGER_PULSE_OUTPUT_ERROR = -11;
|
||||
public static final int NO_AVAILABLE_RESOURCES = -4;
|
||||
public static final int PARAMETER_OUT_OF_RANGE = -28;
|
||||
|
||||
//public static final int SEMAPHORE_WAIT_FOREVER = -1;
|
||||
//public static final int SEMAPHORE_Q_PRIORITY = 0x01;
|
||||
|
||||
public static native ByteBuffer initializeMutexNormal();
|
||||
public static native void deleteMutex(ByteBuffer sem);
|
||||
public static native byte takeMutex(ByteBuffer sem);
|
||||
//public static native ByteBuffer initializeSemaphore(int initialValue);
|
||||
//public static native void deleteSemaphore(ByteBuffer sem);
|
||||
//public static native byte takeSemaphore(ByteBuffer sem, int timeout);
|
||||
public static native short getFPGAVersion(IntBuffer status);
|
||||
public static native int getFPGARevision(IntBuffer status);
|
||||
public static native long getFPGATime(IntBuffer status);
|
||||
|
||||
public static native String getHALErrorMessage(int code);
|
||||
|
||||
public static void checkStatus(IntBuffer status)
|
||||
{
|
||||
int s = status.get(0);
|
||||
if (s != 0)
|
||||
{
|
||||
String message = "Code: " + s + ". " + HALUtil.getHALErrorMessage(s);
|
||||
if (s == HALUtil.NULL_PARAMETER
|
||||
|| s == HALUtil.SAMPLE_RATE_TOO_HIGH
|
||||
|| s == HALUtil.VOLTAGE_OUT_OF_RANGE)
|
||||
throw new IllegalArgumentException(message);
|
||||
else if (s == HALUtil.LOOP_TIMING_ERROR)
|
||||
throw new RuntimeException(message);
|
||||
else if (s == HALUtil.INCOMPATIBLE_STATE
|
||||
|| s == HALUtil.ANALOG_TRIGGER_PULSE_OUTPUT_ERROR)
|
||||
throw new IllegalStateException(message);
|
||||
else if (s == HALUtil.NO_AVAILABLE_RESOURCES)
|
||||
throw new RuntimeException(message);
|
||||
else
|
||||
throw new RuntimeException("Unknown error. Code: " + s + ". " + message);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,12 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
public class I2CJNI extends JNIWrapper {
|
||||
public static native void i2CInitialize(byte port, IntBuffer status);
|
||||
public static native byte i2CTransaction(byte port, byte address, ByteBuffer dataToSend, byte sendSize, ByteBuffer dataReceived, byte receiveSize);
|
||||
public static native byte i2CWrite(byte port, byte address, ByteBuffer dataToSend, byte sendSize);
|
||||
public static native byte i2CRead(byte port, byte address, ByteBuffer dataRecieved, byte receiveSize);
|
||||
public static native void i2CClose(byte port);
|
||||
}
|
||||
@@ -0,0 +1,19 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class InterruptJNI extends JNIWrapper {
|
||||
public interface InterruptHandlerFunction {
|
||||
void apply(int interruptAssertedMask, ByteBuffer param);
|
||||
};
|
||||
public static native ByteBuffer initializeInterrupts(int interruptIndex, byte watcher, IntBuffer status);
|
||||
public static native void cleanInterrupts(ByteBuffer interrupt_pointer, IntBuffer status);
|
||||
public static native void waitForInterrupt(ByteBuffer interrupt_pointer, double timeout, IntBuffer status);
|
||||
public static native void enableInterrupts(ByteBuffer interrupt_pointer, IntBuffer status);
|
||||
public static native void disableInterrupts(ByteBuffer interrupt_pointer, IntBuffer status);
|
||||
public static native double readInterruptTimestamp(ByteBuffer interrupt_pointer, IntBuffer status);
|
||||
public static native void requestInterrupts(ByteBuffer interrupt_pointer, byte routing_module, int routing_pin, byte routing_analog_trigger, IntBuffer status);
|
||||
public static native void attachInterruptHandler(ByteBuffer interrupt_pointer, InterruptHandlerFunction handler, ByteBuffer param, IntBuffer status);
|
||||
public static native void setInterruptUpSourceEdge(ByteBuffer interrupt_pointer, byte risingEdge, byte fallingEdge, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,63 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.io.File;
|
||||
import java.io.InputStream;
|
||||
import java.io.OutputStream;
|
||||
import java.io.FileOutputStream;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
//
|
||||
// base class for all JNI wrappers
|
||||
//
|
||||
public class JNIWrapper
|
||||
{
|
||||
static boolean libraryLoaded = false;
|
||||
static File jniLibrary = null;
|
||||
static
|
||||
{
|
||||
try
|
||||
{
|
||||
if( !libraryLoaded )
|
||||
{
|
||||
// create temporary file
|
||||
jniLibrary = File.createTempFile("libwpilibJavaJNI", ".so");
|
||||
// flag for delete on exit
|
||||
jniLibrary.deleteOnExit();
|
||||
|
||||
byte [] buffer = new byte[1024];
|
||||
|
||||
int readBytes;
|
||||
|
||||
InputStream is = JNIWrapper.class.getResourceAsStream("/linux-arm/libwpilibJavaJNI.so");
|
||||
|
||||
OutputStream os = new FileOutputStream(jniLibrary);
|
||||
|
||||
try
|
||||
{
|
||||
while((readBytes = is.read(buffer)) != -1 )
|
||||
{
|
||||
os.write(buffer, 0, readBytes);
|
||||
}
|
||||
|
||||
}
|
||||
finally
|
||||
{
|
||||
os.close();
|
||||
is.close();
|
||||
}
|
||||
|
||||
|
||||
libraryLoaded = true;
|
||||
}
|
||||
|
||||
System.load(jniLibrary.getAbsolutePath());
|
||||
}
|
||||
catch( Exception ex )
|
||||
{
|
||||
ex.printStackTrace();
|
||||
System.exit(1);
|
||||
}
|
||||
}
|
||||
public static native ByteBuffer getPortWithModule(byte module, byte pin);
|
||||
public static native ByteBuffer getPort(byte pin);
|
||||
}
|
||||
@@ -0,0 +1,10 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
public class PDPJNI extends JNIWrapper {
|
||||
public static native double getPDPTemperature(IntBuffer status);
|
||||
public static native double getPDPVoltage(IntBuffer status);
|
||||
public static native double getPDPChannelCurrent(byte channel, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,23 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
import edu.wpi.first.wpilibj.SensorBase;
|
||||
|
||||
|
||||
public class PWMJNI extends DIOJNI {
|
||||
public static native void setPWM(ByteBuffer digital_port_pointer, short value, IntBuffer status);
|
||||
public static native short getPWM(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
public static native void setPWMPeriodScale(ByteBuffer digital_port_pointer, int squelchMask, IntBuffer status);
|
||||
public static native ByteBuffer allocatePWM(IntBuffer status);
|
||||
public static native ByteBuffer allocatePWMWithModule(byte module, IntBuffer status);
|
||||
public static native void freePWM(ByteBuffer pwmGenerator, IntBuffer status);
|
||||
public static native void freePWMWithModule(byte module, ByteBuffer pwmGenerator, IntBuffer status);
|
||||
public static native void setPWMRate(double rate, IntBuffer status);
|
||||
public static native void setPWMRateWithModule(byte module, double rate, IntBuffer status);
|
||||
public static native void setPWMDutyCycle(ByteBuffer pwmGenerator, double dutyCycle, IntBuffer status);
|
||||
public static native void setPWMDutyCycleWithModule(byte module, ByteBuffer pwmGenerator, double dutyCycle, IntBuffer status);
|
||||
public static native void setPWMOutputChannel(ByteBuffer pwmGenerator, int pin, IntBuffer status);
|
||||
public static native void setPWMOutputChannelWithModule(byte module, ByteBuffer pwmGenerator, int pin, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,11 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
public class RelayJNI extends DIOJNI {
|
||||
public static native void setRelayForward(ByteBuffer digital_port_pointer, byte on, IntBuffer status);
|
||||
public static native void setRelayReverse(ByteBuffer digital_port_pointer, byte on, IntBuffer status);
|
||||
public static native byte getRelayForward(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
public static native byte getRelayReverse(ByteBuffer digital_port_pointer, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.IntBuffer;
|
||||
|
||||
public class SPIJNI extends JNIWrapper {
|
||||
public static native void spiInitialize(byte port, IntBuffer status);
|
||||
public static native int spiTransaction(byte port, ByteBuffer dataToSend, ByteBuffer dataReceived, byte size);
|
||||
public static native int spiWrite(byte port, ByteBuffer dataToSend, byte sendSize);
|
||||
public static native int spiRead(byte port, ByteBuffer dataReceived, byte size);
|
||||
public static native void spiClose(byte port);
|
||||
public static native void spiSetSpeed(byte port, int speed);
|
||||
public static native void spiSetBitsPerWord(byte port, byte bpw);
|
||||
public static native void spiSetOpts(byte port, int msb_first, int sample_on_trailing, int clk_idle_high);
|
||||
public static native void spiSetChipSelectActiveHigh(byte port, IntBuffer status);
|
||||
public static native void spiSetChipSelectActiveLow(byte port, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,10 @@
|
||||
package edu.wpi.first.wpilibj.hal;
|
||||
import java.nio.IntBuffer;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
public class SolenoidJNI extends JNIWrapper {
|
||||
public static native ByteBuffer initializeSolenoidPort(ByteBuffer portPointer, IntBuffer status);
|
||||
public static native ByteBuffer getPortWithModule(byte module, byte channel);
|
||||
public static native void setSolenoid(ByteBuffer port, byte on, IntBuffer status);
|
||||
public static native byte getSolenoid(ByteBuffer port, IntBuffer status);
|
||||
}
|
||||
@@ -0,0 +1,180 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Pointer;
|
||||
import edu.wpi.first.wpilibj.util.SortedVector;
|
||||
|
||||
/**
|
||||
* An image where each pixel is treated as either on or off.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class BinaryImage extends MonoImage {
|
||||
private int numParticles = -1;
|
||||
|
||||
BinaryImage() throws NIVisionException {
|
||||
}
|
||||
|
||||
BinaryImage(BinaryImage sourceImage) {
|
||||
super(sourceImage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the number of particles.
|
||||
* @return The number of particles
|
||||
*/
|
||||
public int getNumberParticles () throws NIVisionException {
|
||||
if (numParticles < 0)
|
||||
numParticles = NIVision.countParticles(image);
|
||||
return numParticles;
|
||||
}
|
||||
|
||||
|
||||
private class ParticleSizeReport {
|
||||
final int index;
|
||||
final double size;
|
||||
public ParticleSizeReport(int index) throws NIVisionException {
|
||||
if ((!(index < BinaryImage.this.getNumberParticles())) || index < 0)
|
||||
throw new IndexOutOfBoundsException();
|
||||
this.index = index;
|
||||
size = ParticleAnalysisReport.getParticleToImagePercent(BinaryImage.this, index);
|
||||
}
|
||||
public ParticleAnalysisReport getParticleAnalysisReport () throws NIVisionException {
|
||||
return new ParticleAnalysisReport(BinaryImage.this, index);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a particle analysis report for the particle at the given index.
|
||||
* @param index The index of the particle to report on.
|
||||
* @return The ParticleAnalysisReport for the particle at the given index
|
||||
*/
|
||||
public ParticleAnalysisReport getParticleAnalysisReport(int index) throws NIVisionException {
|
||||
if (!(index < getNumberParticles())) throw new IndexOutOfBoundsException();
|
||||
return new ParticleAnalysisReport(this, index);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets all the particle analysis reports ordered from largest area to smallest.
|
||||
* @param size The number of particles to return
|
||||
* @return An array of ParticleReports from largest area to smallest
|
||||
*/
|
||||
public ParticleAnalysisReport[] getOrderedParticleAnalysisReports(int size) throws NIVisionException {
|
||||
if (size > getNumberParticles())
|
||||
size = getNumberParticles();
|
||||
ParticleSizeReport[] reports = new ParticleSizeReport[size];
|
||||
SortedVector sorter = new SortedVector(new SortedVector.Comparator() {
|
||||
public int compare(Object object1, Object object2) {
|
||||
ParticleSizeReport p1 = (ParticleSizeReport)object1;
|
||||
ParticleSizeReport p2 = (ParticleSizeReport)object2;
|
||||
if (p1.size < p2.size)
|
||||
return -1;
|
||||
else if (p1.size > p2.size)
|
||||
return 1;
|
||||
return 0;
|
||||
}
|
||||
});
|
||||
for (int i = 0; i < getNumberParticles(); i++)
|
||||
sorter.addElement(new ParticleSizeReport(i));
|
||||
sorter.setSize(size);
|
||||
sorter.copyInto(reports);
|
||||
ParticleAnalysisReport[] finalReports = new ParticleAnalysisReport[reports.length];
|
||||
for (int i = 0; i < finalReports.length; i++)
|
||||
finalReports[i] = reports[i].getParticleAnalysisReport();
|
||||
return finalReports;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets all the particle analysis reports ordered from largest area to smallest.
|
||||
* @return An array of ParticleReports from largest are to smallest
|
||||
*/
|
||||
public ParticleAnalysisReport[] getOrderedParticleAnalysisReports() throws NIVisionException {
|
||||
return getOrderedParticleAnalysisReports(getNumberParticles());
|
||||
}
|
||||
|
||||
|
||||
public void write(String fileName) throws NIVisionException {
|
||||
Pointer colorTable = new Pointer(1024);
|
||||
//Black Background
|
||||
colorTable.setByte(0, (byte)0); //B
|
||||
colorTable.setByte(1, (byte)0); //G
|
||||
colorTable.setByte(2, (byte)0); //R
|
||||
colorTable.setByte(3, (byte)0); //Alpha
|
||||
//Red Particles:
|
||||
colorTable.setByte(4, (byte)0); //B
|
||||
colorTable.setByte(5, (byte)0); //G
|
||||
colorTable.setByte(6, (byte)255); //R
|
||||
colorTable.setByte(7, (byte)0); //Alpha
|
||||
try {
|
||||
NIVision.writeFile(image, fileName, colorTable);
|
||||
} finally {
|
||||
colorTable.free();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* removeSmallObjects filters particles based on their size.
|
||||
* The algorithm erodes the image a specified number of times and keeps the
|
||||
* particles from the original image that remain in the eroded image.
|
||||
* @param connectivity8 true to use connectivity-8 or false for connectivity-4 to determine
|
||||
* whether particles are touching. For more information about connectivity, see Chapter 9,
|
||||
* Binary Morphology, in the NI Vision Concepts manual.
|
||||
* @param erosions the number of erosions to perform
|
||||
* @return a BinaryImage after applying the filter
|
||||
* @throws NIVisionException
|
||||
*/
|
||||
public BinaryImage removeSmallObjects(boolean connectivity8, int erosions) throws NIVisionException {
|
||||
BinaryImage result = new BinaryImage();
|
||||
try {
|
||||
NIVision.sizeFilter(result.image, image, connectivity8, erosions, true);
|
||||
} catch (NIVisionException ex) {
|
||||
result.free();
|
||||
throw ex;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* removeLargeObjects filters particles based on their size.
|
||||
* The algorithm erodes the image a specified number of times and discards the
|
||||
* particles from the original image that remain in the eroded image.
|
||||
* @param connectivity8 true to use connectivity-8 or false for connectivity-4 to determine
|
||||
* whether particles are touching. For more information about connectivity, see Chapter 9,
|
||||
* Binary Morphology, in the NI Vision Concepts manual.
|
||||
* @param erosions the number of erosions to perform
|
||||
* @return a BinaryImage after applying the filter
|
||||
* @throws NIVisionException
|
||||
*/
|
||||
public BinaryImage removeLargeObjects(boolean connectivity8, int erosions) throws NIVisionException {
|
||||
BinaryImage result = new BinaryImage();
|
||||
try {
|
||||
NIVision.sizeFilter(result.image, image, connectivity8, erosions, false);
|
||||
} catch (NIVisionException ex) {
|
||||
result.free();
|
||||
throw ex;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
public BinaryImage convexHull(boolean connectivity8) throws NIVisionException {
|
||||
BinaryImage result = new BinaryImage();
|
||||
try {
|
||||
NIVision.convexHull(result.image, image, connectivity8 ? 1 : 0);
|
||||
} catch (NIVisionException ex) {
|
||||
result.free();
|
||||
throw ex;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
public BinaryImage particleFilter(CriteriaCollection criteria) throws NIVisionException {
|
||||
BinaryImage result = new BinaryImage();
|
||||
NIVision.particleFilter(result.image, image, criteria);
|
||||
return result;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,401 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
/**
|
||||
* A class representing a color image.
|
||||
* @author dtjones
|
||||
*/
|
||||
public abstract class ColorImage extends Image {
|
||||
|
||||
ColorImage(NIVision.ImageType type) throws NIVisionException {
|
||||
super(type);
|
||||
}
|
||||
|
||||
ColorImage(ColorImage sourceImage) {
|
||||
super(sourceImage);
|
||||
}
|
||||
|
||||
private BinaryImage threshold(NIVision.ColorMode colorMode,
|
||||
int low1, int high1,
|
||||
int low2, int high2,
|
||||
int low3, int high3) throws NIVisionException {
|
||||
BinaryImage res = new BinaryImage();
|
||||
NIVision.Range range1 = new NIVision.Range(low1, high1);
|
||||
NIVision.Range range2 = new NIVision.Range(low2, high2);
|
||||
NIVision.Range range3 = new NIVision.Range(low3, high3);
|
||||
try {
|
||||
NIVision.colorThreshold(res.image, image, colorMode, range1.getPointer(), range2.getPointer(), range3.getPointer());
|
||||
} catch (NIVisionException e) {
|
||||
res.free();
|
||||
throw e;
|
||||
} finally {
|
||||
range1.free();
|
||||
range2.free();
|
||||
range3.free();
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
/**
|
||||
* Return a mask of the areas of the image that fall within the given ranges for color values
|
||||
* @param redLow The lower red limit.
|
||||
* @param redHigh The upper red limit.
|
||||
* @param greenLow The lower green limit.
|
||||
* @param greenHigh The upper green limit.
|
||||
* @param blueLow The lower blue limit.
|
||||
* @param blueHigh The upper blue limit.
|
||||
* @return A BinaryImage masking the areas which match the given thresholds.
|
||||
*/
|
||||
public BinaryImage thresholdRGB(int redLow, int redHigh, int greenLow, int greenHigh, int blueLow, int blueHigh) throws NIVisionException {
|
||||
return threshold(NIVision.ColorMode.IMAQ_RGB, redLow, redHigh, greenLow, greenHigh, blueLow, blueHigh);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return a mask of the areas of the image that fall within the given ranges for color values
|
||||
* @param hueLow The lower hue limit.
|
||||
* @param hueHigh The upper hue limit.
|
||||
* @param saturationLow The lower saturation limit.
|
||||
* @param saturationHigh The upper saturation limit.
|
||||
* @param luminenceLow The lower luminence limit.
|
||||
* @param luminenceHigh The upper luminence limit.
|
||||
* @return A BinaryImage masking the areas which match the given thresholds.
|
||||
*/
|
||||
public BinaryImage thresholdHSL(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int luminenceLow, int luminenceHigh) throws NIVisionException {
|
||||
return threshold(NIVision.ColorMode.IMAQ_HSL, hueLow, hueHigh, saturationLow, saturationHigh, luminenceLow, luminenceHigh);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return a mask of the areas of the image that fall within the given ranges for color values
|
||||
* @param hueLow The lower hue limit.
|
||||
* @param hueHigh The upper hue limit.
|
||||
* @param saturationLow The lower saturation limit.
|
||||
* @param saturationHigh The upper saturation limit.
|
||||
* @param valueHigh The lower value limit.
|
||||
* @param valueLow The upper value limit.
|
||||
* @return A BinaryImage masking the areas which match the given thresholds.
|
||||
*/
|
||||
public BinaryImage thresholdHSV(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int valueLow, int valueHigh) throws NIVisionException {
|
||||
return threshold(NIVision.ColorMode.IMAQ_HSV, hueLow, hueHigh, saturationLow, saturationHigh, valueLow, valueHigh);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return a mask of the areas of the image that fall within the given ranges for color values
|
||||
* @param hueLow The lower hue limit.
|
||||
* @param hueHigh The upper hue limit.
|
||||
* @param saturationLow The lower saturation limit.
|
||||
* @param saturationHigh The upper saturation limit.
|
||||
* @param intansityLow The lower intensity limit.
|
||||
* @param intensityHigh The upper intensity limit.
|
||||
* @return A BinaryImage masking the areas which match the given thresholds.
|
||||
*/
|
||||
public BinaryImage thresholdHSI(int hueLow, int hueHigh, int saturationLow, int saturationHigh, int intansityLow, int intensityHigh) throws NIVisionException {
|
||||
return threshold(NIVision.ColorMode.IMAQ_HSI, hueLow, hueHigh, saturationLow, saturationHigh, intansityLow, intensityHigh);
|
||||
}
|
||||
|
||||
MonoImage extractFirstColorPlane(NIVision.ColorMode mode) throws NIVisionException {
|
||||
MonoImage result = new MonoImage();
|
||||
try {
|
||||
NIVision.extractColorPlanes(image, mode, result.image, null, null);
|
||||
} catch (NIVisionException e) {
|
||||
result.free();
|
||||
throw e;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MonoImage extractSecondColorPlane(NIVision.ColorMode mode) throws NIVisionException {
|
||||
MonoImage result = new MonoImage();
|
||||
try {
|
||||
NIVision.extractColorPlanes(image, mode, null, result.image, null);
|
||||
} catch (NIVisionException e) {
|
||||
result.free();
|
||||
throw e;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
MonoImage extractThirdColorPlane(NIVision.ColorMode mode) throws NIVisionException {
|
||||
MonoImage result = new MonoImage();
|
||||
try {
|
||||
NIVision.extractColorPlanes(image, mode, null, null, result.image);
|
||||
} catch (NIVisionException e) {
|
||||
result.free();
|
||||
throw e;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the red color plane from the image when represented in RGB color space.
|
||||
* @return The red color plane from the image.
|
||||
*/
|
||||
public MonoImage getRedPlane() throws NIVisionException {
|
||||
return extractFirstColorPlane(NIVision.ColorMode.IMAQ_RGB);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the green color plane from the image when represented in RGB color space.
|
||||
* @return The green color plane from the image.
|
||||
*/
|
||||
public MonoImage getGreenPlane() throws NIVisionException {
|
||||
return extractSecondColorPlane(NIVision.ColorMode.IMAQ_RGB);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the blue color plane from the image when represented in RGB color space.
|
||||
* @return The blue color plane from the image.
|
||||
*/
|
||||
public MonoImage getBluePlane() throws NIVisionException {
|
||||
return extractThirdColorPlane(NIVision.ColorMode.IMAQ_RGB);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the hue color plane from the image when represented in HSL color space.
|
||||
* @return The hue color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSLHuePlane() throws NIVisionException {
|
||||
return extractFirstColorPlane(NIVision.ColorMode.IMAQ_HSL);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the hue color plane from the image when represented in HSV color space.
|
||||
* @return The hue color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSVHuePlane() throws NIVisionException {
|
||||
return extractFirstColorPlane(NIVision.ColorMode.IMAQ_HSV);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the hue color plane from the image when represented in HSI color space.
|
||||
* @return The hue color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSIHuePlane() throws NIVisionException {
|
||||
return extractFirstColorPlane(NIVision.ColorMode.IMAQ_HSI);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the saturation color plane from the image when represented in HSL color space.
|
||||
* @return The saturation color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSLSaturationPlane() throws NIVisionException {
|
||||
return extractSecondColorPlane(NIVision.ColorMode.IMAQ_HSL);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the saturation color plane from the image when represented in HSV color space.
|
||||
* @return The saturation color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSVSaturationPlane() throws NIVisionException {
|
||||
return extractSecondColorPlane(NIVision.ColorMode.IMAQ_HSV);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the saturation color plane from the image when represented in HSI color space.
|
||||
* @return The saturation color plane from the image.
|
||||
*/
|
||||
public MonoImage getHSISaturationPlane() throws NIVisionException {
|
||||
return extractSecondColorPlane(NIVision.ColorMode.IMAQ_HSI);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the luminance color plane from the image when represented in HSL color space.
|
||||
* @return The luminance color plane from the image.
|
||||
*/
|
||||
public MonoImage getLuminancePlane() throws NIVisionException {
|
||||
return extractThirdColorPlane(NIVision.ColorMode.IMAQ_HSL);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value color plane from the image when represented in HSV color space.
|
||||
* @return The value color plane from the image.
|
||||
*/
|
||||
public MonoImage getValuePlane() throws NIVisionException {
|
||||
return extractThirdColorPlane(NIVision.ColorMode.IMAQ_HSV);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the intensity color plane from the image when represented in HSI color space.
|
||||
* @return The intensity color plane from the image.
|
||||
*/
|
||||
public MonoImage getIntensityPlane() throws NIVisionException {
|
||||
return extractThirdColorPlane(NIVision.ColorMode.IMAQ_HSI);
|
||||
}
|
||||
|
||||
ColorImage replaceFirstColorPlane(NIVision.ColorMode mode, MonoImage plane) throws NIVisionException {
|
||||
NIVision.replaceColorPlanes(image, image, mode, plane.image, null, null);
|
||||
return this;
|
||||
}
|
||||
|
||||
ColorImage replaceSecondColorPlane(NIVision.ColorMode mode, MonoImage plane) throws NIVisionException {
|
||||
NIVision.replaceColorPlanes(image, image, mode, null, plane.image, null);
|
||||
return this;
|
||||
}
|
||||
|
||||
ColorImage replaceThirdColorPlane(NIVision.ColorMode mode, MonoImage plane) throws NIVisionException {
|
||||
NIVision.replaceColorPlanes(image, image, mode, null, null, plane.image);
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the red color plane from the image when represented in RGB color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceRedPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceFirstColorPlane(NIVision.ColorMode.IMAQ_RGB, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the green color plane from the image when represented in RGB color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceGreenPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceSecondColorPlane(NIVision.ColorMode.IMAQ_RGB, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the blue color plane from the image when represented in RGB color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceBluePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceThirdColorPlane(NIVision.ColorMode.IMAQ_RGB, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the hue color plane from the image when represented in HSL color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSLHuePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceFirstColorPlane(NIVision.ColorMode.IMAQ_HSL, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the hue color plane from the image when represented in HSV color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSVHuePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceFirstColorPlane(NIVision.ColorMode.IMAQ_HSV, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the hue color plane from the image when represented in HSI color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSIHuePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceFirstColorPlane(NIVision.ColorMode.IMAQ_HSI, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the saturation color plane from the image when represented in HSL color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSLSaturationPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceSecondColorPlane(NIVision.ColorMode.IMAQ_HSL, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the saturation color plane from the image when represented in HSV color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSVSaturationPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceSecondColorPlane(NIVision.ColorMode.IMAQ_HSV, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the saturation color plane from the image when represented in HSI color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceHSISaturationPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceSecondColorPlane(NIVision.ColorMode.IMAQ_HSI, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the luminance color plane from the image when represented in HSL color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceLuminancePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceThirdColorPlane(NIVision.ColorMode.IMAQ_HSL, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the value color plane from the image when represented in HSV color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceValuePlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceThirdColorPlane(NIVision.ColorMode.IMAQ_HSV, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the intensity color plane from the image when represented in HSI color space.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @param plane The MonoImage representing the new color plane.
|
||||
* @return The resulting image.
|
||||
*/
|
||||
public ColorImage replaceIntensityPlane(MonoImage plane) throws NIVisionException {
|
||||
return replaceThirdColorPlane(NIVision.ColorMode.IMAQ_HSI, plane);
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculates the histogram of each plane of a color image and redistributes
|
||||
* pixel values across the desired range while maintaining pixel value
|
||||
* groupings.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @return The modified image.
|
||||
*/
|
||||
public ColorImage colorEqualize() throws NIVisionException {
|
||||
NIVision.colorEqualize(image, image, true);
|
||||
return this;
|
||||
}
|
||||
|
||||
/**
|
||||
* Calculates the histogram of each plane of a color image and redistributes
|
||||
* pixel values across the desired range while maintaining pixel value
|
||||
* groupings for the Luminance plane only.
|
||||
* This does not create a new image, but modifies this one instead. Create a
|
||||
* copy before hand if you need to continue using the original.
|
||||
* @return The modified image.
|
||||
*/
|
||||
public ColorImage luminanceEqualize() throws NIVisionException {
|
||||
NIVision.colorEqualize(image, image, false);
|
||||
return this;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,49 @@
|
||||
/*
|
||||
* To change this template, choose Tools | Templates
|
||||
* and open the template in the editor.
|
||||
*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Pointer;
|
||||
import edu.wpi.first.wpilibj.image.NIVision.MeasurementType;
|
||||
import java.util.Vector;
|
||||
|
||||
class ParticleFilterCriteria {
|
||||
MeasurementType type;
|
||||
float lower;
|
||||
float upper;
|
||||
boolean outsideRange;
|
||||
|
||||
ParticleFilterCriteria(MeasurementType type, float lower, float upper, boolean outsideRange) {
|
||||
this.type = type;
|
||||
this.lower = lower;
|
||||
this.upper = upper;
|
||||
this.outsideRange = outsideRange;
|
||||
}
|
||||
}
|
||||
|
||||
public class CriteriaCollection {
|
||||
Vector criteria = new Vector();
|
||||
|
||||
public void addCriteria(MeasurementType type, float lower, float upper, boolean outsideRange) {
|
||||
criteria.addElement(new ParticleFilterCriteria(type, lower, upper, outsideRange));
|
||||
}
|
||||
|
||||
public int getNumberOfCriteria() {
|
||||
return criteria.size();
|
||||
}
|
||||
|
||||
public Pointer getCriteriaArray() {
|
||||
Pointer p = new Pointer(criteria.size() * 5 * 4); // 5 elements each 4 bytes
|
||||
for (int i = 0; i < criteria.size(); i++) {
|
||||
ParticleFilterCriteria pfc = (ParticleFilterCriteria) criteria.elementAt(i);
|
||||
p.setInt(i * 20, pfc.type.value);
|
||||
p.setFloat(i * 20 + 4, pfc.lower);
|
||||
p.setFloat(i * 20 + 8, pfc.upper);
|
||||
p.setInt(i * 20 + 12, 0); // always use pixel measurements for now
|
||||
p.setInt(i * 20 + 16, pfc.outsideRange ? 1 : 0);
|
||||
}
|
||||
return p;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,68 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class CurveOptions extends Structure {
|
||||
|
||||
int m_extractionMode;
|
||||
int m_threshold;
|
||||
int m_filterSize;
|
||||
int m_minLength;
|
||||
int m_rowStepSize;
|
||||
int m_columnStepSize;
|
||||
int m_maxEndPointGap;
|
||||
int m_onlyClosed;
|
||||
int m_subPixelAccuracy;
|
||||
|
||||
public CurveOptions(int m_extractionMode, int m_threshold, int m_filterSize, int m_minLength, int m_rowStepSize, int m_columnStepSize, int m_maxEndPointGap, int m_onlyClosed, int m_subPixelAccuracy) {
|
||||
this.m_extractionMode = m_extractionMode;
|
||||
this.m_threshold = m_threshold;
|
||||
this.m_filterSize = m_filterSize;
|
||||
this.m_minLength = m_minLength;
|
||||
this.m_rowStepSize = m_rowStepSize;
|
||||
this.m_columnStepSize = m_columnStepSize;
|
||||
this.m_maxEndPointGap = m_maxEndPointGap;
|
||||
this.m_onlyClosed = m_onlyClosed;
|
||||
this.m_subPixelAccuracy = m_subPixelAccuracy;
|
||||
allocateMemory();
|
||||
write();
|
||||
}
|
||||
|
||||
|
||||
|
||||
public void read() {
|
||||
}
|
||||
|
||||
public void write() {
|
||||
backingNativeMemory.setInt(0, m_extractionMode);
|
||||
backingNativeMemory.setInt(4, m_threshold);
|
||||
backingNativeMemory.setInt(8, m_filterSize);
|
||||
backingNativeMemory.setInt(12, m_minLength);
|
||||
backingNativeMemory.setInt(16, m_rowStepSize);
|
||||
backingNativeMemory.setInt(20, m_columnStepSize);
|
||||
backingNativeMemory.setInt(24, m_maxEndPointGap);
|
||||
backingNativeMemory.setInt(28, m_onlyClosed);
|
||||
backingNativeMemory.setInt(32, m_subPixelAccuracy);
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return 36;
|
||||
}
|
||||
|
||||
public void free() {
|
||||
release();
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,57 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class EllipseDescriptor extends Structure {
|
||||
|
||||
double m_minMajorRadius;
|
||||
double m_maxMajorRadius;
|
||||
double m_minMinorRadius;
|
||||
double m_maxMinorRadius;
|
||||
|
||||
public EllipseDescriptor(double m_minMajorRadius, double m_maxMajorRadius, double m_minMinorRadius, double m_maxMinorRadius) {
|
||||
this.m_minMajorRadius = m_minMajorRadius;
|
||||
this.m_maxMajorRadius = m_maxMajorRadius;
|
||||
this.m_minMinorRadius = m_minMinorRadius;
|
||||
this.m_maxMinorRadius = m_maxMinorRadius;
|
||||
allocateMemory();
|
||||
write();
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the c memory associated with this object.
|
||||
*/
|
||||
public void free() {
|
||||
release();
|
||||
}
|
||||
|
||||
public void read() {
|
||||
m_minMajorRadius = backingNativeMemory.getDouble(0);
|
||||
m_maxMajorRadius = backingNativeMemory.getDouble(8);
|
||||
m_minMinorRadius = backingNativeMemory.getDouble(16);
|
||||
m_maxMinorRadius = backingNativeMemory.getDouble(24);
|
||||
}
|
||||
|
||||
public void write() {
|
||||
backingNativeMemory.setDouble(0, m_minMajorRadius);
|
||||
backingNativeMemory.setDouble(8, m_maxMajorRadius);
|
||||
backingNativeMemory.setDouble(16, m_minMinorRadius);
|
||||
backingNativeMemory.setDouble(24, m_maxMinorRadius);
|
||||
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return 32;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,74 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Pointer;
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class EllipseMatch {
|
||||
|
||||
static final int ellipseMatchSize = 40;
|
||||
public double m_xPos;
|
||||
public double m_yPos;
|
||||
public double m_rotation;
|
||||
public double m_majorRadius;
|
||||
public double m_minorRadius;
|
||||
public double m_score;
|
||||
|
||||
private class EllipseMatchStructure extends Structure {
|
||||
|
||||
public EllipseMatchStructure(int address) {
|
||||
useMemory(new Pointer(address, ellipseMatchSize));
|
||||
read();
|
||||
}
|
||||
|
||||
public void read() {
|
||||
m_xPos = backingNativeMemory.getFloat(0);
|
||||
m_yPos = backingNativeMemory.getFloat(4);
|
||||
m_rotation = backingNativeMemory.getDouble(8);
|
||||
m_majorRadius = backingNativeMemory.getDouble(16);
|
||||
m_minorRadius = backingNativeMemory.getDouble(24);
|
||||
m_score = backingNativeMemory.getDouble(32);
|
||||
|
||||
}
|
||||
|
||||
public void write() {
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return ellipseMatchSize;
|
||||
}
|
||||
}
|
||||
|
||||
EllipseMatch(int address) {
|
||||
new EllipseMatchStructure(address);
|
||||
}
|
||||
|
||||
public String toString() {
|
||||
return "Ellipse Match:\n" +
|
||||
" Pos x: " + m_xPos + " y: " + m_yPos + "\n" +
|
||||
" Radius major: " + m_majorRadius + " minor: " + m_minorRadius + "\n" +
|
||||
" Rotation: " + m_rotation + " Score: " + m_score + "\n";
|
||||
}
|
||||
|
||||
protected static EllipseMatch[] getMatchesFromMemory(int address, int number) {
|
||||
if (address == 0) {
|
||||
return new EllipseMatch[0];
|
||||
}
|
||||
|
||||
EllipseMatch[] toReturn = new EllipseMatch[number];
|
||||
for (int i = 0; i < number; i++) {
|
||||
toReturn[i] = new EllipseMatch(address + i * ellipseMatchSize);
|
||||
}
|
||||
return toReturn;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,34 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
/**
|
||||
* A color image represented in HSL color space at 3 bytes per pixel.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class HSLImage extends ColorImage {
|
||||
|
||||
/**
|
||||
* Create a new 0x0 image.
|
||||
*/
|
||||
public HSLImage() throws NIVisionException {
|
||||
super(NIVision.ImageType.imaqImageHSL);
|
||||
}
|
||||
|
||||
HSLImage(HSLImage sourceImage) {
|
||||
super(sourceImage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new image by loading a file.
|
||||
* @param fileName The path of the file to load.
|
||||
*/
|
||||
public HSLImage(String fileName) throws NIVisionException {
|
||||
super(NIVision.ImageType.imaqImageHSL);
|
||||
NIVision.readFile(image, fileName);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,76 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Pointer;
|
||||
|
||||
/**
|
||||
* Class representing a generic image.
|
||||
* @author dtjones
|
||||
*/
|
||||
public abstract class Image {
|
||||
|
||||
/**
|
||||
* Pointer to the image memory
|
||||
*/
|
||||
public final Pointer image;
|
||||
static final int DEFAULT_BORDER_SIZE = 3;
|
||||
|
||||
Image(NIVision.ImageType type) throws NIVisionException {
|
||||
image = NIVision.imaqCreateImage(type, DEFAULT_BORDER_SIZE);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a new image pointing to the same data as the source image. The
|
||||
* imgae data is not copied, it is just referenced by both objects. Freeing
|
||||
* one will free both.
|
||||
* @param sourceImage The image to reference
|
||||
*/
|
||||
Image(Image sourceImage) {
|
||||
image = sourceImage.image;
|
||||
}
|
||||
|
||||
/**
|
||||
* Write the image to a file.
|
||||
*
|
||||
* Supported extensions:
|
||||
* .aipd or .apd AIPD
|
||||
* .bmp BMP
|
||||
* .jpg or .jpeg JPEG
|
||||
* .jp2 JPEG2000
|
||||
* .png PNG
|
||||
* .tif or .tiff TIFF
|
||||
*
|
||||
* @param fileName The path to write the image to.
|
||||
*/
|
||||
public void write(String fileName) throws NIVisionException {
|
||||
NIVision.writeFile(image, fileName);
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the memory associated with an image.
|
||||
*/
|
||||
public void free() throws NIVisionException {
|
||||
NIVision.dispose(image);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the height of the image in pixels.
|
||||
* @return The height of the image.
|
||||
*/
|
||||
public int getHeight() throws NIVisionException {
|
||||
return NIVision.getHeight(image);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the width of the image in pixels.
|
||||
* @return The width of the image.
|
||||
*/
|
||||
public int getWidth() throws NIVisionException {
|
||||
return NIVision.getWidth(image);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,121 @@
|
||||
/*
|
||||
* To change this template, choose Tools | Templates
|
||||
* and open the template in the editor.
|
||||
*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Pointer;
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author koconnor
|
||||
*/
|
||||
public class LinearAverages {
|
||||
|
||||
Pointer columnAveragesPtr;
|
||||
int columnCount;
|
||||
float[] columnAverages;
|
||||
Pointer rowAveragesPtr;
|
||||
int rowCount;
|
||||
float[] rowAverages;
|
||||
Pointer risingDiagAveragesPtr;
|
||||
int risingDiagCount;
|
||||
float[] risingDiagAverages;
|
||||
Pointer fallingDiagAveragesPtr;
|
||||
int fallingDiagCount;
|
||||
float[] fallingDiagAverages;
|
||||
|
||||
public static class LinearAveragesMode {
|
||||
|
||||
public final int value;
|
||||
static final int IMAQ_COLUMN_AVERAGES_val = 1;
|
||||
static final int IMAQ_ROW_AVERAGES_val = 2;
|
||||
static final int IMAQ_RISING_DIAG_AVERAGES_val = 4;
|
||||
static final int IMAQ_FALLING_DIAG_AVERAGES_val = 8;
|
||||
static final int IMAQ_ALL_LINEAR_AVERAGES_val = 15;
|
||||
public static final LinearAveragesMode IMAQ_COLUMN_AVERAGES = new LinearAveragesMode(IMAQ_COLUMN_AVERAGES_val);
|
||||
public static final LinearAveragesMode IMAQ_ROW_AVERAGES = new LinearAveragesMode(IMAQ_ROW_AVERAGES_val);
|
||||
public static final LinearAveragesMode IMAQ_RISING_DIAG_AVERAGES = new LinearAveragesMode(IMAQ_RISING_DIAG_AVERAGES_val);
|
||||
public static final LinearAveragesMode IMAQ_FALLING_DIAG_AVERAGES = new LinearAveragesMode(IMAQ_FALLING_DIAG_AVERAGES_val);
|
||||
public static final LinearAveragesMode IMAQ_ALL_LINEAR_AVERAGES = new LinearAveragesMode(IMAQ_ALL_LINEAR_AVERAGES_val);
|
||||
|
||||
private LinearAveragesMode (int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
|
||||
private class LinearAveragesStruct extends Structure {
|
||||
|
||||
public void read() {
|
||||
columnCount = backingNativeMemory.getInt(4);
|
||||
columnAveragesPtr = backingNativeMemory.getPointer(0, 4*columnCount);
|
||||
columnAverages = new float[columnCount];
|
||||
columnAveragesPtr.getFloats(0, columnAverages, 0, columnCount);
|
||||
rowCount = backingNativeMemory.getInt(12);
|
||||
rowAveragesPtr = backingNativeMemory.getPointer(8, 4*rowCount);
|
||||
rowAverages = new float[rowCount];
|
||||
rowAveragesPtr.getFloats(0, rowAverages, 0, rowCount);
|
||||
risingDiagCount = backingNativeMemory.getInt(20);
|
||||
risingDiagAveragesPtr = backingNativeMemory.getPointer(16, 4*risingDiagCount);
|
||||
risingDiagAverages = new float[risingDiagCount];
|
||||
risingDiagAveragesPtr.getFloats(0, risingDiagAverages, 0, risingDiagCount);
|
||||
fallingDiagCount = backingNativeMemory.getInt(28);
|
||||
fallingDiagAveragesPtr = backingNativeMemory.getPointer(24, 4*fallingDiagCount);
|
||||
fallingDiagAverages = new float[fallingDiagCount];
|
||||
fallingDiagAveragesPtr.getFloats(0, fallingDiagAverages, 0, fallingDiagCount);
|
||||
}
|
||||
|
||||
public void write() {
|
||||
backingNativeMemory.setPointer(0, columnAveragesPtr);
|
||||
backingNativeMemory.setInt(4, columnCount);
|
||||
backingNativeMemory.setPointer(8, rowAveragesPtr);
|
||||
backingNativeMemory.setInt(12, rowCount);
|
||||
backingNativeMemory.setPointer(16, risingDiagAveragesPtr);
|
||||
backingNativeMemory.setInt(20, risingDiagCount);
|
||||
backingNativeMemory.setPointer(24, fallingDiagAveragesPtr);
|
||||
backingNativeMemory.setInt(28, fallingDiagCount);
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return 32;
|
||||
}
|
||||
|
||||
/**
|
||||
* Free the memory used by this range
|
||||
*/
|
||||
public void free() {
|
||||
release();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new range with the specified upper and lower boundaries
|
||||
* @param lower The lower limit
|
||||
* @param upper The upper limit
|
||||
*/
|
||||
public LinearAveragesStruct(int address) {
|
||||
useMemory(new Pointer(address, size()));
|
||||
read();
|
||||
}
|
||||
}
|
||||
|
||||
LinearAverages(int address) {
|
||||
new LinearAveragesStruct(address);
|
||||
}
|
||||
|
||||
public float[] getColumnAverages() {
|
||||
return columnAverages;
|
||||
}
|
||||
|
||||
public float[] getRowAverages() {
|
||||
return rowAverages;
|
||||
}
|
||||
|
||||
public float[] getRisingDiagAverages() {
|
||||
return risingDiagAverages;
|
||||
}
|
||||
|
||||
public float[] getFallingDiagAverages() {
|
||||
return fallingDiagAverages;
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,36 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
/**
|
||||
* A grey scale image represented at a byte per pixel.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class MonoImage extends Image {
|
||||
|
||||
/**
|
||||
* Create a new 0x0 image.
|
||||
*/
|
||||
public MonoImage() throws NIVisionException {
|
||||
super(NIVision.ImageType.imaqImageU8);
|
||||
}
|
||||
|
||||
MonoImage(MonoImage sourceImage) {
|
||||
super(sourceImage);
|
||||
}
|
||||
|
||||
public EllipseMatch[] detectEllipses(EllipseDescriptor ellipseDescriptor,
|
||||
CurveOptions curveOptions, ShapeDetectionOptions shapeDetectionOptions,
|
||||
RegionOfInterest roi) throws NIVisionException {
|
||||
return NIVision.detectEllipses(this, ellipseDescriptor, curveOptions, shapeDetectionOptions, roi);
|
||||
}
|
||||
|
||||
public EllipseMatch[] detectEllipses(EllipseDescriptor ellipseDescriptor)
|
||||
throws NIVisionException {
|
||||
return NIVision.detectEllipses(this, ellipseDescriptor, null, null, null);
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,87 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
/**
|
||||
* Class to store commonly used information about a particle.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class ParticleAnalysisReport {
|
||||
|
||||
/**
|
||||
* The height of the image in pixels.
|
||||
*/
|
||||
public final int imageHeight;
|
||||
/**
|
||||
* The width of the image in pixels.
|
||||
*/
|
||||
public final int imageWidth;
|
||||
/** X-coordinate of the point representing the average position of the
|
||||
* total particle mass, assuming every point in the particle has a constant density */
|
||||
public final int center_mass_x; // MeasurementType: IMAQ_MT_CENTER_OF_MASS_X
|
||||
/** Y-coordinate of the point representing the average position of the
|
||||
* total particle mass, assuming every point in the particle has a constant density */
|
||||
public final int center_mass_y; // MeasurementType: IMAQ_MT_CENTER_OF_MASS_Y
|
||||
/**
|
||||
* Center of mass x value normalized to -1.0 to +1.0 range.
|
||||
*/
|
||||
public final double center_mass_x_normalized;
|
||||
/**
|
||||
* Center of mass y value normalized to -1.0 to +1.0 range.
|
||||
*/
|
||||
public final double center_mass_y_normalized;
|
||||
/** Area of the particle */
|
||||
public final double particleArea; // MeasurementType: IMAQ_MT_AREA
|
||||
/** Bounding Rectangle */
|
||||
public final int boundingRectLeft; // left/top/width/height
|
||||
/** Bounding Rectangle */
|
||||
public final int boundingRectTop;
|
||||
/** Bounding Rectangle */
|
||||
public final int boundingRectWidth;
|
||||
/** Bounding Rectangle */
|
||||
public final int boundingRectHeight;
|
||||
/** Percentage of the particle Area covering the Image Area. */
|
||||
public final double particleToImagePercent; // MeasurementType: IMAQ_MT_AREA_BY_IMAGE_AREA
|
||||
/** Percentage of the particle Area in relation to its Particle and Holes Area */
|
||||
public final double particleQuality; // MeasurementType: IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA
|
||||
|
||||
ParticleAnalysisReport(BinaryImage image, int index) throws NIVisionException {
|
||||
imageHeight = image.getHeight();
|
||||
imageWidth = image.getWidth();
|
||||
center_mass_x = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_CENTER_OF_MASS_X);
|
||||
center_mass_y = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_CENTER_OF_MASS_Y);
|
||||
center_mass_x_normalized = (2.0 * center_mass_x / imageWidth) - 1.0;
|
||||
center_mass_y_normalized = (2.0 * center_mass_y / imageHeight) - 1.0;
|
||||
particleArea = NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_AREA);
|
||||
boundingRectLeft = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_BOUNDING_RECT_LEFT);
|
||||
boundingRectTop = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_BOUNDING_RECT_TOP);
|
||||
boundingRectWidth = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_BOUNDING_RECT_WIDTH);
|
||||
boundingRectHeight = (int) NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_BOUNDING_RECT_HEIGHT);
|
||||
particleToImagePercent = NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_AREA_BY_IMAGE_AREA);
|
||||
particleQuality = NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA);
|
||||
}
|
||||
|
||||
static double getParticleToImagePercent(BinaryImage image, int index) throws NIVisionException {
|
||||
return NIVision.MeasureParticle(image.image, index, false, NIVision.MeasurementType.IMAQ_MT_AREA_BY_IMAGE_AREA);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get string representation of the particle analysis report.
|
||||
* @return A string representation of the particle analysis report.
|
||||
*/
|
||||
public String toString() {
|
||||
return "Particle Report: \n" +
|
||||
" Image Height : " + imageHeight + "\n" +
|
||||
" Image Width : " + imageWidth + "\n" +
|
||||
" Center of mass : ( " + center_mass_x + " , " + center_mass_y + " )\n" +
|
||||
" normalized : ( " + center_mass_x_normalized + " , " + center_mass_y_normalized + " )\n" +
|
||||
" Area : " + particleArea + "\n" +
|
||||
" percent : " + particleToImagePercent + "\n" +
|
||||
" Bounding Rect : ( " + boundingRectLeft + " , " + boundingRectTop + " ) " + boundingRectWidth + "*" + boundingRectHeight + "\n" +
|
||||
" Quality : " + particleQuality + "\n";
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,35 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
/**
|
||||
* A color image represented in RGB color space at 3 bytes per pixel.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class RGBImage extends ColorImage {
|
||||
|
||||
/**
|
||||
* Create a new 0x0 image.
|
||||
*/
|
||||
public RGBImage() throws NIVisionException {
|
||||
super(NIVision.ImageType.imaqImageRGB);
|
||||
}
|
||||
|
||||
RGBImage(RGBImage sourceImage) {
|
||||
super(sourceImage);
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new image by loading a file.
|
||||
* @param fileName The path of the file to load.
|
||||
*/
|
||||
public RGBImage(String fileName) throws NIVisionException {
|
||||
super(NIVision.ImageType.imaqImageRGB);
|
||||
NIVision.readFile(image, fileName);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,28 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
* This is a dummy class which needs to be filled in.
|
||||
* @author dtjones
|
||||
*/
|
||||
public class RegionOfInterest extends Structure {
|
||||
|
||||
public void read() {
|
||||
}
|
||||
|
||||
public void write() {
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return 0;
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,71 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.image;
|
||||
|
||||
import com.sun.jna.Structure;
|
||||
|
||||
/**
|
||||
*
|
||||
* @author dtjones
|
||||
*/
|
||||
public class ShapeDetectionOptions extends Structure {
|
||||
|
||||
int mode; //unsigned int Specifies the method used when looking for the shape in the image. Combine values from the GeometricMatchingMode enumeration to specify the value of this element.
|
||||
int angleRanges; //RangeFloat* An array of angle ranges, in degrees, where each range specifies how much you expect the shape to be rotated in the image. To decrease the search time, limit the degrees of rotation in which you expect to find the shape in the image. Set this element to NULL to allow all angles. This function ignores this range if mode does not include IMAQ_GEOMETRIC_MATCH_ROTATION_INVARIANT.
|
||||
int numAngleRanges; //int The size of the orientationRanges array.
|
||||
float scaleRangeMin; // RangeFloat A range that specifies the sizes of the shapes you expect to be in the image, expressed as a ratio percentage representing the size of the pattern in the image divided by size of the original pattern multiplied by 100. This function ignores this range if mode does not include IMAQ_GEOMETRIC_MATCH_SCALE_INVARIANT
|
||||
float scaleRangeMax;
|
||||
double minMatchScore; // double The minimum score a match can have for the function to consider the match valid. Acceptable values range from 0 to 1,000.
|
||||
|
||||
public static final int IMAQ_GEOMETRIC_MATCH_SHIFT_INVARIANT = 0; // Searches for occurrences of the pattern in the image, assuming that the pattern is not rotated more than plus or minus 5 degrees.
|
||||
public static final int IMAQ_GEOMETRIC_MATCH_ROTATION_INVARIANT = 1; // Searches for occurrences of the pattern in the image with reduced restriction on the rotation of the pattern.
|
||||
public static final int IMAQ_GEOMETRIC_MATCH_SCALE_INVARIANT = 2; // Searches for occurrences of the pattern in the image with reduced restriction on the size of the pattern.
|
||||
public static final int IMAQ_GEOMETRIC_MATCH_OCCLUSION_INVARIANT = 4; // Searches for occurrences of the pattern in the image, allowing for a specified percentage of the pattern to be occluded.
|
||||
|
||||
|
||||
public ShapeDetectionOptions(int mode, int angleRanges, int numAngleRanges, float scaleRangeMin, float scaleRangeMax, double minMatchScore) {
|
||||
this.mode = mode;
|
||||
this.angleRanges = angleRanges;
|
||||
this.numAngleRanges = numAngleRanges;
|
||||
this.scaleRangeMin = scaleRangeMin;
|
||||
this.scaleRangeMax = scaleRangeMax;
|
||||
this.minMatchScore = minMatchScore;
|
||||
allocateMemory();
|
||||
write();
|
||||
}
|
||||
|
||||
|
||||
public void read() {
|
||||
mode = backingNativeMemory.getInt(0);
|
||||
angleRanges = backingNativeMemory.getInt(4);
|
||||
numAngleRanges = backingNativeMemory.getInt(8);
|
||||
scaleRangeMin = backingNativeMemory.getFloat(12);
|
||||
scaleRangeMax = backingNativeMemory.getFloat(16);
|
||||
minMatchScore = backingNativeMemory.getDouble(20);
|
||||
}
|
||||
|
||||
public void write() {
|
||||
backingNativeMemory.setInt(0, mode);
|
||||
backingNativeMemory.setInt(4, angleRanges);
|
||||
backingNativeMemory.setInt(8, numAngleRanges);
|
||||
backingNativeMemory.setFloat(12, scaleRangeMin);
|
||||
backingNativeMemory.setFloat(16, scaleRangeMax);
|
||||
backingNativeMemory.setDouble(20, minMatchScore);
|
||||
|
||||
|
||||
}
|
||||
|
||||
public int size() {
|
||||
return 28;
|
||||
}
|
||||
|
||||
public void free() {
|
||||
release();
|
||||
}
|
||||
|
||||
}
|
||||
@@ -0,0 +1,12 @@
|
||||
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
|
||||
<html>
|
||||
<head>
|
||||
<title>Image Processing Wrappers</title>
|
||||
<meta http-equiv="Content-Type" content="text/html; charset=MacRoman">
|
||||
</head>
|
||||
<body>
|
||||
Provides classes to access National Instrument's nivison library for machine vision enables automated image processing
|
||||
for color identification, tracking and analysis. The full specification for the simplified FRC Vision programming
|
||||
interface is in the FRC Vision API Specification document, which is in the
|
||||
WindRiver\docs\extensions\FRC directory of the Wind River installation with this document. </body>
|
||||
</html>
|
||||
@@ -0,0 +1,18 @@
|
||||
package edu.wpi.first.wpilibj.internal;
|
||||
|
||||
import edu.wpi.first.wpilibj.HLUsageReporting;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
|
||||
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
|
||||
import edu.wpi.first.wpilibj.communication.UsageReporting;
|
||||
|
||||
public class HardwareHLUsageReporting implements HLUsageReporting.Interface {
|
||||
@Override
|
||||
public void reportScheduler() {
|
||||
UsageReporting.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void reportPIDController(int num) {
|
||||
UsageReporting.report(tResourceType.kResourceType_PIDController, num);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,125 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) FIRST 2008-2012. 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 the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
package edu.wpi.first.wpilibj.internal;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.Utility;
|
||||
import edu.wpi.first.wpilibj.parsing.IUtility;
|
||||
|
||||
/**
|
||||
* Timer objects measure accumulated time in milliseconds.
|
||||
* The timer object functions like a stopwatch. It can be started, stopped, and cleared. When the
|
||||
* timer is running its value counts up in milliseconds. When stopped, the timer holds the current
|
||||
* value. The implementation simply records the time when started and subtracts the current time
|
||||
* whenever the value is requested.
|
||||
*/
|
||||
public class HardwareTimer implements IUtility, Timer.StaticInterface {
|
||||
/**
|
||||
* Pause the thread for a specified time. Pause the execution of the
|
||||
* thread for a specified period of time given in seconds. Motors will
|
||||
* continue to run at their last assigned values, and sensors will continue
|
||||
* to update. Only the task containing the wait will pause until the wait
|
||||
* time is expired.
|
||||
*
|
||||
* @param seconds Length of time to pause
|
||||
*/
|
||||
@Override
|
||||
public void delay(final double seconds) {
|
||||
try {
|
||||
Thread.sleep((long) (seconds * 1e3));
|
||||
} catch (final InterruptedException e) {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the system clock time in seconds. Return the time from the
|
||||
* FPGA hardware clock in seconds since the FPGA started.
|
||||
*
|
||||
* @return Robot running time in seconds.
|
||||
*/
|
||||
@Override
|
||||
public double getFPGATimestamp() {
|
||||
return Utility.getFPGATime() / 1000000.0;
|
||||
}
|
||||
|
||||
@Override
|
||||
public double getMatchTime() {
|
||||
return DriverStation.getInstance().getMatchTime();
|
||||
}
|
||||
|
||||
@Override
|
||||
public Timer.Interface newTimer() {
|
||||
return new TimerImpl();
|
||||
}
|
||||
|
||||
class TimerImpl implements Timer.Interface {
|
||||
private long m_startTime;
|
||||
private double m_accumulatedTime;
|
||||
private boolean m_running;
|
||||
|
||||
/**
|
||||
* Create a new timer object.
|
||||
* Create a new timer object and reset the time to zero. The timer is initially not running and
|
||||
* must be started.
|
||||
*/
|
||||
public TimerImpl() {
|
||||
reset();
|
||||
}
|
||||
|
||||
private long getMsClock() {
|
||||
return Utility.getFPGATime() / 1000;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the current time from the timer. If the clock is running it is derived from
|
||||
* the current system clock the start time stored in the timer class. If the clock
|
||||
* is not running, then return the time when it was last stopped.
|
||||
*
|
||||
* @return Current time value for this timer in seconds
|
||||
*/
|
||||
public synchronized double get() {
|
||||
if (m_running) {
|
||||
return ((double) ((getMsClock() - m_startTime) + m_accumulatedTime)) / 1000.0;
|
||||
} else {
|
||||
return m_accumulatedTime;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the timer by setting the time to 0.
|
||||
* Make the timer startTime the current time so new requests will be relative now
|
||||
*/
|
||||
public synchronized void reset() {
|
||||
m_accumulatedTime = 0;
|
||||
m_startTime = getMsClock();
|
||||
}
|
||||
|
||||
/**
|
||||
* Start the timer running.
|
||||
* Just set the running flag to true indicating that all time requests should be
|
||||
* relative to the system clock.
|
||||
*/
|
||||
public synchronized void start() {
|
||||
m_startTime = getMsClock();
|
||||
m_running = true;
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the timer.
|
||||
* This computes the time as of now and clears the running flag, causing all
|
||||
* subsequent time requests to be read from the accumulated time rather than
|
||||
* looking at the system clock.
|
||||
*/
|
||||
public synchronized void stop() {
|
||||
final double temp = get();
|
||||
m_accumulatedTime = temp;
|
||||
m_running = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user