mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Use diozero for GPIO (#2171)
The old GPIO abstraction was replaced with [`diozero`](https://www.diozero.com), which supports most hardware running Linux due to its use of GPIO character devices provided by the Linux kernel. `diozero` also supports [alternate providers](https://www.diozero.com/concepts/providers.html#providers) if for some reason the character device API is insufficient. Certain capabilities outside of the character device API is also implemented for common hardware. Custom GPIO commands are implemented via a custom `diozero` provider. The configuration for custom GPIO will need manually updated according to the Hardware Config documentation page. The status LED class was also reworked to support additional statuses or LED indication types, although none have been added yet. This was tested on a RPi 5 with LL3 illumination LEDs and an RGB status led attached. All capabilities worked as expected. All 8 status LED colors were tested and functional via modifying the code. Basic functionality of custom GPIO was tested with dummy commands.
This commit is contained in:
@@ -3,7 +3,6 @@
|
||||
"supportURL" : "https://limelightvision.io",
|
||||
"ledPins" : [ 13, 18 ],
|
||||
"ledsCanDim" : true,
|
||||
"ledPWMRange" : [ 0, 100 ],
|
||||
"ledPWMFrequency" : 30000,
|
||||
"vendorFOV" : 75.76079874010732
|
||||
}
|
||||
|
||||
@@ -8,7 +8,7 @@ By default, PhotonVision attempts to make minimal assumptions of the hardware it
|
||||
|
||||
## LED Support
|
||||
|
||||
For Raspberry-Pi based hardware, PhotonVision can use [PiGPIO](https://abyz.me.uk/rpi/pigpio/) to control IO pins. The mapping of which pins control which LED's is part of the hardware config. The pins are active-high: set high when LED's are commanded on, and set low when commanded off.
|
||||
When running on Linux, PhotonVision can use [diozero](https://www.diozero.com) to control IO pins. The mapping of which pins control which LED's is part of the hardware config. The illumination LED pins are active-high: set high when LED's are commanded on, and set low when commanded off.
|
||||
|
||||
```{eval-rst}
|
||||
.. tab-set-code::
|
||||
@@ -16,14 +16,11 @@ For Raspberry-Pi based hardware, PhotonVision can use [PiGPIO](https://abyz.me.u
|
||||
|
||||
{
|
||||
"ledPins" : [ 13 ],
|
||||
"ledSetCommand" : "",
|
||||
"ledsCanDim" : true,
|
||||
"ledPWMRange" : [ 0, 100 ],
|
||||
"ledPWMSetRange" : "",
|
||||
"ledBrightnessRange" : [ 0, 100 ],
|
||||
"ledPWMFrequency" : 0,
|
||||
"ledDimCommand" : "",
|
||||
"ledBlinkCommand" : "",
|
||||
"statusRGBPins" : [ ],
|
||||
"statusRGBActiveHigh" : false,
|
||||
}
|
||||
```
|
||||
|
||||
@@ -31,6 +28,49 @@ For Raspberry-Pi based hardware, PhotonVision can use [PiGPIO](https://abyz.me.u
|
||||
No hardware boards with status RGB LED pins or non-dimming LED's have been tested yet. Please reach out to the development team if these features are desired, they can assist with configuration and testing.
|
||||
:::
|
||||
|
||||
### GPIO Pinout
|
||||
|
||||
::::{tab-set}
|
||||
|
||||
:::{tab-item} Raspberry Pi
|
||||
|
||||
The following diagram shows the GPIO pin numbering of the 40-pin header on Raspberry Pi hardware, courtesy of [pinout.xyz](https://pinout.xyz). Compute modules use the pin numbering from their respective datasheet.
|
||||
|
||||
```{image} https://raw.githubusercontent.com/pinout-xyz/Pinout.xyz/master/resources/raspberry-pi-pinout.png
|
||||
:alt: Raspberry Pi GPIO Pinout
|
||||
```
|
||||
|
||||
:::
|
||||
::::
|
||||
|
||||
### Custom GPIO
|
||||
|
||||
If your hardware does not support diozero's default provider, custom commands can be provided to interact with the GPIO lines. The examples below show what parameters are provided to each command, which can be used in any order or multiple times as needed.
|
||||
|
||||
```{eval-rst}
|
||||
.. tab-set-code::
|
||||
.. code-block:: json
|
||||
|
||||
{
|
||||
"getGPIOCommand" : "getGPIO {p}",
|
||||
"setGPIOCommand" : "setGPIO {p} {s}",
|
||||
"setPWMCommand" : "setPWM {p} {v}",
|
||||
"setPWMFrequencyCommand" : "setPWMFrequency {p} {f}",
|
||||
"releaseGPIOCommand" : "releseGPIO {p}",
|
||||
}
|
||||
```
|
||||
|
||||
The following template strings are used to input parameters to the commands:
|
||||
|
||||
| Template | Parameter | Values |
|
||||
| -------- | ---------- | ---------- |
|
||||
| `{p}` | pin number | integers |
|
||||
| `{s}` | state | true/false |
|
||||
| `{v}` | value | 0.0-1.0 |
|
||||
| `{f}` | frequency | integers |
|
||||
|
||||
If you were using custom LED commands from 2025 or earlier and still need custom GPIO commands, they can likely be copied over. `ledSetCommand` can be reused as `setGPIOCommand`. `ledDimCommand` can be reused with edits as `setPWMCommand`, replacing any occurrences of `{v}` with `$(awk 'BEGIN{ print int({v}*100) }')` if your command requires integer percentages.
|
||||
|
||||
## Hardware Interaction Commands
|
||||
|
||||
For Non-Raspberry-Pi hardware, users must provide valid hardware-specific commands for some parts of the UI interaction (including performance metrics, and executing system restarts).
|
||||
@@ -101,14 +141,16 @@ Here is a complete example `hardwareConfig.json`:
|
||||
"deviceLogoPath" : "",
|
||||
"supportURL" : "https://www.youtube.com/watch?v=b-CvLWbfZhU",
|
||||
"ledPins" : [2, 13],
|
||||
"ledSetCommand" : "",
|
||||
"ledsCanDim" : true,
|
||||
"ledPWMRange" : [ 0, 100 ],
|
||||
"ledPWMSetRange" : "",
|
||||
"ledBrightnessRange" : [ 0, 100 ],
|
||||
"ledPWMFrequency" : 0,
|
||||
"ledDimCommand" : "",
|
||||
"ledBlinkCommand" : "",
|
||||
"statusRGBPins" : [ ],
|
||||
"statusRGBActiveHigh" : false,
|
||||
"getGPIOCommand" : "getGPIO {p}",
|
||||
"setGPIOCommand" : "setGPIO {p} {s}",
|
||||
"setPWMCommand" : "setPWM {p} {v}",
|
||||
"setPWMFrequencyCommand" : "setPWMFrequency {p} {f}",
|
||||
"releaseGPIOCommand" : "releseGPIO {p}",
|
||||
"cpuTempCommand" : "",
|
||||
"cpuMemoryCommand" : "",
|
||||
"cpuUtilCommand" : "",
|
||||
|
||||
@@ -31,6 +31,7 @@ dependencies {
|
||||
// These stay as implementation dependencies since they don't have native code that gets packaged
|
||||
implementation 'org.zeroturnaround:zt-zip:1.14'
|
||||
implementation "org.xerial:sqlite-jdbc:3.41.0.0"
|
||||
implementation 'com.diozero:diozero-core:1.4.1'
|
||||
|
||||
// The JNI libraries use wpilibNatives, the java libraries use implementation
|
||||
if (jniPlatform == "linuxarm64") {
|
||||
|
||||
@@ -28,12 +28,18 @@ public class HardwareConfig {
|
||||
|
||||
// LED control
|
||||
public final ArrayList<Integer> ledPins;
|
||||
public final String ledSetCommand;
|
||||
public final boolean ledsCanDim;
|
||||
public final ArrayList<Integer> ledBrightnessRange;
|
||||
public final String ledDimCommand;
|
||||
public final String ledBlinkCommand;
|
||||
public final int ledPWMFrequency;
|
||||
public final ArrayList<Integer> statusRGBPins;
|
||||
public final boolean statusRGBActiveHigh;
|
||||
|
||||
// Custom GPIO
|
||||
public final String getGPIOCommand;
|
||||
public final String setGPIOCommand;
|
||||
public final String setPWMCommand;
|
||||
public final String setPWMFrequencyCommand;
|
||||
public final String releaseGPIOCommand;
|
||||
|
||||
// Metrics
|
||||
public final String cpuTempCommand;
|
||||
@@ -55,12 +61,16 @@ public class HardwareConfig {
|
||||
String deviceLogoPath,
|
||||
String supportURL,
|
||||
ArrayList<Integer> ledPins,
|
||||
String ledSetCommand,
|
||||
boolean ledsCanDim,
|
||||
ArrayList<Integer> ledBrightnessRange,
|
||||
String ledDimCommand,
|
||||
String ledBlinkCommand,
|
||||
int ledPwmFrequency,
|
||||
ArrayList<Integer> statusRGBPins,
|
||||
boolean statusRGBActiveHigh,
|
||||
String getGPIOCommand,
|
||||
String setGPIOCommand,
|
||||
String setPWMCommand,
|
||||
String setPWMFrequencyCommand,
|
||||
String releaseGPIOCommand,
|
||||
String cpuTempCommand,
|
||||
String cpuMemoryCommand,
|
||||
String cpuUtilCommand,
|
||||
@@ -76,12 +86,16 @@ public class HardwareConfig {
|
||||
this.deviceLogoPath = deviceLogoPath;
|
||||
this.supportURL = supportURL;
|
||||
this.ledPins = ledPins;
|
||||
this.ledSetCommand = ledSetCommand;
|
||||
this.ledsCanDim = ledsCanDim;
|
||||
this.ledBrightnessRange = ledBrightnessRange;
|
||||
this.ledDimCommand = ledDimCommand;
|
||||
this.ledBlinkCommand = ledBlinkCommand;
|
||||
this.ledPWMFrequency = ledPwmFrequency;
|
||||
this.statusRGBPins = statusRGBPins;
|
||||
this.statusRGBActiveHigh = statusRGBActiveHigh;
|
||||
this.getGPIOCommand = getGPIOCommand;
|
||||
this.setGPIOCommand = setGPIOCommand;
|
||||
this.setPWMCommand = setPWMCommand;
|
||||
this.setPWMFrequencyCommand = setPWMFrequencyCommand;
|
||||
this.releaseGPIOCommand = releaseGPIOCommand;
|
||||
this.cpuTempCommand = cpuTempCommand;
|
||||
this.cpuMemoryCommand = cpuMemoryCommand;
|
||||
this.cpuUtilCommand = cpuUtilCommand;
|
||||
@@ -100,12 +114,16 @@ public class HardwareConfig {
|
||||
deviceLogoPath = "";
|
||||
supportURL = "";
|
||||
ledPins = new ArrayList<>();
|
||||
ledSetCommand = "";
|
||||
ledsCanDim = false;
|
||||
ledBrightnessRange = new ArrayList<>();
|
||||
ledDimCommand = "";
|
||||
ledBlinkCommand = "";
|
||||
ledPWMFrequency = 0;
|
||||
statusRGBPins = new ArrayList<>();
|
||||
statusRGBActiveHigh = false;
|
||||
getGPIOCommand = "";
|
||||
setGPIOCommand = "";
|
||||
setPWMCommand = "";
|
||||
setPWMFrequencyCommand = "";
|
||||
releaseGPIOCommand = "";
|
||||
cpuTempCommand = "";
|
||||
cpuMemoryCommand = "";
|
||||
cpuUtilCommand = "";
|
||||
@@ -127,7 +145,7 @@ public class HardwareConfig {
|
||||
}
|
||||
|
||||
/**
|
||||
* @return True if any command has been configured to a non-default empty, false otherwise
|
||||
* @return True if any info command has been configured to be non-empty, false otherwise
|
||||
*/
|
||||
public final boolean hasCommandsConfigured() {
|
||||
return cpuTempCommand != ""
|
||||
@@ -137,11 +155,21 @@ public class HardwareConfig {
|
||||
|| cpuUptimeCommand != ""
|
||||
|| gpuMemoryCommand != ""
|
||||
|| ramUtilCommand != ""
|
||||
|| ledBlinkCommand != ""
|
||||
|| gpuMemUsageCommand != ""
|
||||
|| diskUsageCommand != "";
|
||||
}
|
||||
|
||||
/**
|
||||
* @return True if any gpio command has been configured to be non-empty, false otherwise
|
||||
*/
|
||||
public final boolean hasGPIOCommandsConfigured() {
|
||||
return getGPIOCommand != ""
|
||||
|| setGPIOCommand != ""
|
||||
|| setPWMCommand != ""
|
||||
|| setPWMFrequencyCommand != ""
|
||||
|| releaseGPIOCommand != "";
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "HardwareConfig[deviceName="
|
||||
@@ -152,18 +180,26 @@ public class HardwareConfig {
|
||||
+ supportURL
|
||||
+ ", ledPins="
|
||||
+ ledPins
|
||||
+ ", ledSetCommand="
|
||||
+ ledSetCommand
|
||||
+ ", ledsCanDim="
|
||||
+ ledsCanDim
|
||||
+ ", ledBrightnessRange="
|
||||
+ ledBrightnessRange
|
||||
+ ", ledDimCommand="
|
||||
+ ledDimCommand
|
||||
+ ", ledBlinkCommand="
|
||||
+ ledBlinkCommand
|
||||
+ ", ledPWMFrequency="
|
||||
+ ledPWMFrequency
|
||||
+ ", statusRGBPins="
|
||||
+ statusRGBPins
|
||||
+ ", statusRGBActiveHigh"
|
||||
+ statusRGBActiveHigh
|
||||
+ ", getGPIOCommand="
|
||||
+ getGPIOCommand
|
||||
+ ", setGPIOCommand="
|
||||
+ setGPIOCommand
|
||||
+ ", setPWMCommand="
|
||||
+ setPWMCommand
|
||||
+ ", setPWMFrequencyCommand="
|
||||
+ setPWMFrequencyCommand
|
||||
+ ", releaseGPIOCommand="
|
||||
+ releaseGPIOCommand
|
||||
+ ", cpuTempCommand="
|
||||
+ cpuTempCommand
|
||||
+ ", cpuMemoryCommand="
|
||||
|
||||
@@ -1,99 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO;
|
||||
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
|
||||
public class CustomGPIO extends GPIOBase {
|
||||
private boolean currentState;
|
||||
private final int port;
|
||||
|
||||
public CustomGPIO(int port) {
|
||||
this.port = port;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void togglePin() {
|
||||
if (this.port != -1) {
|
||||
execute(
|
||||
commands
|
||||
.get("setState")
|
||||
.replace("{s}", String.valueOf(!currentState))
|
||||
.replace("{p}", String.valueOf(this.port)));
|
||||
currentState = !currentState;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPinNumber() {
|
||||
return port;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setStateImpl(boolean state) {
|
||||
if (this.port != -1) {
|
||||
execute(
|
||||
commands
|
||||
.get("setState")
|
||||
.replace("{s}", String.valueOf(state))
|
||||
.replace("{p}", String.valueOf(port)));
|
||||
currentState = state;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean shutdown() {
|
||||
if (this.port != -1) {
|
||||
execute(commands.get("shutdown"));
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getStateImpl() {
|
||||
return currentState;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void blinkImpl(int pulseTimeMillis, int blinks) {
|
||||
execute(
|
||||
commands
|
||||
.get("blink")
|
||||
.replace("{pulseTime}", String.valueOf(pulseTimeMillis))
|
||||
.replace("{blinks}", String.valueOf(blinks))
|
||||
.replace("{p}", String.valueOf(this.port)));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBrightnessImpl(int brightness) {
|
||||
execute(
|
||||
commands
|
||||
.get("dim")
|
||||
.replace("{p}", String.valueOf(port))
|
||||
.replace("{v}", String.valueOf(brightness)));
|
||||
}
|
||||
|
||||
public static void setConfig(HardwareConfig config) {
|
||||
if (Platform.isRaspberryPi()) return;
|
||||
commands.replace("setState", config.ledSetCommand);
|
||||
commands.replace("dim", config.ledDimCommand);
|
||||
commands.replace("blink", config.ledBlinkCommand);
|
||||
}
|
||||
}
|
||||
@@ -1,99 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO;
|
||||
|
||||
import java.util.Arrays;
|
||||
import java.util.HashMap;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public abstract class GPIOBase {
|
||||
private static final Logger logger = new Logger(GPIOBase.class, LogGroup.General);
|
||||
private static final ShellExec runCommand = new ShellExec(true, true);
|
||||
|
||||
protected static HashMap<String, String> commands =
|
||||
new HashMap<>() {
|
||||
{
|
||||
put("setState", "");
|
||||
put("shutdown", "");
|
||||
put("dim", "");
|
||||
put("blink", "");
|
||||
}
|
||||
};
|
||||
|
||||
protected static String execute(String command) {
|
||||
try {
|
||||
runCommand.executeBashCommand(command);
|
||||
} catch (Exception e) {
|
||||
logger.error(Arrays.toString(e.getStackTrace()));
|
||||
return "";
|
||||
}
|
||||
return runCommand.getOutput();
|
||||
}
|
||||
|
||||
public abstract int getPinNumber();
|
||||
|
||||
public void setState(boolean state) {
|
||||
if (getPinNumber() != -1) {
|
||||
setStateImpl(state);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void setStateImpl(boolean state);
|
||||
|
||||
public final void setOff() {
|
||||
setState(false);
|
||||
}
|
||||
|
||||
public final void setOn() {
|
||||
setState(true);
|
||||
}
|
||||
|
||||
public void togglePin() {
|
||||
setState(!getStateImpl());
|
||||
}
|
||||
|
||||
public abstract boolean shutdown();
|
||||
|
||||
public final boolean getState() {
|
||||
if (getPinNumber() != -1) {
|
||||
return getStateImpl();
|
||||
} else return false;
|
||||
}
|
||||
|
||||
public abstract boolean getStateImpl();
|
||||
|
||||
public final void blink(int pulseTimeMillis, int blinks) {
|
||||
if (getPinNumber() != -1) {
|
||||
blinkImpl(pulseTimeMillis, blinks);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void blinkImpl(int pulseTimeMillis, int blinks);
|
||||
|
||||
public final void setBrightness(int brightness) {
|
||||
if (getPinNumber() != -1) {
|
||||
if (brightness > 100) brightness = 100;
|
||||
if (brightness < 0) brightness = 0;
|
||||
setBrightnessImpl(brightness);
|
||||
}
|
||||
}
|
||||
|
||||
protected abstract void setBrightnessImpl(int brightness);
|
||||
}
|
||||
@@ -1,40 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
@SuppressWarnings("SpellCheckingInspection")
|
||||
public enum PigpioCommand {
|
||||
PCMD_READ(3), // int gpio_read(unsigned gpio)
|
||||
PCMD_WRITE(4), // int gpio_write(unsigned gpio, unsigned level)
|
||||
PCMD_WVCLR(27), // int wave_clear(void)
|
||||
PCMD_WVAG(28), // int wave_add_generic(unsigned numPulses, gpioPulse_t *pulses)
|
||||
PCMD_WVHLT(33), // int wave_tx_stop(void)
|
||||
PCMD_WVCRE(49), // int wave_create(void)
|
||||
PCMD_WVDEL(50), // int wave_delete(unsigned wave_id)
|
||||
PCMD_WVTX(51), // int wave_tx_send(unsigned wave_id) (once)
|
||||
PCMD_WVTXR(52), // int wave_tx_send(unsigned wave_id) (repeat)
|
||||
PCMD_GDC(83), // int get_duty_cycle(unsigned user_gpio)
|
||||
PCMD_HP(86), // int hardware_pwm(unsigned gpio, unsigned PWMfreq, unsigned PWMduty)
|
||||
PCMD_WVTXM(100); // int wave_tx_send(unsigned wave_id, unsigned wave_mode)
|
||||
|
||||
public final int value;
|
||||
|
||||
PigpioCommand(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
}
|
||||
@@ -1,343 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import java.util.HashMap;
|
||||
|
||||
/**
|
||||
* A class that defines the exceptions that can be thrown by Pigpio.
|
||||
*
|
||||
* <p>Credit to nkolban
|
||||
* https://github.com/nkolban/jpigpio/blob/master/JPigpio/src/jpigpio/PigpioException.java
|
||||
*/
|
||||
@SuppressWarnings({"SpellCheckingInspection", "unused", "RedundantSuppression"})
|
||||
public class PigpioException extends Exception {
|
||||
private int rc = -99999999;
|
||||
private static final long serialVersionUID = 443595760654129068L;
|
||||
|
||||
public PigpioException() {
|
||||
super();
|
||||
}
|
||||
|
||||
public PigpioException(int rc) {
|
||||
super();
|
||||
this.rc = rc;
|
||||
}
|
||||
|
||||
public PigpioException(int rc, String msg) {
|
||||
super(msg);
|
||||
this.rc = rc;
|
||||
}
|
||||
|
||||
public PigpioException(String arg0, Throwable arg1, boolean arg2, boolean arg3) {
|
||||
super(arg0, arg1, arg2, arg3);
|
||||
}
|
||||
|
||||
public PigpioException(String arg0, Throwable arg1) {
|
||||
super(arg0, arg1);
|
||||
}
|
||||
|
||||
public PigpioException(String arg0) {
|
||||
super(arg0);
|
||||
}
|
||||
|
||||
public PigpioException(Throwable arg0) {
|
||||
super(arg0);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getMessage() {
|
||||
return "(" + rc + ") " + getMessageForError(rc);
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve the error code that was returned by the underlying Pigpio call.
|
||||
*
|
||||
* @return The error code that was returned by the underlying Pigpio call.
|
||||
*/
|
||||
public int getErrorCode() {
|
||||
return rc;
|
||||
} // End of getErrorCode
|
||||
|
||||
// Public constants for the error codes that can be thrown by Pigpio
|
||||
public static final int PI_INIT_FAILED = -1; // gpioInitialise failed
|
||||
public static final int PI_BAD_USER_GPIO = -2; // gpio not 0-31
|
||||
public static final int PI_BAD_GPIO = -3; // gpio not 0-53
|
||||
public static final int PI_BAD_MODE = -4; // mode not 0-7
|
||||
public static final int PI_BAD_LEVEL = -5; // level not 0-1
|
||||
public static final int PI_BAD_PUD = -6; // pud not 0-2
|
||||
public static final int PI_BAD_PULSEWIDTH = -7; // pulsewidth not 0 or 500-2500
|
||||
public static final int PI_BAD_DUTYCYCLE = -8; // dutycycle outside set range
|
||||
public static final int PI_BAD_TIMER = -9; // timer not 0-9
|
||||
public static final int PI_BAD_MS = -10; // ms not 10-60000
|
||||
public static final int PI_BAD_TIMETYPE = -11; // timetype not 0-1
|
||||
public static final int PI_BAD_SECONDS = -12; // seconds < 0
|
||||
public static final int PI_BAD_MICROS = -13; // micros not 0-999999
|
||||
public static final int PI_TIMER_FAILED = -14; // gpioSetTimerFunc failed
|
||||
public static final int PI_BAD_WDOG_TIMEOUT = -15; // timeout not 0-60000
|
||||
public static final int PI_NO_ALERT_FUNC = -16; // DEPRECATED
|
||||
public static final int PI_BAD_CLK_PERIPH = -17; // clock peripheral not 0-1
|
||||
public static final int PI_BAD_CLK_SOURCE = -18; // DEPRECATED
|
||||
public static final int PI_BAD_CLK_MICROS = -19; // clock micros not 1, 2, 4, 5, 8, or 10
|
||||
public static final int PI_BAD_BUF_MILLIS = -20; // buf millis not 100-10000
|
||||
public static final int PI_BAD_DUTYRANGE = -21; // dutycycle range not 25-40000
|
||||
public static final int PI_BAD_DUTY_RANGE = -21; // DEPRECATED (use PI_BAD_DUTYRANGE)
|
||||
public static final int PI_BAD_SIGNUM = -22; // signum not 0-63
|
||||
public static final int PI_BAD_PATHNAME = -23; // can't open pathname
|
||||
public static final int PI_NO_HANDLE = -24; // no handle available
|
||||
public static final int PI_BAD_HANDLE = -25; // unknown handle
|
||||
public static final int PI_BAD_IF_FLAGS = -26; // ifFlags > 3
|
||||
public static final int PI_BAD_CHANNEL = -27; // DMA channel not 0-14
|
||||
public static final int PI_BAD_PRIM_CHANNEL = -27; // DMA primary channel not 0-14
|
||||
public static final int PI_BAD_SOCKET_PORT = -28; // socket port not 1024-32000
|
||||
public static final int PI_BAD_FIFO_COMMAND = -29; // unrecognized fifo command
|
||||
public static final int PI_BAD_SECO_CHANNEL = -30; // DMA secondary channel not 0-6
|
||||
public static final int PI_NOT_INITIALISED = -31; // function called before gpioInitialise
|
||||
public static final int PI_INITIALISED = -32; // function called after gpioInitialise
|
||||
public static final int PI_BAD_WAVE_MODE = -33; // waveform mode not 0-1
|
||||
public static final int PI_BAD_CFG_INTERNAL = -34; // bad parameter in gpioCfgInternals call
|
||||
public static final int PI_BAD_WAVE_BAUD = -35; // baud rate not 50-250K(RX)/50-1M(TX)
|
||||
public static final int PI_TOO_MANY_PULSES = -36; // waveform has too many pulses
|
||||
public static final int PI_TOO_MANY_CHARS = -37; // waveform has too many chars
|
||||
public static final int PI_NOT_SERIAL_GPIO = -38; // no serial read in progress on gpio
|
||||
public static final int PI_BAD_SERIAL_STRUC = -39; // bad (null) serial structure parameter
|
||||
public static final int PI_BAD_SERIAL_BUF = -40; // bad (null) serial buf parameter
|
||||
public static final int PI_NOT_PERMITTED = -41; // gpio operation not permitted
|
||||
public static final int PI_SOME_PERMITTED = -42; // one or more gpios not permitted
|
||||
public static final int PI_BAD_WVSC_COMMND = -43; // bad WVSC subcommand
|
||||
public static final int PI_BAD_WVSM_COMMND = -44; // bad WVSM subcommand
|
||||
public static final int PI_BAD_WVSP_COMMND = -45; // bad WVSP subcommand
|
||||
public static final int PI_BAD_PULSELEN = -46; // trigger pulse length not 1-100
|
||||
public static final int PI_BAD_SCRIPT = -47; // invalid script
|
||||
public static final int PI_BAD_SCRIPT_ID = -48; // unknown script id
|
||||
public static final int PI_BAD_SER_OFFSET = -49; // add serial data offset > 30 minutes
|
||||
public static final int PI_GPIO_IN_USE = -50; // gpio already in use
|
||||
public static final int PI_BAD_SERIAL_COUNT = -51; // must read at least a byte at a time
|
||||
public static final int PI_BAD_PARAM_NUM = -52; // script parameter id not 0-9
|
||||
public static final int PI_DUP_TAG = -53; // script has duplicate tag
|
||||
public static final int PI_TOO_MANY_TAGS = -54; // script has too many tags
|
||||
public static final int PI_BAD_SCRIPT_CMD = -55; // illegal script command
|
||||
public static final int PI_BAD_VAR_NUM = -56; // script variable id not 0-149
|
||||
public static final int PI_NO_SCRIPT_ROOM = -57; // no more room for scripts
|
||||
public static final int PI_NO_MEMORY = -58; // can't allocate temporary memory
|
||||
public static final int PI_SOCK_READ_FAILED = -59; // socket read failed
|
||||
public static final int PI_SOCK_WRIT_FAILED = -60; // socket write failed
|
||||
public static final int PI_TOO_MANY_PARAM = -61; // too many script parameters (> 10)
|
||||
public static final int PI_NOT_HALTED = -62; // script already running or failed
|
||||
public static final int PI_BAD_TAG = -63; // script has unresolved tag
|
||||
public static final int PI_BAD_MICS_DELAY = -64; // bad MICS delay (too large)
|
||||
public static final int PI_BAD_MILS_DELAY = -65; // bad MILS delay (too large)
|
||||
public static final int PI_BAD_WAVE_ID = -66; // non existent wave id
|
||||
public static final int PI_TOO_MANY_CBS = -67; // No more CBs for waveform
|
||||
public static final int PI_TOO_MANY_OOL = -68; // No more OOL for waveform
|
||||
public static final int PI_EMPTY_WAVEFORM = -69; // attempt to create an empty waveform
|
||||
public static final int PI_NO_WAVEFORM_ID = -70; // no more waveforms
|
||||
public static final int PI_I2C_OPEN_FAILED = -71; // can't open I2C device
|
||||
public static final int PI_SER_OPEN_FAILED = -72; // can't open serial device
|
||||
public static final int PI_SPI_OPEN_FAILED = -73; // can't open SPI device
|
||||
public static final int PI_BAD_I2C_BUS = -74; // bad I2C bus
|
||||
public static final int PI_BAD_I2C_ADDR = -75; // bad I2C address
|
||||
public static final int PI_BAD_SPI_CHANNEL = -76; // bad SPI channel
|
||||
public static final int PI_BAD_FLAGS = -77; // bad i2c/spi/ser open flags
|
||||
public static final int PI_BAD_SPI_SPEED = -78; // bad SPI speed
|
||||
public static final int PI_BAD_SER_DEVICE = -79; // bad serial device name
|
||||
public static final int PI_BAD_SER_SPEED = -80; // bad serial baud rate
|
||||
public static final int PI_BAD_PARAM = -81; // bad i2c/spi/ser parameter
|
||||
public static final int PI_I2C_WRITE_FAILED = -82; // i2c write failed
|
||||
public static final int PI_I2C_READ_FAILED = -83; // i2c read failed
|
||||
public static final int PI_BAD_SPI_COUNT = -84; // bad SPI count
|
||||
public static final int PI_SER_WRITE_FAILED = -85; // ser write failed
|
||||
public static final int PI_SER_READ_FAILED = -86; // ser read failed
|
||||
public static final int PI_SER_READ_NO_DATA = -87; // ser read no data available
|
||||
public static final int PI_UNKNOWN_COMMAND = -88; // unknown command
|
||||
public static final int PI_SPI_XFER_FAILED = -89; // spi xfer/read/write failed
|
||||
public static final int PI_BAD_POINTER = -90; // bad (NULL) pointer
|
||||
public static final int PI_NO_AUX_SPI = -91; // need a A+/B+/Pi2 for auxiliary SPI
|
||||
public static final int PI_NOT_PWM_GPIO = -92; // gpio is not in use for PWM
|
||||
public static final int PI_NOT_SERVO_GPIO = -93; // gpio is not in use for servo pulses
|
||||
public static final int PI_NOT_HCLK_GPIO = -94; // gpio has no hardware clock
|
||||
public static final int PI_NOT_HPWM_GPIO = -95; // gpio has no hardware PWM
|
||||
public static final int PI_BAD_HPWM_FREQ = -96; // hardware PWM frequency not 1-125M
|
||||
public static final int PI_BAD_HPWM_DUTY = -97; // hardware PWM dutycycle not 0-1M
|
||||
public static final int PI_BAD_HCLK_FREQ = -98; // hardware clock frequency not 4689-250M
|
||||
public static final int PI_BAD_HCLK_PASS = -99; // need password to use hardware clock 1
|
||||
public static final int PI_HPWM_ILLEGAL = -100; // illegal, PWM in use for main clock
|
||||
public static final int PI_BAD_DATABITS = -101; // serial data bits not 1-32
|
||||
public static final int PI_BAD_STOPBITS = -102; // serial (half) stop bits not 2-8
|
||||
public static final int PI_MSG_TOOBIG = -103; // socket/pipe message too big
|
||||
public static final int PI_BAD_MALLOC_MODE = -104; // bad memory allocation mode
|
||||
public static final int PI_TOO_MANY_SEGS = -105; // too many I2C transaction parts
|
||||
public static final int PI_BAD_I2C_SEG = -106; // a combined I2C transaction failed
|
||||
public static final int PI_BAD_SMBUS_CMD = -107;
|
||||
public static final int PI_NOT_I2C_GPIO = -108;
|
||||
public static final int PI_BAD_I2C_WLEN = -109;
|
||||
public static final int PI_BAD_I2C_RLEN = -110;
|
||||
public static final int PI_BAD_I2C_CMD = -111;
|
||||
public static final int PI_BAD_I2C_BAUD = -112;
|
||||
public static final int PI_CHAIN_LOOP_CNT = -113;
|
||||
public static final int PI_BAD_CHAIN_LOOP = -114;
|
||||
public static final int PI_CHAIN_COUNTER = -115;
|
||||
public static final int PI_BAD_CHAIN_CMD = -116;
|
||||
public static final int PI_BAD_CHAIN_DELAY = -117;
|
||||
public static final int PI_CHAIN_NESTING = -118;
|
||||
public static final int PI_CHAIN_TOO_BIG = -119;
|
||||
public static final int PI_DEPRECATED = -120;
|
||||
public static final int PI_BAD_SER_INVERT = -121;
|
||||
public static final int PI_BAD_EDGE = -122;
|
||||
public static final int PI_BAD_ISR_INIT = -123;
|
||||
public static final int PI_BAD_FOREVER = -124;
|
||||
public static final int PI_BAD_FILTER = -125;
|
||||
|
||||
public static final int PI_PIGIF_ERR_0 = -2000;
|
||||
public static final int PI_PIGIF_ERR_99 = -2099;
|
||||
|
||||
public static final int PI_CUSTOM_ERR_0 = -3000;
|
||||
public static final int PI_CUSTOM_ERR_999 = -3999;
|
||||
|
||||
private static final HashMap<Integer, String> errorMessages = new HashMap<>();
|
||||
|
||||
static {
|
||||
errorMessages.put(PI_INIT_FAILED, "pigpio initialisation failed");
|
||||
errorMessages.put(PI_BAD_USER_GPIO, "GPIO not 0-31");
|
||||
errorMessages.put(PI_BAD_GPIO, "GPIO not 0-53");
|
||||
errorMessages.put(PI_BAD_MODE, "mode not 0-7");
|
||||
errorMessages.put(PI_BAD_LEVEL, "level not 0-1");
|
||||
errorMessages.put(PI_BAD_PUD, "pud not 0-2");
|
||||
errorMessages.put(PI_BAD_PULSEWIDTH, "pulsewidth not 0 or 500-2500");
|
||||
errorMessages.put(PI_BAD_DUTYCYCLE, "dutycycle not 0-range (default 255)");
|
||||
errorMessages.put(PI_BAD_TIMER, "timer not 0-9");
|
||||
errorMessages.put(PI_BAD_MS, "ms not 10-60000");
|
||||
errorMessages.put(PI_BAD_TIMETYPE, "timetype not 0-1");
|
||||
errorMessages.put(PI_BAD_SECONDS, "seconds < 0");
|
||||
errorMessages.put(PI_BAD_MICROS, "micros not 0-999999");
|
||||
errorMessages.put(PI_TIMER_FAILED, "gpioSetTimerFunc failed");
|
||||
errorMessages.put(PI_BAD_WDOG_TIMEOUT, "timeout not 0-60000");
|
||||
errorMessages.put(PI_NO_ALERT_FUNC, "DEPRECATED");
|
||||
errorMessages.put(PI_BAD_CLK_PERIPH, "clock peripheral not 0-1");
|
||||
errorMessages.put(PI_BAD_CLK_SOURCE, "DEPRECATED");
|
||||
errorMessages.put(PI_BAD_CLK_MICROS, "clock micros not 1, 2, 4, 5, 8, or 10");
|
||||
errorMessages.put(PI_BAD_BUF_MILLIS, "buf millis not 100-10000");
|
||||
errorMessages.put(PI_BAD_DUTYRANGE, "dutycycle range not 25-40000");
|
||||
errorMessages.put(PI_BAD_SIGNUM, "signum not 0-63");
|
||||
errorMessages.put(PI_BAD_PATHNAME, "can't open pathname");
|
||||
errorMessages.put(PI_NO_HANDLE, "no handle available");
|
||||
errorMessages.put(PI_BAD_HANDLE, "unknown handle");
|
||||
errorMessages.put(PI_BAD_IF_FLAGS, "ifFlags > 3");
|
||||
errorMessages.put(PI_BAD_CHANNEL, "DMA channel not 0-14");
|
||||
errorMessages.put(PI_BAD_SOCKET_PORT, "socket port not 1024-30000");
|
||||
errorMessages.put(PI_BAD_FIFO_COMMAND, "unknown fifo command");
|
||||
errorMessages.put(PI_BAD_SECO_CHANNEL, "DMA secondary channel not 0-14");
|
||||
errorMessages.put(PI_NOT_INITIALISED, "function called before gpioInitialise");
|
||||
errorMessages.put(PI_INITIALISED, "function called after gpioInitialise");
|
||||
errorMessages.put(PI_BAD_WAVE_MODE, "waveform mode not 0-1");
|
||||
errorMessages.put(PI_BAD_CFG_INTERNAL, "bad parameter in gpioCfgInternals call");
|
||||
errorMessages.put(PI_BAD_WAVE_BAUD, "baud rate not 50-250000(RX)/1000000(TX)");
|
||||
errorMessages.put(PI_TOO_MANY_PULSES, "waveform has too many pulses");
|
||||
errorMessages.put(PI_TOO_MANY_CHARS, "waveform has too many chars");
|
||||
errorMessages.put(PI_NOT_SERIAL_GPIO, "no bit bang serial read in progress on GPIO");
|
||||
errorMessages.put(PI_NOT_PERMITTED, "no permission to update GPIO");
|
||||
errorMessages.put(PI_SOME_PERMITTED, "no permission to update one or more GPIO");
|
||||
errorMessages.put(PI_BAD_WVSC_COMMND, "bad WVSC subcommand");
|
||||
errorMessages.put(PI_BAD_WVSM_COMMND, "bad WVSM subcommand");
|
||||
errorMessages.put(PI_BAD_WVSP_COMMND, "bad WVSP subcommand");
|
||||
errorMessages.put(PI_BAD_PULSELEN, "trigger pulse length not 1-100");
|
||||
errorMessages.put(PI_BAD_SCRIPT, "invalid script");
|
||||
errorMessages.put(PI_BAD_SCRIPT_ID, "unknown script id");
|
||||
errorMessages.put(PI_BAD_SER_OFFSET, "add serial data offset > 30 minute");
|
||||
errorMessages.put(PI_GPIO_IN_USE, "GPIO already in use");
|
||||
errorMessages.put(PI_BAD_SERIAL_COUNT, "must read at least a byte at a time");
|
||||
errorMessages.put(PI_BAD_PARAM_NUM, "script parameter id not 0-9");
|
||||
errorMessages.put(PI_DUP_TAG, "script has duplicate tag");
|
||||
errorMessages.put(PI_TOO_MANY_TAGS, "script has too many tags");
|
||||
errorMessages.put(PI_BAD_SCRIPT_CMD, "illegal script command");
|
||||
errorMessages.put(PI_BAD_VAR_NUM, "script variable id not 0-149");
|
||||
errorMessages.put(PI_NO_SCRIPT_ROOM, "no more room for scripts");
|
||||
errorMessages.put(PI_NO_MEMORY, "can't allocate temporary memory");
|
||||
errorMessages.put(PI_SOCK_READ_FAILED, "socket read failed");
|
||||
errorMessages.put(PI_SOCK_WRIT_FAILED, "socket write failed");
|
||||
errorMessages.put(PI_TOO_MANY_PARAM, "too many script parameters (> 10)");
|
||||
errorMessages.put(PI_NOT_HALTED, "script already running or failed");
|
||||
errorMessages.put(PI_BAD_TAG, "script has unresolved tag");
|
||||
errorMessages.put(PI_BAD_MICS_DELAY, "bad MICS delay (too large)");
|
||||
errorMessages.put(PI_BAD_MILS_DELAY, "bad MILS delay (too large)");
|
||||
errorMessages.put(PI_BAD_WAVE_ID, "non existent wave id");
|
||||
errorMessages.put(PI_TOO_MANY_CBS, "No more CBs for waveform");
|
||||
errorMessages.put(PI_TOO_MANY_OOL, "No more OOL for waveform");
|
||||
errorMessages.put(PI_EMPTY_WAVEFORM, "attempt to create an empty waveform");
|
||||
errorMessages.put(PI_NO_WAVEFORM_ID, "No more waveform ids");
|
||||
errorMessages.put(PI_I2C_OPEN_FAILED, "can't open I2C device");
|
||||
errorMessages.put(PI_SER_OPEN_FAILED, "can't open serial device");
|
||||
errorMessages.put(PI_SPI_OPEN_FAILED, "can't open SPI device");
|
||||
errorMessages.put(PI_BAD_I2C_BUS, "bad I2C bus");
|
||||
errorMessages.put(PI_BAD_I2C_ADDR, "bad I2C address");
|
||||
errorMessages.put(PI_BAD_SPI_CHANNEL, "bad SPI channel");
|
||||
errorMessages.put(PI_BAD_FLAGS, "bad i2c/spi/ser open flags");
|
||||
errorMessages.put(PI_BAD_SPI_SPEED, "bad SPI speed");
|
||||
errorMessages.put(PI_BAD_SER_DEVICE, "bad serial device name");
|
||||
errorMessages.put(PI_BAD_SER_SPEED, "bad serial baud rate");
|
||||
errorMessages.put(PI_BAD_PARAM, "bad i2c/spi/ser parameter");
|
||||
errorMessages.put(PI_I2C_WRITE_FAILED, "I2C write failed");
|
||||
errorMessages.put(PI_I2C_READ_FAILED, "I2C read failed");
|
||||
errorMessages.put(PI_BAD_SPI_COUNT, "bad SPI count");
|
||||
errorMessages.put(PI_SER_WRITE_FAILED, "ser write failed");
|
||||
errorMessages.put(PI_SER_READ_FAILED, "ser read failed");
|
||||
errorMessages.put(PI_SER_READ_NO_DATA, "ser read no data available");
|
||||
errorMessages.put(PI_UNKNOWN_COMMAND, "unknown command");
|
||||
errorMessages.put(PI_SPI_XFER_FAILED, "SPI xfer/read/write failed");
|
||||
errorMessages.put(PI_BAD_POINTER, "bad (NULL) pointer");
|
||||
errorMessages.put(PI_NO_AUX_SPI, "no auxiliary SPI on Pi A or B");
|
||||
errorMessages.put(PI_NOT_PWM_GPIO, "GPIO is not in use for PWM");
|
||||
errorMessages.put(PI_NOT_SERVO_GPIO, "GPIO is not in use for servo pulses");
|
||||
errorMessages.put(PI_NOT_HCLK_GPIO, "GPIO has no hardware clock");
|
||||
errorMessages.put(PI_NOT_HPWM_GPIO, "GPIO has no hardware PWM");
|
||||
errorMessages.put(PI_BAD_HPWM_FREQ, "hardware PWM frequency not 1-125M");
|
||||
errorMessages.put(PI_BAD_HPWM_DUTY, "hardware PWM dutycycle not 0-1M");
|
||||
errorMessages.put(PI_BAD_HCLK_FREQ, "hardware clock frequency not 4689-250M");
|
||||
errorMessages.put(PI_BAD_HCLK_PASS, "need password to use hardware clock 1");
|
||||
errorMessages.put(PI_HPWM_ILLEGAL, "illegal, PWM in use for main clock");
|
||||
errorMessages.put(PI_BAD_DATABITS, "serial data bits not 1-32");
|
||||
errorMessages.put(PI_BAD_STOPBITS, "serial (half) stop bits not 2-8");
|
||||
errorMessages.put(PI_MSG_TOOBIG, "socket/pipe message too big");
|
||||
errorMessages.put(PI_BAD_MALLOC_MODE, "bad memory allocation mode");
|
||||
errorMessages.put(PI_TOO_MANY_SEGS, "too many I2C transaction segments");
|
||||
errorMessages.put(PI_BAD_I2C_SEG, "an I2C transaction segment failed");
|
||||
errorMessages.put(PI_BAD_SMBUS_CMD, "SMBus command not supported");
|
||||
errorMessages.put(PI_NOT_I2C_GPIO, "no bit bang I2C in progress on GPIO");
|
||||
errorMessages.put(PI_BAD_I2C_WLEN, "bad I2C write length");
|
||||
errorMessages.put(PI_BAD_I2C_RLEN, "bad I2C read length");
|
||||
errorMessages.put(PI_BAD_I2C_CMD, "bad I2C command");
|
||||
errorMessages.put(PI_BAD_I2C_BAUD, "bad I2C baud rate, not 50-500k");
|
||||
errorMessages.put(PI_CHAIN_LOOP_CNT, "bad chain loop count");
|
||||
errorMessages.put(PI_BAD_CHAIN_LOOP, "empty chain loop");
|
||||
errorMessages.put(PI_CHAIN_COUNTER, "too many chain counters");
|
||||
errorMessages.put(PI_BAD_CHAIN_CMD, "bad chain command");
|
||||
errorMessages.put(PI_BAD_CHAIN_DELAY, "bad chain delay micros");
|
||||
errorMessages.put(PI_CHAIN_NESTING, "chain counters nested too deeply");
|
||||
errorMessages.put(PI_CHAIN_TOO_BIG, "chain is too long");
|
||||
errorMessages.put(PI_DEPRECATED, "deprecated function removed");
|
||||
errorMessages.put(PI_BAD_SER_INVERT, "bit bang serial invert not 0 or 1");
|
||||
errorMessages.put(PI_BAD_EDGE, "bad ISR edge value, not 0-2");
|
||||
errorMessages.put(PI_BAD_ISR_INIT, "bad ISR initialisation");
|
||||
errorMessages.put(PI_BAD_FOREVER, "loop forever must be last chain command");
|
||||
errorMessages.put(PI_BAD_FILTER, "bad filter parameter");
|
||||
}
|
||||
|
||||
public static String getMessageForError(int errorCode) {
|
||||
return errorMessages.get(errorCode);
|
||||
}
|
||||
}
|
||||
@@ -1,93 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class PigpioPin extends GPIOBase {
|
||||
public static final Logger logger = new Logger(PigpioPin.class, LogGroup.General);
|
||||
private static final PigpioSocket piSocket = new PigpioSocket();
|
||||
|
||||
private final boolean isHardwarePWMPin;
|
||||
private final int pinNo;
|
||||
|
||||
private boolean hasFailedHardwarePWM;
|
||||
|
||||
public PigpioPin(int pinNo) {
|
||||
isHardwarePWMPin = pinNo == 12 || pinNo == 13 || pinNo == 17 || pinNo == 18;
|
||||
this.pinNo = pinNo;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPinNumber() {
|
||||
return pinNo;
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setStateImpl(boolean state) {
|
||||
try {
|
||||
piSocket.gpioWrite(pinNo, state);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("gpioWrite FAIL - " + e.getMessage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean shutdown() {
|
||||
setState(false);
|
||||
return true;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getStateImpl() {
|
||||
try {
|
||||
return piSocket.gpioRead(pinNo);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("gpioRead FAIL - " + e.getMessage());
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void blinkImpl(int pulseTimeMillis, int blinks) {
|
||||
try {
|
||||
piSocket.generateAndSendWaveform(pulseTimeMillis, blinks, pinNo);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Could not set blink - " + e.getMessage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void setBrightnessImpl(int brightness) {
|
||||
if (isHardwarePWMPin) {
|
||||
try {
|
||||
piSocket.hardwarePWM(pinNo, 22000, (int) (1000000 * (brightness / 100.0)));
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to hardPWM - " + e.getMessage());
|
||||
}
|
||||
} else if (!hasFailedHardwarePWM) {
|
||||
logger.warn(
|
||||
"Specified pin ("
|
||||
+ pinNo
|
||||
+ ") is not capable of hardware PWM - no action will be taken.");
|
||||
hasFailedHardwarePWM = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,39 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
public class PigpioPulse {
|
||||
int gpioOn;
|
||||
int gpioOff;
|
||||
int delayMicros;
|
||||
|
||||
/**
|
||||
* Initialises a pulse.
|
||||
*
|
||||
* @param gpioOn GPIO number to switch on at the start of the pulse. If zero, then no GPIO will be
|
||||
* switched on.
|
||||
* @param gpioOff GPIO number to switch off at the start of the pulse. If zero, then no GPIO will
|
||||
* be switched off.
|
||||
* @param delayMicros the delay in microseconds before the next pulse.
|
||||
*/
|
||||
public PigpioPulse(int gpioOn, int gpioOff, int delayMicros) {
|
||||
this.gpioOn = gpioOn != 0 ? 1 << gpioOn : 0;
|
||||
this.gpioOff = gpioOff != 0 ? 1 << gpioOff : 0;
|
||||
this.delayMicros = delayMicros;
|
||||
}
|
||||
}
|
||||
@@ -1,357 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import static org.photonvision.common.hardware.GPIO.pi.PigpioException.*;
|
||||
|
||||
import java.io.IOException;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.util.ArrayList;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
@SuppressWarnings({"SpellCheckingInspection", "unused"})
|
||||
public class PigpioSocket {
|
||||
private static final Logger logger = new Logger(PigpioSocket.class, LogGroup.General);
|
||||
private static final int PIGPIOD_MESSAGE_SIZE = 12;
|
||||
|
||||
private PigpioSocketLock commandSocket;
|
||||
private int activeWaveformID = -1;
|
||||
|
||||
/** Creates and starts a socket connection to a pigpio daemon on localhost */
|
||||
public PigpioSocket() {
|
||||
this("127.0.0.1", 8888);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates and starts a socket connection to a pigpio daemon on a remote host with the specified
|
||||
* address and port
|
||||
*
|
||||
* @param addr Address of remote pigpio daemon
|
||||
* @param port Port of remote pigpio daemon
|
||||
*/
|
||||
public PigpioSocket(String addr, int port) {
|
||||
try {
|
||||
commandSocket = new PigpioSocketLock(addr, port);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to create or connect to Pigpio Daemon socket", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Reconnects to the pigpio daemon
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void reconnect() throws PigpioException {
|
||||
try {
|
||||
commandSocket.reconnect();
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to reconnect to Pigpio Daemon socket", e);
|
||||
throw new PigpioException("reconnect", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Terminates the connection to the pigpio daemon
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void gpioTerminate() throws PigpioException {
|
||||
try {
|
||||
commandSocket.terminate();
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to terminate connection to Pigpio Daemon socket", e);
|
||||
throw new PigpioException("gpioTerminate", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Read the GPIO level
|
||||
*
|
||||
* @param pin Pin to read from
|
||||
* @return Value of the pin
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public boolean gpioRead(int pin) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_READ.value, pin);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode != 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to read GPIO pin: " + pin, e);
|
||||
throw new PigpioException("gpioRead", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Write the GPIO level
|
||||
*
|
||||
* @param pin Pin to write to
|
||||
* @param value Value to write
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void gpioWrite(int pin, boolean value) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WRITE.value, pin, value ? 1 : 0);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to write to GPIO pin: " + pin, e);
|
||||
throw new PigpioException("gpioWrite", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Clears all waveforms and any data added by calls to {@link #waveAddGeneric(ArrayList)}
|
||||
*
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void waveClear() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVCLR.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to clear waveforms", e);
|
||||
throw new PigpioException("waveClear", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Adds a number of pulses to the current waveform
|
||||
*
|
||||
* @param pulses ArrayList of pulses to add
|
||||
* @return the new total number of pulses in the current waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
private int waveAddGeneric(ArrayList<PigpioPulse> pulses) throws PigpioException {
|
||||
// pigpio wave message format
|
||||
|
||||
// I p1 0
|
||||
// I p2 0
|
||||
// I p3 pulses * 12
|
||||
// ## extension ##
|
||||
// III on/off/delay * pulses
|
||||
|
||||
if (pulses == null || pulses.isEmpty()) return 0;
|
||||
|
||||
try {
|
||||
ByteBuffer bb = ByteBuffer.allocate(pulses.size() * 12);
|
||||
bb.order(ByteOrder.LITTLE_ENDIAN);
|
||||
for (var pulse : pulses) {
|
||||
bb.putInt(pulse.gpioOn).putInt(pulse.gpioOff).putInt(pulse.delayMicros);
|
||||
}
|
||||
|
||||
int retCode =
|
||||
commandSocket.sendCmd(
|
||||
PigpioCommand.PCMD_WVAG.value,
|
||||
0,
|
||||
0,
|
||||
pulses.size() * PIGPIOD_MESSAGE_SIZE,
|
||||
bb.array());
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to add pulse(s) to waveform", e);
|
||||
throw new PigpioException("waveAddGeneric", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates pulses and adds them to the current waveform
|
||||
*
|
||||
* @param pulseTimeMillis Pulse length in milliseconds
|
||||
* @param blinks Number of times to pulse. -1 for repeat
|
||||
* @param pinNo Pin to pulse
|
||||
*/
|
||||
private void addBlinkPulsesToWaveform(int pulseTimeMillis, int blinks, int pinNo) {
|
||||
boolean repeat = blinks == -1;
|
||||
|
||||
if (blinks == 0) return;
|
||||
|
||||
if (repeat) {
|
||||
blinks = 1;
|
||||
}
|
||||
|
||||
try {
|
||||
ArrayList<PigpioPulse> pulses = new ArrayList<>();
|
||||
var startPulse = new PigpioPulse(pinNo, 0, pulseTimeMillis * 1000);
|
||||
var endPulse = new PigpioPulse(0, pinNo, pulseTimeMillis * 1000);
|
||||
|
||||
for (int i = 0; i < blinks; i++) {
|
||||
pulses.add(startPulse);
|
||||
pulses.add(endPulse);
|
||||
}
|
||||
|
||||
waveAddGeneric(pulses);
|
||||
pulses.clear();
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Generates and sends a waveform to the given pins with the specified parameters.
|
||||
*
|
||||
* @param pulseTimeMillis Pulse length in milliseconds
|
||||
* @param blinks Number of times to pulse. -1 for repeat
|
||||
* @param pins Pins to pulse
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void generateAndSendWaveform(int pulseTimeMillis, int blinks, int... pins)
|
||||
throws PigpioException {
|
||||
if (pins.length == 0) return;
|
||||
boolean repeat = blinks == -1;
|
||||
if (blinks == 0) return;
|
||||
|
||||
// stop any active waves
|
||||
waveTxStop();
|
||||
waveClear();
|
||||
|
||||
if (activeWaveformID != -1) {
|
||||
waveDelete(activeWaveformID);
|
||||
activeWaveformID = -1;
|
||||
}
|
||||
|
||||
for (int pin : pins) {
|
||||
addBlinkPulsesToWaveform(pulseTimeMillis, blinks, pin);
|
||||
}
|
||||
|
||||
int waveformId = waveCreate();
|
||||
|
||||
if (waveformId >= 0) {
|
||||
if (repeat) {
|
||||
waveSendRepeat(waveformId);
|
||||
} else {
|
||||
waveSendOnce(waveformId);
|
||||
}
|
||||
} else {
|
||||
logger.error("Failed to send wave: " + getMessageForError(waveformId));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Stops the transmission of the current waveform
|
||||
*
|
||||
* @return success
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public boolean waveTxStop() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVHLT.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode == 0;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to stop waveform", e);
|
||||
throw new PigpioException("waveTxStop", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates a waveform from the data provided by the prior calls to {@link
|
||||
* #waveAddGeneric(ArrayList)} Upon success a wave ID greater than or equal to 0 is returned
|
||||
*
|
||||
* @return ID of the created waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveCreate() throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVCRE.value);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to create new waveform", e);
|
||||
throw new PigpioException("waveCreate", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Deletes the waveform with specified wave ID
|
||||
*
|
||||
* @param waveId ID of the waveform to delete
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void waveDelete(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVDEL.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
logger.error("Failed to delete wave: " + waveId, e);
|
||||
throw new PigpioException("waveDelete", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmits the waveform with specified wave ID. The waveform is sent once
|
||||
*
|
||||
* @param waveId ID of the waveform to transmit
|
||||
* @return The number of DMA control blocks in the waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveSendOnce(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVTX.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("waveSendOnce", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Transmits the waveform with specified wave ID. The waveform cycles until cancelled (either by
|
||||
* the sending of a new waveform or {@link #waveTxStop()}
|
||||
*
|
||||
* @param waveId ID of the waveform to transmit
|
||||
* @return The number of DMA control blocks in the waveform
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public int waveSendRepeat(int waveId) throws PigpioException {
|
||||
try {
|
||||
int retCode = commandSocket.sendCmd(PigpioCommand.PCMD_WVTXR.value, waveId);
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
return retCode;
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("waveSendRepeat", e);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Starts hardware PWM on a GPIO at the specified frequency and dutycycle
|
||||
*
|
||||
* @param pin GPIO pin to start PWM on
|
||||
* @param pwmFrequency Frequency to run at (1Hz-125MHz). Frequencies above 30MHz are unlikely to
|
||||
* work
|
||||
* @param pwmDuty Duty cycle to run at (0-1,000,000)
|
||||
* @throws PigpioException on failure
|
||||
*/
|
||||
public void hardwarePWM(int pin, int pwmFrequency, int pwmDuty) throws PigpioException {
|
||||
try {
|
||||
ByteBuffer bb = ByteBuffer.allocate(4);
|
||||
bb.order(ByteOrder.LITTLE_ENDIAN);
|
||||
bb.putInt(pwmDuty);
|
||||
|
||||
int retCode =
|
||||
commandSocket.sendCmd(PigpioCommand.PCMD_HP.value, pin, pwmFrequency, 4, bb.array());
|
||||
if (retCode < 0) throw new PigpioException(retCode);
|
||||
} catch (IOException e) {
|
||||
throw new PigpioException("hardwarePWM", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,147 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.GPIO.pi;
|
||||
|
||||
import java.io.DataInputStream;
|
||||
import java.io.DataOutputStream;
|
||||
import java.io.IOException;
|
||||
import java.net.Socket;
|
||||
import java.nio.ByteBuffer;
|
||||
|
||||
/**
|
||||
* Credit to nkolban
|
||||
* https://github.com/nkolban/jpigpio/blob/master/JPigpio/src/jpigpio/SocketLock.java
|
||||
*/
|
||||
final class PigpioSocketLock {
|
||||
private static final int replyTimeoutMillis = 1000;
|
||||
|
||||
private final String addr;
|
||||
private final int port;
|
||||
|
||||
private Socket socket;
|
||||
private DataInputStream in;
|
||||
private DataOutputStream out;
|
||||
|
||||
public PigpioSocketLock(String addr, int port) throws IOException {
|
||||
this.addr = addr;
|
||||
this.port = port;
|
||||
reconnect();
|
||||
}
|
||||
|
||||
public void reconnect() throws IOException {
|
||||
socket = new Socket(addr, port);
|
||||
out = new DataOutputStream(socket.getOutputStream());
|
||||
in = new DataInputStream(socket.getInputStream());
|
||||
}
|
||||
|
||||
public void terminate() throws IOException {
|
||||
in.close();
|
||||
in = null;
|
||||
|
||||
out.flush();
|
||||
out.close();
|
||||
out = null;
|
||||
|
||||
socket.close();
|
||||
socket = null;
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, 0, 0, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, 0, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, p2, 0, b);
|
||||
}
|
||||
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2, int p3) throws IOException {
|
||||
byte[] b = {};
|
||||
return sendCmd(cmd, p1, p2, p3, b);
|
||||
}
|
||||
|
||||
/**
|
||||
* Send extended command to pigpiod and return result code
|
||||
*
|
||||
* @param cmd Command to send
|
||||
* @param p1 Command parameter 1
|
||||
* @param p2 Command parameter 2
|
||||
* @param p3 Command parameter 3 (usually length of extended data - see paramater ext)
|
||||
* @param ext Array of bytes containing extended data
|
||||
* @return Command result code
|
||||
* @throws IOException in case of network connection error
|
||||
*/
|
||||
@SuppressWarnings("UnusedAssignment")
|
||||
public synchronized int sendCmd(int cmd, int p1, int p2, int p3, byte[] ext) throws IOException {
|
||||
ByteBuffer bb = ByteBuffer.allocate(16 + ext.length);
|
||||
|
||||
bb.putInt(Integer.reverseBytes(cmd));
|
||||
bb.putInt(Integer.reverseBytes(p1));
|
||||
bb.putInt(Integer.reverseBytes(p2));
|
||||
bb.putInt(Integer.reverseBytes(p3));
|
||||
|
||||
if (ext.length > 0) {
|
||||
bb.put(ext);
|
||||
}
|
||||
|
||||
out.write(bb.array());
|
||||
out.flush();
|
||||
|
||||
int w = replyTimeoutMillis;
|
||||
int a = in.available();
|
||||
|
||||
// if by any chance there is no response from pigpiod, then wait up to
|
||||
// specified timeout
|
||||
while (w > 0 && a < 16) {
|
||||
w -= 10;
|
||||
try {
|
||||
Thread.sleep(10);
|
||||
} catch (InterruptedException ignored) {
|
||||
}
|
||||
a = in.available();
|
||||
}
|
||||
|
||||
// throw exception if response from pigpiod has not arrived yet
|
||||
if (in.available() < 16) {
|
||||
throw new IOException(
|
||||
"Timeout: No response from pigpio daemon within " + replyTimeoutMillis + " ms.");
|
||||
}
|
||||
|
||||
int resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // ignore response
|
||||
resp = Integer.reverseBytes(in.readInt()); // contains error or response
|
||||
return resp;
|
||||
}
|
||||
|
||||
/**
|
||||
* Read all remaining bytes coming from pigpiod
|
||||
*
|
||||
* @param data Array to store read bytes.
|
||||
* @throws IOException if unable to read from network
|
||||
*/
|
||||
public void readBytes(byte[] data) throws IOException {
|
||||
in.readFully(data);
|
||||
}
|
||||
}
|
||||
@@ -17,18 +17,24 @@
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import com.diozero.api.DeviceMode;
|
||||
import com.diozero.internal.spi.NativeDeviceFactoryInterface;
|
||||
import com.diozero.sbc.BoardPinInfo;
|
||||
import com.diozero.sbc.DeviceFactoryHelper;
|
||||
import edu.wpi.first.networktables.IntegerPublisher;
|
||||
import edu.wpi.first.networktables.IntegerSubscriber;
|
||||
import java.io.IOException;
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import java.util.HashSet;
|
||||
import java.util.List;
|
||||
import java.util.Set;
|
||||
import java.util.function.Supplier;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.configuration.HardwareSettings;
|
||||
import org.photonvision.common.dataflow.networktables.NTDataChangeListener;
|
||||
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioSocket;
|
||||
import org.photonvision.common.hardware.gpio.CustomAdapter;
|
||||
import org.photonvision.common.hardware.gpio.CustomDeviceFactory;
|
||||
import org.photonvision.common.hardware.metrics.MetricsManager;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
@@ -59,8 +65,6 @@ public class HardwareManager {
|
||||
|
||||
public final VisionLED visionLED; // May be null if no LED is specified
|
||||
|
||||
private final PigpioSocket pigpioSocket; // will be null unless on Raspi
|
||||
|
||||
public static HardwareManager getInstance() {
|
||||
if (instance == null) {
|
||||
var conf = ConfigManager.getInstance().getConfig();
|
||||
@@ -88,32 +92,44 @@ public class HardwareManager {
|
||||
NetworkTablesManager.getInstance().kRootTable.getIntegerTopic("ledModeState").publish();
|
||||
ledModeState.set(VisionLEDMode.kDefault.value);
|
||||
|
||||
CustomGPIO.setConfig(hardwareConfig);
|
||||
// Device factory is lazy to prevent creating one if it will go unused.
|
||||
Supplier<NativeDeviceFactoryInterface> lazyDeviceFactory =
|
||||
new Supplier<NativeDeviceFactoryInterface>() {
|
||||
NativeDeviceFactoryInterface deviceFactory = null;
|
||||
|
||||
if (Platform.isRaspberryPi()) {
|
||||
pigpioSocket = new PigpioSocket();
|
||||
} else {
|
||||
pigpioSocket = null;
|
||||
}
|
||||
@Override
|
||||
public NativeDeviceFactoryInterface get() {
|
||||
if (deviceFactory == null) {
|
||||
if (hardwareConfig.hasGPIOCommandsConfigured()) {
|
||||
deviceFactory = HardwareManager.configureCustomGPIO(hardwareConfig);
|
||||
} else {
|
||||
deviceFactory = DeviceFactoryHelper.getNativeDeviceFactory();
|
||||
}
|
||||
}
|
||||
|
||||
return deviceFactory;
|
||||
}
|
||||
};
|
||||
|
||||
statusLED =
|
||||
hardwareConfig.statusRGBPins.size() == 3
|
||||
? new StatusLED(hardwareConfig.statusRGBPins)
|
||||
? new StatusLED(
|
||||
lazyDeviceFactory.get(),
|
||||
hardwareConfig.statusRGBPins,
|
||||
hardwareConfig.statusRGBActiveHigh)
|
||||
: null;
|
||||
|
||||
if (statusLED != null) {
|
||||
TimedTaskManager.getInstance().addTask("StatusLEDUpdate", this::statusLEDUpdate, 150);
|
||||
}
|
||||
|
||||
var hasBrightnessRange = hardwareConfig.ledBrightnessRange.size() == 2;
|
||||
visionLED =
|
||||
hardwareConfig.ledPins.isEmpty()
|
||||
? null
|
||||
: new VisionLED(
|
||||
lazyDeviceFactory.get(),
|
||||
hardwareConfig.ledPins,
|
||||
hardwareConfig.ledsCanDim,
|
||||
hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(0) : 0,
|
||||
hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(1) : 100,
|
||||
pigpioSocket,
|
||||
hardwareConfig.ledPWMFrequency,
|
||||
ledModeState::set);
|
||||
|
||||
ledModeListener =
|
||||
@@ -135,6 +151,33 @@ public class HardwareManager {
|
||||
// if (Platform.isLinux()) MetricsPublisher.getInstance().startTask();
|
||||
}
|
||||
|
||||
public static NativeDeviceFactoryInterface configureCustomGPIO(HardwareConfig hardwareConfig) {
|
||||
// Create a new adapter and device factory using the commands from hardwareConfig
|
||||
CustomAdapter adapter =
|
||||
new CustomAdapter(
|
||||
hardwareConfig.getGPIOCommand,
|
||||
hardwareConfig.setGPIOCommand,
|
||||
hardwareConfig.setPWMCommand,
|
||||
hardwareConfig.setPWMFrequencyCommand,
|
||||
hardwareConfig.setPWMFrequencyCommand);
|
||||
CustomDeviceFactory deviceFactory = new CustomDeviceFactory(adapter);
|
||||
BoardPinInfo pinInfo = deviceFactory.getBoardPinInfo();
|
||||
|
||||
// Populate pin info according to hardware config
|
||||
for (int pin : hardwareConfig.ledPins) {
|
||||
if (hardwareConfig.ledsCanDim) {
|
||||
pinInfo.addGpioPinInfo(pin, pin, List.of(DeviceMode.PWM_OUTPUT, DeviceMode.DIGITAL_OUTPUT));
|
||||
} else {
|
||||
pinInfo.addGpioPinInfo(pin, pin, List.of(DeviceMode.DIGITAL_OUTPUT));
|
||||
}
|
||||
}
|
||||
for (int pin : hardwareConfig.statusRGBPins) {
|
||||
pinInfo.addGpioPinInfo(pin, pin, List.of(DeviceMode.DIGITAL_OUTPUT));
|
||||
}
|
||||
|
||||
return deviceFactory;
|
||||
}
|
||||
|
||||
public void setBrightnessPercent(int percent) {
|
||||
if (percent != hardwareSettings.ledBrightnessPercentage) {
|
||||
hardwareSettings.ledBrightnessPercentage = percent;
|
||||
@@ -170,59 +213,51 @@ public class HardwareManager {
|
||||
|
||||
// API's supporting status LEDs
|
||||
|
||||
private Map<String, Boolean> pipelineTargets = new HashMap<String, Boolean>();
|
||||
private Set<String> pipelineTargets = new HashSet<String>();
|
||||
private boolean ntConnected = false;
|
||||
private boolean systemRunning = false;
|
||||
private int blinkCounter = 0;
|
||||
|
||||
public void setTargetsVisibleStatus(String uniqueName, boolean hasTargets) {
|
||||
pipelineTargets.put(uniqueName, hasTargets);
|
||||
if (hasTargets) {
|
||||
pipelineTargets.add(uniqueName);
|
||||
} else {
|
||||
pipelineTargets.remove(uniqueName);
|
||||
}
|
||||
updateStatus();
|
||||
}
|
||||
|
||||
public void setNTConnected(boolean isConnected) {
|
||||
this.ntConnected = isConnected;
|
||||
ntConnected = isConnected;
|
||||
updateStatus();
|
||||
}
|
||||
|
||||
public void setRunning(boolean isRunning) {
|
||||
this.systemRunning = isRunning;
|
||||
}
|
||||
|
||||
private void statusLEDUpdate() {
|
||||
// make blinky
|
||||
boolean blinky = ((blinkCounter % 3) > 0);
|
||||
|
||||
// check if any pipeline has a visible target
|
||||
boolean anyTarget = false;
|
||||
for (var t : this.pipelineTargets.values()) {
|
||||
if (t) {
|
||||
anyTarget = true;
|
||||
}
|
||||
public void setError(PhotonStatus status) {
|
||||
if (status == null || !status.isError()) {
|
||||
updateStatus();
|
||||
} else if (statusLED != null) {
|
||||
statusLED.setStatus(status);
|
||||
}
|
||||
}
|
||||
|
||||
if (this.systemRunning) {
|
||||
if (!this.ntConnected) {
|
||||
if (anyTarget) {
|
||||
// Blue Flashing
|
||||
statusLED.setRGB(false, false, blinky);
|
||||
} else {
|
||||
// Yellow flashing
|
||||
statusLED.setRGB(blinky, blinky, false);
|
||||
}
|
||||
private void updateStatus() {
|
||||
if (statusLED == null) {
|
||||
return;
|
||||
}
|
||||
PhotonStatus status;
|
||||
boolean anyTarget = !pipelineTargets.isEmpty();
|
||||
if (ntConnected) {
|
||||
if (anyTarget) {
|
||||
status = PhotonStatus.NT_CONNECTED_TARGETS_VISIBLE;
|
||||
} else {
|
||||
if (anyTarget) {
|
||||
// Blue
|
||||
statusLED.setRGB(false, false, blinky);
|
||||
} else {
|
||||
// blinky green
|
||||
statusLED.setRGB(false, blinky, false);
|
||||
}
|
||||
status = PhotonStatus.NT_CONNECTED_TARGETS_MISSING;
|
||||
}
|
||||
} else {
|
||||
// Faulted, not running... blinky red
|
||||
statusLED.setRGB(blinky, false, false);
|
||||
if (anyTarget) {
|
||||
status = PhotonStatus.NT_DISCONNECTED_TARGETS_VISIBLE;
|
||||
} else {
|
||||
status = PhotonStatus.NT_DISCONNECTED_TARGETS_MISSING;
|
||||
}
|
||||
}
|
||||
|
||||
blinkCounter++;
|
||||
statusLED.setStatus(status);
|
||||
}
|
||||
|
||||
public void publishMetrics() {
|
||||
|
||||
@@ -0,0 +1,43 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
public enum PhotonStatus {
|
||||
// Nominal states
|
||||
NT_CONNECTED_TARGETS_VISIBLE,
|
||||
NT_CONNECTED_TARGETS_MISSING,
|
||||
NT_DISCONNECTED_TARGETS_VISIBLE,
|
||||
NT_DISCONNECTED_TARGETS_MISSING,
|
||||
|
||||
// Error states
|
||||
GENERIC_ERROR(true);
|
||||
|
||||
final boolean error;
|
||||
|
||||
PhotonStatus() {
|
||||
this(false);
|
||||
}
|
||||
|
||||
PhotonStatus(boolean error) {
|
||||
this.error = error;
|
||||
}
|
||||
|
||||
boolean isError() {
|
||||
return this.error;
|
||||
}
|
||||
}
|
||||
@@ -17,17 +17,21 @@
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import com.diozero.devices.LED;
|
||||
import com.diozero.internal.spi.NativeDeviceFactoryInterface;
|
||||
import java.util.List;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioPin;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
|
||||
public class StatusLED {
|
||||
public final GPIOBase redLED;
|
||||
public final GPIOBase greenLED;
|
||||
public final GPIOBase blueLED;
|
||||
public class StatusLED implements AutoCloseable {
|
||||
public final LED redLED;
|
||||
public final LED greenLED;
|
||||
public final LED blueLED;
|
||||
protected int blinkCounter;
|
||||
|
||||
public StatusLED(List<Integer> statusLedPins) {
|
||||
protected PhotonStatus status = PhotonStatus.GENERIC_ERROR;
|
||||
|
||||
public StatusLED(
|
||||
NativeDeviceFactoryInterface deviceFactory, List<Integer> statusLedPins, boolean activeHigh) {
|
||||
// fill unassigned pins with -1 to disable
|
||||
if (statusLedPins.size() != 3) {
|
||||
for (int i = 0; i < 3 - statusLedPins.size(); i++) {
|
||||
@@ -35,24 +39,53 @@ public class StatusLED {
|
||||
}
|
||||
}
|
||||
|
||||
if (Platform.isRaspberryPi()) {
|
||||
redLED = new PigpioPin(statusLedPins.get(0));
|
||||
greenLED = new PigpioPin(statusLedPins.get(1));
|
||||
blueLED = new PigpioPin(statusLedPins.get(2));
|
||||
} else {
|
||||
redLED = new CustomGPIO(statusLedPins.get(0));
|
||||
greenLED = new CustomGPIO(statusLedPins.get(1));
|
||||
blueLED = new CustomGPIO(statusLedPins.get(2));
|
||||
}
|
||||
// Outputs are active-low for a common-anode RGB LED
|
||||
redLED = new LED(deviceFactory, statusLedPins.get(0), activeHigh, false);
|
||||
greenLED = new LED(deviceFactory, statusLedPins.get(1), activeHigh, false);
|
||||
blueLED = new LED(deviceFactory, statusLedPins.get(2), activeHigh, false);
|
||||
|
||||
TimedTaskManager.getInstance().addTask("StatusLEDUpdate", this::updateLED, 150);
|
||||
}
|
||||
|
||||
public void setRGB(boolean r, boolean g, boolean b) {
|
||||
// Outputs are active-low, so invert the level applied
|
||||
redLED.setState(!r);
|
||||
redLED.setBrightness(r ? 0 : 100);
|
||||
greenLED.setState(!g);
|
||||
greenLED.setBrightness(g ? 0 : 100);
|
||||
blueLED.setState(!b);
|
||||
blueLED.setBrightness(b ? 0 : 100);
|
||||
protected void setRGB(boolean r, boolean g, boolean b) {
|
||||
redLED.setOn(r);
|
||||
greenLED.setOn(g);
|
||||
blueLED.setOn(b);
|
||||
}
|
||||
|
||||
public void setStatus(PhotonStatus status) {
|
||||
this.status = status;
|
||||
}
|
||||
|
||||
protected void updateLED() {
|
||||
boolean blink = blinkCounter > 0;
|
||||
|
||||
switch (status) {
|
||||
case NT_CONNECTED_TARGETS_VISIBLE ->
|
||||
// Blue
|
||||
setRGB(false, false, true);
|
||||
case NT_CONNECTED_TARGETS_MISSING ->
|
||||
// Blinking Green
|
||||
setRGB(false, blink, false);
|
||||
case NT_DISCONNECTED_TARGETS_VISIBLE ->
|
||||
// Blinking Blue
|
||||
setRGB(false, false, blink);
|
||||
case NT_DISCONNECTED_TARGETS_MISSING ->
|
||||
// Blinking Yellow
|
||||
setRGB(blink, blink, false);
|
||||
case GENERIC_ERROR ->
|
||||
// Blinking Red
|
||||
setRGB(blink, false, false);
|
||||
}
|
||||
|
||||
blinkCounter++;
|
||||
blinkCounter %= 3;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
redLED.close();
|
||||
greenLED.close();
|
||||
blueLED.close();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -17,54 +17,62 @@
|
||||
|
||||
package org.photonvision.common.hardware;
|
||||
|
||||
import com.diozero.devices.LED;
|
||||
import com.diozero.devices.PwmLed;
|
||||
import com.diozero.internal.spi.NativeDeviceFactoryInterface;
|
||||
import com.diozero.sbc.BoardPinInfo;
|
||||
import edu.wpi.first.networktables.NetworkTableEvent;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.Consumer;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioException;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioPin;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioSocket;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TimedTaskManager;
|
||||
import org.photonvision.common.util.math.MathUtils;
|
||||
|
||||
public class VisionLED {
|
||||
public class VisionLED implements AutoCloseable {
|
||||
private static final Logger logger = new Logger(VisionLED.class, LogGroup.VisionModule);
|
||||
private static final String blinkTaskID = "VisionLEDBlink";
|
||||
|
||||
private final int[] ledPins;
|
||||
private final List<GPIOBase> visionLEDs = new ArrayList<>();
|
||||
private final List<LED> visionLEDs = new ArrayList<>();
|
||||
private final List<PwmLed> dimmableVisionLEDs = new ArrayList<>();
|
||||
private final int brightnessMin;
|
||||
private final int brightnessMax;
|
||||
private final PigpioSocket pigpioSocket;
|
||||
|
||||
private VisionLEDMode currentLedMode = VisionLEDMode.kDefault;
|
||||
private BooleanSupplier pipelineModeSupplier;
|
||||
|
||||
private int mappedBrightnessPercentage;
|
||||
private float mappedBrightness = 0.0f;
|
||||
|
||||
private final Consumer<Integer> modeConsumer;
|
||||
|
||||
public VisionLED(
|
||||
NativeDeviceFactoryInterface deviceFactory,
|
||||
List<Integer> ledPins,
|
||||
boolean ledsCanDim,
|
||||
int brightnessMin,
|
||||
int brightnessMax,
|
||||
PigpioSocket pigpioSocket,
|
||||
int pwmFrequency,
|
||||
Consumer<Integer> visionLEDmode) {
|
||||
this.brightnessMin = brightnessMin;
|
||||
this.brightnessMax = brightnessMax;
|
||||
this.pigpioSocket = pigpioSocket;
|
||||
this.modeConsumer = visionLEDmode;
|
||||
this.ledPins = ledPins.stream().mapToInt(i -> i).toArray();
|
||||
if (pwmFrequency > 0) {
|
||||
deviceFactory.setBoardPwmFrequency(pwmFrequency);
|
||||
}
|
||||
BoardPinInfo boardPinInfo = deviceFactory.getBoardPinInfo();
|
||||
ledPins.forEach(
|
||||
pin -> {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
visionLEDs.add(new PigpioPin(pin));
|
||||
if (ledsCanDim && boardPinInfo.getByPwmOrGpioNumberOrThrow(pin).isPwmOutputSupported()) {
|
||||
PwmLed led = new PwmLed(deviceFactory, pin);
|
||||
if (pwmFrequency > 0) {
|
||||
led.setPwmFrequency(pwmFrequency);
|
||||
}
|
||||
dimmableVisionLEDs.add(led);
|
||||
} else {
|
||||
visionLEDs.add(new CustomGPIO(pin));
|
||||
visionLEDs.add(new LED(deviceFactory, pin));
|
||||
}
|
||||
});
|
||||
pipelineModeSupplier = () -> false;
|
||||
@@ -75,7 +83,8 @@ public class VisionLED {
|
||||
}
|
||||
|
||||
public void setBrightness(int percentage) {
|
||||
mappedBrightnessPercentage = MathUtils.map(percentage, 0, 100, brightnessMin, brightnessMax);
|
||||
mappedBrightness =
|
||||
(float) (MathUtils.map(percentage, 0.0, 100.0, brightnessMin, brightnessMax) / 100.0);
|
||||
setInternal(currentLedMode, false);
|
||||
}
|
||||
|
||||
@@ -87,42 +96,32 @@ public class VisionLED {
|
||||
}
|
||||
|
||||
private void blinkImpl(int pulseLengthMillis, int blinkCount) {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
try {
|
||||
setStateImpl(false); // hack to ensure hardware PWM has stopped before trying to blink
|
||||
pigpioSocket.generateAndSendWaveform(pulseLengthMillis, blinkCount, ledPins);
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to blink!", e);
|
||||
} catch (NullPointerException e) {
|
||||
logger.error("Failed to blink, pigpio internal issue!", e);
|
||||
}
|
||||
} else {
|
||||
for (GPIOBase led : visionLEDs) {
|
||||
led.blink(pulseLengthMillis, blinkCount);
|
||||
}
|
||||
}
|
||||
TimedTaskManager.getInstance().cancelTask(blinkTaskID);
|
||||
AtomicInteger blinks = new AtomicInteger();
|
||||
TimedTaskManager.getInstance()
|
||||
.addTask(
|
||||
blinkTaskID,
|
||||
() -> {
|
||||
for (LED led : visionLEDs) {
|
||||
led.toggle();
|
||||
}
|
||||
for (PwmLed led : dimmableVisionLEDs) {
|
||||
led.setValue(mappedBrightness - led.getValue());
|
||||
}
|
||||
if (blinks.incrementAndGet() >= blinkCount * 2) {
|
||||
TimedTaskManager.getInstance().cancelTask(blinkTaskID);
|
||||
}
|
||||
},
|
||||
pulseLengthMillis);
|
||||
}
|
||||
|
||||
private void setStateImpl(boolean state) {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
try {
|
||||
// stop any active blink
|
||||
pigpioSocket.waveTxStop();
|
||||
} catch (PigpioException e) {
|
||||
logger.error("Failed to stop blink!", e);
|
||||
} catch (NullPointerException e) {
|
||||
logger.error("Failed to blink, pigpio internal issue!", e);
|
||||
}
|
||||
TimedTaskManager.getInstance().cancelTask(blinkTaskID);
|
||||
for (LED led : visionLEDs) {
|
||||
led.setOn(state);
|
||||
}
|
||||
try {
|
||||
// if the user has set an LED brightness other than 100%, use that instead
|
||||
if (mappedBrightnessPercentage == 100 || !state) {
|
||||
visionLEDs.forEach((led) -> led.setState(state));
|
||||
} else {
|
||||
visionLEDs.forEach((led) -> led.setBrightness(mappedBrightnessPercentage));
|
||||
}
|
||||
} catch (NullPointerException e) {
|
||||
logger.error("Failed to blink, pigpio internal issue!", e);
|
||||
for (PwmLed led : dimmableVisionLEDs) {
|
||||
led.setValue(mappedBrightness);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -152,28 +151,42 @@ public class VisionLED {
|
||||
}
|
||||
|
||||
private void setInternal(VisionLEDMode newLedMode, boolean fromNT) {
|
||||
// LED state has three different sources:
|
||||
// Pipeline, which supplies the default LED state
|
||||
// NT, which supplies the user override LED state
|
||||
// Internal methods, which supply special actions such as the startup blink
|
||||
//
|
||||
// LED state is set with this method when the pipeline changes, NT state changes,
|
||||
// or an internal request is received.
|
||||
|
||||
var lastLedMode = currentLedMode;
|
||||
|
||||
if (fromNT) {
|
||||
if (fromNT || currentLedMode == VisionLEDMode.kDefault) {
|
||||
switch (newLedMode) {
|
||||
case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean());
|
||||
case kOff -> setStateImpl(false);
|
||||
case kOn -> setStateImpl(true);
|
||||
case kBlink -> blinkImpl(85, -1);
|
||||
}
|
||||
}
|
||||
|
||||
if (fromNT) {
|
||||
currentLedMode = newLedMode;
|
||||
logger.info(
|
||||
"Changing LED mode from \"" + lastLedMode.toString() + "\" to \"" + newLedMode + "\"");
|
||||
} else {
|
||||
if (currentLedMode == VisionLEDMode.kDefault) {
|
||||
switch (newLedMode) {
|
||||
case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean());
|
||||
case kOff -> setStateImpl(false);
|
||||
case kOn -> setStateImpl(true);
|
||||
case kBlink -> blinkImpl(85, -1);
|
||||
}
|
||||
}
|
||||
logger.info("Changing LED internal state to " + newLedMode.toString());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
TimedTaskManager.getInstance().cancelTask(blinkTaskID);
|
||||
for (LED led : visionLEDs) {
|
||||
led.close();
|
||||
}
|
||||
for (PwmLed led : dimmableVisionLEDs) {
|
||||
led.close();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,87 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.ShellExec;
|
||||
|
||||
public class CustomAdapter {
|
||||
private static final Logger logger = new Logger(CustomAdapter.class, LogGroup.General);
|
||||
private static final ThreadLocal<ShellExec> runCommand =
|
||||
ThreadLocal.withInitial(() -> new ShellExec(true, true));
|
||||
|
||||
protected final String getGPIOCommand;
|
||||
protected final String setGPIOCommand;
|
||||
protected final String setPWMCommand;
|
||||
protected final String setPWMFrequencyCommand;
|
||||
protected final String releaseGPIOCommand;
|
||||
|
||||
public CustomAdapter(
|
||||
String getGPIOCommand,
|
||||
String setGPIOCommand,
|
||||
String setPWMCommand,
|
||||
String setPWMFrequencyCommand,
|
||||
String releaseGPIOCommand) {
|
||||
this.getGPIOCommand = getGPIOCommand;
|
||||
this.setGPIOCommand = setGPIOCommand;
|
||||
this.setPWMCommand = setPWMCommand;
|
||||
this.setPWMFrequencyCommand = setPWMFrequencyCommand;
|
||||
this.releaseGPIOCommand = releaseGPIOCommand;
|
||||
}
|
||||
|
||||
protected static String execute(String command) {
|
||||
try {
|
||||
runCommand.get().executeBashCommand(command);
|
||||
} catch (Exception e) {
|
||||
logger.error("Exception caught running GPIO command \"" + command + "\"", e);
|
||||
return "";
|
||||
}
|
||||
return runCommand.get().getOutput();
|
||||
}
|
||||
|
||||
public boolean getGPIO(int gpio) {
|
||||
return Boolean.parseBoolean(
|
||||
execute(getGPIOCommand.replace("{p}", Integer.toString(gpio))).trim());
|
||||
}
|
||||
|
||||
public void setGPIO(int gpio, boolean state) {
|
||||
execute(
|
||||
setGPIOCommand
|
||||
.replace("{p}", Integer.toString(gpio))
|
||||
.replace("{s}", Boolean.toString(state)));
|
||||
}
|
||||
|
||||
public void setPWM(int gpio, double value) {
|
||||
execute(
|
||||
setPWMCommand
|
||||
.replace("{p}", Integer.toString(gpio))
|
||||
.replace("{v}", Double.toString(value)));
|
||||
}
|
||||
|
||||
public void setPwmFrequency(int gpio, int frequency) {
|
||||
execute(
|
||||
setPWMFrequencyCommand
|
||||
.replace("{p}", Integer.toString(gpio))
|
||||
.replace("{f}", Integer.toString(frequency)));
|
||||
}
|
||||
|
||||
public void releaseGPIO(int gpio) {
|
||||
execute(releaseGPIOCommand.replace("{p}", Integer.toString(gpio)));
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,201 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import com.diozero.api.DeviceMode;
|
||||
import com.diozero.api.GpioEventTrigger;
|
||||
import com.diozero.api.GpioPullUpDown;
|
||||
import com.diozero.api.I2CConstants.AddressSize;
|
||||
import com.diozero.api.PinInfo;
|
||||
import com.diozero.api.RuntimeIOException;
|
||||
import com.diozero.api.SerialConstants.DataBits;
|
||||
import com.diozero.api.SerialConstants.Parity;
|
||||
import com.diozero.api.SerialConstants.StopBits;
|
||||
import com.diozero.api.SpiClockMode;
|
||||
import com.diozero.internal.spi.AnalogInputDeviceInterface;
|
||||
import com.diozero.internal.spi.AnalogOutputDeviceInterface;
|
||||
import com.diozero.internal.spi.BaseNativeDeviceFactory;
|
||||
import com.diozero.internal.spi.GpioDigitalInputDeviceInterface;
|
||||
import com.diozero.internal.spi.GpioDigitalInputOutputDeviceInterface;
|
||||
import com.diozero.internal.spi.GpioDigitalOutputDeviceInterface;
|
||||
import com.diozero.internal.spi.InternalI2CDeviceInterface;
|
||||
import com.diozero.internal.spi.InternalPwmOutputDeviceInterface;
|
||||
import com.diozero.internal.spi.InternalSerialDeviceInterface;
|
||||
import com.diozero.internal.spi.InternalServoDeviceInterface;
|
||||
import com.diozero.internal.spi.InternalSpiDeviceInterface;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class CustomDeviceFactory extends BaseNativeDeviceFactory {
|
||||
public static final String DEVICE_NAME = "Custom";
|
||||
|
||||
public static final String GET_GPIO_PROP = "diozero.custom.getGPIO";
|
||||
public static final String SET_GPIO_PROP = "diozero.custom.setGPIO";
|
||||
public static final String SET_PWM_PROP = "diozero.custom.setPWM";
|
||||
public static final String SET_PWM_FREQUENCY_PROP = "diozero.custom.setPWMFrequency";
|
||||
public static final String RELEASE_GPIO_PROP = "diozero.custom.releaseGPIO";
|
||||
|
||||
private static final Logger logger = new Logger(CustomDeviceFactory.class, LogGroup.General);
|
||||
|
||||
public final CustomAdapter adapter;
|
||||
|
||||
public CustomDeviceFactory(CustomAdapter adapter) {
|
||||
this.adapter = adapter;
|
||||
}
|
||||
|
||||
public CustomDeviceFactory() {
|
||||
String getGPIOCommand = System.getProperty(GET_GPIO_PROP, "");
|
||||
String setGPIOCommand = System.getProperty(SET_GPIO_PROP, "");
|
||||
String setPWMCommand = System.getProperty(SET_PWM_PROP, "");
|
||||
String setPWMFrequencyCommand = System.getProperty(SET_PWM_FREQUENCY_PROP, "");
|
||||
String releaseGPIOCommand = System.getProperty(RELEASE_GPIO_PROP, "");
|
||||
|
||||
this.adapter =
|
||||
new CustomAdapter(
|
||||
getGPIOCommand,
|
||||
setGPIOCommand,
|
||||
setPWMCommand,
|
||||
setPWMFrequencyCommand,
|
||||
releaseGPIOCommand);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void start() {}
|
||||
|
||||
@Override
|
||||
public void shutdown() {}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return DEVICE_NAME;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getGpioValue(int gpio) {
|
||||
return adapter.getGPIO(gpio) ? 1 : 0;
|
||||
}
|
||||
|
||||
@Override
|
||||
public DeviceMode getGpioMode(int gpio) {
|
||||
throw new UnsupportedOperationException("GPIO mode can not be retrieved");
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getBoardPwmFrequency() {
|
||||
throw new UnsupportedOperationException("PWM frequency cannot be retrieved");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBoardPwmFrequency(int pwmFrequency) {
|
||||
logger.warn("Setting PWM frequency is not implemented");
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getBoardServoFrequency() {
|
||||
throw new UnsupportedOperationException("Servo frequency cannot be retrieved");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setBoardServoFrequency(int servoFrequency) {
|
||||
logger.warn("Setting servo frequency is not implemented");
|
||||
}
|
||||
|
||||
@Override
|
||||
public GpioDigitalInputDeviceInterface createDigitalInputDevice(
|
||||
String key, PinInfo pinInfo, GpioPullUpDown pud, GpioEventTrigger trigger) {
|
||||
return new CustomDigitalInputDevice(this, key, pinInfo.getDeviceNumber(), pud, trigger);
|
||||
}
|
||||
|
||||
@Override
|
||||
public GpioDigitalOutputDeviceInterface createDigitalOutputDevice(
|
||||
String key, PinInfo pinInfo, boolean initialValue) {
|
||||
return new CustomDigitalOutputDevice(this, key, pinInfo.getDeviceNumber(), initialValue);
|
||||
}
|
||||
|
||||
@Override
|
||||
public GpioDigitalInputOutputDeviceInterface createDigitalInputOutputDevice(
|
||||
String key, PinInfo pinInfo, DeviceMode mode) {
|
||||
return new CustomDigitalInputOutputDevice(this, key, pinInfo.getDeviceNumber(), mode);
|
||||
}
|
||||
|
||||
@Override
|
||||
public InternalPwmOutputDeviceInterface createPwmOutputDevice(
|
||||
String key, PinInfo pinInfo, int pwmFrequency, float initialValue) {
|
||||
return new CustomPwmOutputDevice(
|
||||
this, key, pinInfo.getDeviceNumber(), pwmFrequency, initialValue);
|
||||
}
|
||||
|
||||
@Override
|
||||
public InternalServoDeviceInterface createServoDevice(
|
||||
String key,
|
||||
PinInfo pinInfo,
|
||||
int frequencyHz,
|
||||
int minPulseWidthUs,
|
||||
int maxPulseWidthUs,
|
||||
int initialPulseWidthUs) {
|
||||
throw new UnsupportedOperationException(
|
||||
"Servo devices are not supported by this device factory");
|
||||
}
|
||||
|
||||
@Override
|
||||
public AnalogInputDeviceInterface createAnalogInputDevice(String key, PinInfo pinInfo) {
|
||||
throw new UnsupportedOperationException(
|
||||
"Analog inputs are not supported by this device factory");
|
||||
}
|
||||
|
||||
@Override
|
||||
public AnalogOutputDeviceInterface createAnalogOutputDevice(
|
||||
String key, PinInfo pinInfo, float initialValue) {
|
||||
throw new UnsupportedOperationException(
|
||||
"Analog outputs are not supported by this device factory");
|
||||
}
|
||||
|
||||
@Override
|
||||
public InternalSpiDeviceInterface createSpiDevice(
|
||||
String key,
|
||||
int controller,
|
||||
int chipSelect,
|
||||
int frequency,
|
||||
SpiClockMode spiClockMode,
|
||||
boolean lsbFirst)
|
||||
throws RuntimeIOException {
|
||||
throw new UnsupportedOperationException("SPI devices are not supported by this device factory");
|
||||
}
|
||||
|
||||
@Override
|
||||
public InternalI2CDeviceInterface createI2CDevice(
|
||||
String key, int controller, int address, AddressSize addressSize) throws RuntimeIOException {
|
||||
throw new UnsupportedOperationException("I2C devices are not supported by this device factory");
|
||||
}
|
||||
|
||||
@Override
|
||||
public InternalSerialDeviceInterface createSerialDevice(
|
||||
String key,
|
||||
String deviceFilename,
|
||||
int baud,
|
||||
DataBits dataBits,
|
||||
StopBits stopBits,
|
||||
Parity parity,
|
||||
boolean readBlocking,
|
||||
int minReadChars,
|
||||
int readTimeoutMillis)
|
||||
throws RuntimeIOException {
|
||||
throw new UnsupportedOperationException(
|
||||
"Serial communication is not supported by this device factory");
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,63 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import com.diozero.api.DigitalInputEvent;
|
||||
import com.diozero.api.GpioEventTrigger;
|
||||
import com.diozero.api.GpioPullUpDown;
|
||||
import com.diozero.api.RuntimeIOException;
|
||||
import com.diozero.internal.spi.AbstractInputDevice;
|
||||
import com.diozero.internal.spi.GpioDigitalInputDeviceInterface;
|
||||
|
||||
public class CustomDigitalInputDevice extends AbstractInputDevice<DigitalInputEvent>
|
||||
implements GpioDigitalInputDeviceInterface {
|
||||
protected final CustomAdapter adapter;
|
||||
protected final int gpio;
|
||||
|
||||
public CustomDigitalInputDevice(
|
||||
CustomDeviceFactory deviceFactory,
|
||||
String key,
|
||||
int gpio,
|
||||
GpioPullUpDown pud,
|
||||
GpioEventTrigger trigger) {
|
||||
super(key, deviceFactory);
|
||||
|
||||
adapter = deviceFactory.adapter;
|
||||
this.gpio = gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getValue() throws RuntimeIOException {
|
||||
return adapter.getGPIO(gpio);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getGpio() {
|
||||
return gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setDebounceTimeMillis(int debounceTime) {
|
||||
throw new UnsupportedOperationException("Debounce is not supported");
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void closeDevice() throws RuntimeIOException {
|
||||
adapter.releaseGPIO(gpio);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,71 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import com.diozero.api.DeviceMode;
|
||||
import com.diozero.api.DigitalInputEvent;
|
||||
import com.diozero.api.RuntimeIOException;
|
||||
import com.diozero.internal.spi.AbstractInputDevice;
|
||||
import com.diozero.internal.spi.GpioDigitalInputOutputDeviceInterface;
|
||||
|
||||
public class CustomDigitalInputOutputDevice extends AbstractInputDevice<DigitalInputEvent>
|
||||
implements GpioDigitalInputOutputDeviceInterface {
|
||||
protected final CustomAdapter adapter;
|
||||
protected final int gpio;
|
||||
private boolean outputValue = false;
|
||||
|
||||
public CustomDigitalInputOutputDevice(
|
||||
CustomDeviceFactory deviceFactory, String key, int gpio, DeviceMode mode) {
|
||||
super(key, deviceFactory);
|
||||
|
||||
this.adapter = deviceFactory.adapter;
|
||||
this.gpio = gpio;
|
||||
|
||||
setMode(mode);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setValue(boolean value) throws RuntimeIOException {
|
||||
outputValue = value;
|
||||
setValue(value);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getValue() throws RuntimeIOException {
|
||||
return adapter.getGPIO(gpio);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getGpio() {
|
||||
return gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setMode(DeviceMode mode) {
|
||||
if (mode == DeviceMode.DIGITAL_INPUT) {
|
||||
getValue(); // Ensure the pin direction is input
|
||||
} else if (mode == DeviceMode.DIGITAL_OUTPUT) {
|
||||
setValue(outputValue); // Restore the last output state
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void closeDevice() {
|
||||
adapter.releaseGPIO(gpio);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,61 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import com.diozero.api.RuntimeIOException;
|
||||
import com.diozero.internal.spi.AbstractDevice;
|
||||
import com.diozero.internal.spi.GpioDigitalOutputDeviceInterface;
|
||||
|
||||
public class CustomDigitalOutputDevice extends AbstractDevice
|
||||
implements GpioDigitalOutputDeviceInterface {
|
||||
protected final CustomAdapter adapter;
|
||||
protected final int gpio;
|
||||
private boolean state;
|
||||
|
||||
public CustomDigitalOutputDevice(
|
||||
CustomDeviceFactory deviceFactory, String key, int gpio, boolean initialValue) {
|
||||
super(key, deviceFactory);
|
||||
|
||||
this.adapter = deviceFactory.adapter;
|
||||
this.gpio = gpio;
|
||||
this.state = initialValue;
|
||||
|
||||
setValue(initialValue);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getValue() throws RuntimeIOException {
|
||||
return state;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getGpio() {
|
||||
return gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setValue(boolean value) throws RuntimeIOException {
|
||||
state = value;
|
||||
adapter.setGPIO(gpio, value);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void closeDevice() throws RuntimeIOException {
|
||||
adapter.releaseGPIO(gpio);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,82 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.hardware.gpio;
|
||||
|
||||
import com.diozero.api.RuntimeIOException;
|
||||
import com.diozero.internal.spi.AbstractDevice;
|
||||
import com.diozero.internal.spi.InternalPwmOutputDeviceInterface;
|
||||
|
||||
public class CustomPwmOutputDevice extends AbstractDevice
|
||||
implements InternalPwmOutputDeviceInterface {
|
||||
protected final CustomAdapter adapter;
|
||||
protected final int gpio;
|
||||
private float state;
|
||||
private int frequency;
|
||||
|
||||
public CustomPwmOutputDevice(
|
||||
CustomDeviceFactory deviceFactory,
|
||||
String key,
|
||||
int gpio,
|
||||
int pwmFrequency,
|
||||
float initialValue) {
|
||||
super(key, deviceFactory);
|
||||
|
||||
this.adapter = deviceFactory.adapter;
|
||||
this.gpio = gpio;
|
||||
this.frequency = pwmFrequency;
|
||||
|
||||
setValue(initialValue);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getGpio() {
|
||||
return gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPwmNum() {
|
||||
return gpio;
|
||||
}
|
||||
|
||||
@Override
|
||||
public float getValue() throws RuntimeIOException {
|
||||
return state;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setValue(float value) throws RuntimeIOException {
|
||||
state = value;
|
||||
adapter.setPWM(gpio, value);
|
||||
}
|
||||
|
||||
@Override
|
||||
public int getPwmFrequency() throws RuntimeIOException {
|
||||
return frequency;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setPwmFrequency(int frequencyHz) throws RuntimeIOException {
|
||||
frequency = frequencyHz;
|
||||
adapter.setPwmFrequency(gpio, frequencyHz);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected void closeDevice() throws RuntimeIOException {
|
||||
adapter.releaseGPIO(gpio);
|
||||
}
|
||||
}
|
||||
@@ -19,12 +19,15 @@ package org.photonvision.hardware;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertArrayEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import com.diozero.internal.spi.NativeDeviceFactoryInterface;
|
||||
import com.fasterxml.jackson.databind.ObjectMapper;
|
||||
import java.io.IOException;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.HardwareManager;
|
||||
import org.photonvision.common.hardware.gpio.CustomDeviceFactory;
|
||||
import org.photonvision.common.util.TestUtils;
|
||||
|
||||
public class HardwareConfigTest {
|
||||
@@ -41,7 +44,9 @@ public class HardwareConfigTest {
|
||||
assertEquals(config.cpuThrottleReasonCmd, "");
|
||||
assertEquals(config.diskUsageCommand, "");
|
||||
assertArrayEquals(config.ledPins.stream().mapToInt(i -> i).toArray(), new int[] {2, 13});
|
||||
CustomGPIO.setConfig(config);
|
||||
NativeDeviceFactoryInterface deviceFactory = HardwareManager.configureCustomGPIO(config);
|
||||
assertTrue(deviceFactory instanceof CustomDeviceFactory);
|
||||
deviceFactory.close();
|
||||
|
||||
} catch (IOException e) {
|
||||
e.printStackTrace();
|
||||
|
||||
@@ -1,49 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.hardware;
|
||||
|
||||
import org.junit.jupiter.api.Assumptions;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioException;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioSocket;
|
||||
import org.photonvision.common.hardware.HardwareManager;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
|
||||
public class HardwareManagerTest {
|
||||
public static final Logger logger = new Logger(HardwareManager.class, LogGroup.General);
|
||||
|
||||
@Test
|
||||
public void managementTest() throws InterruptedException {
|
||||
Assumptions.assumeTrue(Platform.isRaspberryPi());
|
||||
var socket = new PigpioSocket();
|
||||
try {
|
||||
socket.gpioWrite(18, false);
|
||||
socket.gpioWrite(13, false);
|
||||
Thread.sleep(500);
|
||||
for (int i = 0; i < 1000000; i++) {
|
||||
int duty = 1000000 - i;
|
||||
socket.hardwarePWM(18, 1000000, duty);
|
||||
Thread.sleep(0, 25);
|
||||
}
|
||||
} catch (PigpioException e) {
|
||||
logger.error("error", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -17,16 +17,26 @@
|
||||
|
||||
package org.photonvision.hardware;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import com.diozero.internal.provider.builtin.DefaultDeviceFactory;
|
||||
import com.diozero.internal.spi.NativeDeviceFactoryInterface;
|
||||
import com.fasterxml.jackson.databind.ObjectMapper;
|
||||
import java.io.IOException;
|
||||
import java.util.HashSet;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Assumptions;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Nested;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.photonvision.common.LoadJNI;
|
||||
import org.photonvision.common.hardware.GPIO.CustomGPIO;
|
||||
import org.photonvision.common.hardware.GPIO.GPIOBase;
|
||||
import org.photonvision.common.hardware.GPIO.pi.PigpioPin;
|
||||
import org.photonvision.common.configuration.HardwareConfig;
|
||||
import org.photonvision.common.hardware.HardwareManager;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.hardware.VisionLED;
|
||||
import org.photonvision.common.hardware.metrics.MetricsManager;
|
||||
import org.photonvision.common.util.TestUtils;
|
||||
|
||||
public class HardwareTest {
|
||||
@Test
|
||||
@@ -51,44 +61,71 @@ public class HardwareTest {
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testGPIO() {
|
||||
GPIOBase gpio;
|
||||
if (Platform.isRaspberryPi()) {
|
||||
gpio = new PigpioPin(18);
|
||||
} else {
|
||||
gpio = new CustomGPIO(18);
|
||||
public void testNativeGPIO() {
|
||||
try (NativeDeviceFactoryInterface deviceFactory = new DefaultDeviceFactory()) {
|
||||
Assumptions.assumeTrue(deviceFactory.getBoardInfo().isRecognised());
|
||||
|
||||
try (VisionLED led = new VisionLED(deviceFactory, List.of(2, 13), false, 0, 100, 0, null)) {
|
||||
// Verify states can be set
|
||||
led.setState(true);
|
||||
assertEquals(1, deviceFactory.getGpioValue(2));
|
||||
assertEquals(1, deviceFactory.getGpioValue(13));
|
||||
led.setState(false);
|
||||
assertEquals(0, deviceFactory.getGpioValue(2));
|
||||
assertEquals(0, deviceFactory.getGpioValue(13));
|
||||
}
|
||||
}
|
||||
|
||||
gpio.setOn(); // HIGH
|
||||
assertTrue(gpio.getState());
|
||||
|
||||
gpio.setOff(); // LOW
|
||||
assertFalse(gpio.getState());
|
||||
|
||||
gpio.togglePin(); // HIGH
|
||||
assertTrue(gpio.getState());
|
||||
|
||||
gpio.togglePin(); // LOW
|
||||
assertFalse(gpio.getState());
|
||||
|
||||
gpio.setState(true); // HIGH
|
||||
assertTrue(gpio.getState());
|
||||
|
||||
gpio.setState(false); // LOW
|
||||
assertFalse(gpio.getState());
|
||||
|
||||
var success = gpio.shutdown();
|
||||
assertTrue(success);
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testBlink() {
|
||||
if (!Platform.isRaspberryPi()) return;
|
||||
GPIOBase pwm = new PigpioPin(18);
|
||||
pwm.blink(125, 3);
|
||||
var startms = System.currentTimeMillis();
|
||||
while (true) {
|
||||
if (System.currentTimeMillis() - startms > 4500) break;
|
||||
@Nested
|
||||
class CustomGPIOTest {
|
||||
HardwareConfig hardwareConfig = null;
|
||||
NativeDeviceFactoryInterface deviceFactory = null;
|
||||
|
||||
@BeforeEach
|
||||
void setup() throws IOException {
|
||||
System.out.println("Loading Hardware configs...");
|
||||
hardwareConfig =
|
||||
new ObjectMapper().readValue(TestUtils.getHardwareConfigJson(), HardwareConfig.class);
|
||||
deviceFactory = HardwareManager.configureCustomGPIO(hardwareConfig);
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testCustomGPIO() throws IOException {
|
||||
try (VisionLED led = new VisionLED(deviceFactory, List.of(2, 13), false, 0, 100, 0, null)) {
|
||||
// Verify states can be set
|
||||
led.setState(true);
|
||||
assertEquals(1, deviceFactory.getGpioValue(2));
|
||||
assertEquals(1, deviceFactory.getGpioValue(13));
|
||||
led.setState(false);
|
||||
assertEquals(0, deviceFactory.getGpioValue(2));
|
||||
assertEquals(0, deviceFactory.getGpioValue(13));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testBlink() throws InterruptedException, IOException {
|
||||
try (VisionLED led = new VisionLED(deviceFactory, List.of(2, 13), false, 0, 100, 0, null)) {
|
||||
// Verify blinking toggles between states
|
||||
HashSet<Integer> seenValues = new HashSet<>();
|
||||
led.blink(125, 3);
|
||||
var startms = System.currentTimeMillis();
|
||||
while (System.currentTimeMillis() - startms < 1000) {
|
||||
seenValues.add(deviceFactory.getGpioValue(2));
|
||||
}
|
||||
assertEquals(2, seenValues.size());
|
||||
assertTrue(seenValues.contains(0));
|
||||
assertTrue(seenValues.contains(1));
|
||||
|
||||
seenValues.clear();
|
||||
|
||||
// Verify that after blinking, toggling has stopped
|
||||
startms = System.currentTimeMillis();
|
||||
while (System.currentTimeMillis() - startms < 250) {
|
||||
seenValues.add(deviceFactory.getGpioValue(2));
|
||||
}
|
||||
assertEquals(1, seenValues.size());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -268,15 +268,15 @@ public class Main {
|
||||
ConfigManager.getInstance().load(); // init config manager
|
||||
ConfigManager.getInstance().requestSave();
|
||||
|
||||
logger.debug("Loading HardwareManager...");
|
||||
// Force load the hardware manager
|
||||
HardwareManager.getInstance();
|
||||
|
||||
logger.info("Loading ML models...");
|
||||
var modelManager = NeuralNetworkModelManager.getInstance();
|
||||
modelManager.extractModels();
|
||||
modelManager.discoverModels();
|
||||
|
||||
logger.debug("Loading HardwareManager...");
|
||||
// Force load the hardware manager
|
||||
HardwareManager.getInstance();
|
||||
|
||||
logger.debug("Loading NetworkManager...");
|
||||
NetworkManager.getInstance().reinitialize();
|
||||
|
||||
@@ -306,7 +306,7 @@ public class Main {
|
||||
VisionSourceManager.getInstance().registerTimedTasks();
|
||||
|
||||
logger.info("Starting server...");
|
||||
HardwareManager.getInstance().setRunning(true);
|
||||
HardwareManager.getInstance().setError(null);
|
||||
Server.initialize(DEFAULT_WEBPORT);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,10 +4,11 @@
|
||||
"supportURL": "https://support.photonvision.com",
|
||||
"ledPins" : [2, 13],
|
||||
"statusRGBPins" : [-1, -1, -1],
|
||||
"ledSetCommand" : "",
|
||||
"ledsCanDim" : true,
|
||||
"ledDimCommand" : "echo 10",
|
||||
"ledBlinkCommand" : "echo 10",
|
||||
"getGPIOCommand": "cat /tmp/GPIO{p}",
|
||||
"setGPIOCommand": "echo {s} > /tmp/GPIO{p}",
|
||||
"setPWMCommand": "echo {v} > /tmp/GPIO{p}",
|
||||
"releaseGPIOCommand": "rm /tmp/GPIO{p}",
|
||||
"cpuTempCommand" : "echo 10",
|
||||
"cpuMemoryCommand" : "echo 10",
|
||||
"cpuUtilCommand" : "echo 10",
|
||||
|
||||
Reference in New Issue
Block a user