mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Compare commits
6 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
846528ce9c | ||
|
|
7383a9040d | ||
|
|
ab09e7fa14 | ||
|
|
cd3d9b06bb | ||
|
|
fd4628d419 | ||
|
|
5fdfa3132f |
@@ -1,6 +1,5 @@
|
||||
{
|
||||
"deviceName" : "Limelight 2+",
|
||||
"supportURL" : "https://limelightvision.io",
|
||||
"ledPins" : [ 13, 18 ],
|
||||
"ledsCanDim" : true,
|
||||
"ledPWMFrequency" : 1000,
|
||||
|
||||
@@ -1,6 +1,5 @@
|
||||
{
|
||||
"deviceName" : "Limelight 2",
|
||||
"supportURL" : "https://limelightvision.io",
|
||||
"ledPins" : [ 17, 18 ],
|
||||
"ledsCanDim" : false,
|
||||
"vendorFOV" : 75.76079874010732
|
||||
|
||||
@@ -103,9 +103,9 @@ If your hardware contains a camera with a known field of vision, it can be enter
|
||||
}
|
||||
```
|
||||
|
||||
## Cosmetic & Branding
|
||||
## Device Name Branding
|
||||
|
||||
To help differentiate your hardware from other solutions, some customization is allowed.
|
||||
To help differentiate your hardware from other solutions, a device name may be set.
|
||||
|
||||
```{eval-rst}
|
||||
.. tab-set-code::
|
||||
@@ -113,8 +113,6 @@ To help differentiate your hardware from other solutions, some customization is
|
||||
|
||||
{
|
||||
"deviceName" : "Super Cool Custom Hardware",
|
||||
"deviceLogoPath" : "",
|
||||
"supportURL" : "https://cat-bounce.com/",
|
||||
}
|
||||
```
|
||||
|
||||
@@ -132,8 +130,6 @@ Here is a complete example `hardwareConfig.json`:
|
||||
|
||||
{
|
||||
"deviceName" : "Blinky McBlinkface",
|
||||
"deviceLogoPath" : "",
|
||||
"supportURL" : "https://www.youtube.com/watch?v=b-CvLWbfZhU",
|
||||
"ledPins" : [2, 13],
|
||||
"ledsCanDim" : true,
|
||||
"ledBrightnessRange" : [ 0, 100 ],
|
||||
|
||||
@@ -52,10 +52,10 @@ Only use a static IP when connected to the **robot radio**, and never when testi
|
||||
3. Open the settings tab on the left pane.
|
||||
4. Under the Networking section, set your team number.
|
||||
5. Change your IP to Static.
|
||||
6. Set your coprocessor's IP address to “10.TE.AM.11”. More information on IP format can be found [here](https://docs.wpilib.org/en/stable/docs/networking/networking-introduction/ip-configurations.html#on-the-field-static-configuration).
|
||||
6. Set your coprocessor's IP address to “10.TE.AM.xx”. "xx" should be a unique number not currently used by another device on the robot in the `.6-.19` range. More information on IP format can be found [here](https://docs.wpilib.org/en/stable/docs/networking/networking-introduction/ip-configurations.html#on-the-field-static-configuration).
|
||||
7. Click the “Save” button.
|
||||
|
||||
Power-cycle your robot and then you will now be access the PhotonVision dashboard at `10.TE.AM.11:5800`.
|
||||
Power-cycle your robot and then you will now be access the PhotonVision dashboard at `10.TE.AM.xx:5800`.
|
||||
|
||||
```{image} images/static.png
|
||||
:alt: Correctly set static IP
|
||||
|
||||
@@ -196,6 +196,42 @@ If the camera is mounted on a mobile mechanism (like a turret) this transform ca
|
||||
visionSim.adjustCamera(cameraSim, robotToCamera);
|
||||
```
|
||||
|
||||
## Low-Resource Vision Simulation with Photonvision
|
||||
|
||||
By default, PhotonCameraSim renders two simulated camera streams using OpenCV:
|
||||
|
||||
- Raw stream - The unprocessed camera view
|
||||
- Processed stream - The camera view with vision processing overlays
|
||||
|
||||
These streams are nice if you want to actually view the simulated images, but they can be computationally expensive. This may cause lag and reduced simulation performance on lower-powered computers.
|
||||
Lightweight Configuration
|
||||
|
||||
The following configuration disables both streams while still allowing tag detection and pose simulation to work. It's not perfect, but it's much better performance-wise than the default configuration.
|
||||
|
||||
.. code-block:: java
|
||||
|
||||
// lightweight config version
|
||||
// var cameraProperties = new SimCameraProperties();
|
||||
// cameraSim = new PhotonCameraSim(camera, cameraProperties, aprilTagLayout);
|
||||
// cameraSim.enableRawStream(false); // disables raw image stream
|
||||
// cameraSim.enableProcessedStream(false); // disables processed image stream
|
||||
|
||||
**Use Case**
|
||||
|
||||
This configuration is ideal for Chromebooks or low-spec machines where rendering the simulated camera images causes lag, but vision data is still desired for testing.
|
||||
|
||||
**What Still Works**
|
||||
|
||||
- AprilTag detection
|
||||
- Pose estimation
|
||||
- NetworkTables data publishing
|
||||
- Robot positioning and targeting
|
||||
|
||||
**What's Disabled**
|
||||
|
||||
- Visual camera stream rendering
|
||||
- Real-time visual debugging of camera output
|
||||
|
||||
## Updating The Simulation World
|
||||
|
||||
To update the `VisionSystemSim`, we simply have to pass in the simulated robot pose periodically (in `simulationPeriodic()`).
|
||||
|
||||
@@ -555,7 +555,7 @@ watch(metricsHistorySnapshot, () => {
|
||||
:variant="theme.global.name.value === 'LightTheme' ? 'elevated' : 'outlined'"
|
||||
@click="
|
||||
offlineUpdateDialog.show = false;
|
||||
handleOfflineUpdate(offlineUpdate.value.files[0]);
|
||||
handleOfflineUpdate(offlineUpdate.files[0]);
|
||||
"
|
||||
>
|
||||
<v-icon start class="open-icon" size="large"> mdi-upload </v-icon>
|
||||
|
||||
@@ -23,8 +23,6 @@ import java.util.ArrayList;
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
public class HardwareConfig {
|
||||
public final String deviceName;
|
||||
public final String deviceLogoPath;
|
||||
public final String supportURL;
|
||||
|
||||
// LED control
|
||||
public final ArrayList<Integer> ledPins;
|
||||
@@ -47,8 +45,6 @@ public class HardwareConfig {
|
||||
|
||||
public HardwareConfig(
|
||||
String deviceName,
|
||||
String deviceLogoPath,
|
||||
String supportURL,
|
||||
ArrayList<Integer> ledPins,
|
||||
boolean ledsCanDim,
|
||||
ArrayList<Integer> ledBrightnessRange,
|
||||
@@ -63,8 +59,6 @@ public class HardwareConfig {
|
||||
String restartHardwareCommand,
|
||||
double vendorFOV) {
|
||||
this.deviceName = deviceName;
|
||||
this.deviceLogoPath = deviceLogoPath;
|
||||
this.supportURL = supportURL;
|
||||
this.ledPins = ledPins;
|
||||
this.ledsCanDim = ledsCanDim;
|
||||
this.ledBrightnessRange = ledBrightnessRange;
|
||||
@@ -82,8 +76,6 @@ public class HardwareConfig {
|
||||
|
||||
public HardwareConfig() {
|
||||
deviceName = "";
|
||||
deviceLogoPath = "";
|
||||
supportURL = "";
|
||||
ledPins = new ArrayList<>();
|
||||
ledsCanDim = false;
|
||||
ledBrightnessRange = new ArrayList<>();
|
||||
@@ -121,10 +113,6 @@ public class HardwareConfig {
|
||||
public String toString() {
|
||||
return "HardwareConfig[deviceName="
|
||||
+ deviceName
|
||||
+ ", deviceLogoPath="
|
||||
+ deviceLogoPath
|
||||
+ ", supportURL="
|
||||
+ supportURL
|
||||
+ ", ledPins="
|
||||
+ ledPins
|
||||
+ ", ledsCanDim="
|
||||
|
||||
@@ -104,7 +104,6 @@ public class NetworkTablesManager {
|
||||
|
||||
public void registerTimedTasks() {
|
||||
m_timeSync.start();
|
||||
TimedTaskManager.getInstance().addTask("NTManager", this::ntTick, 5000);
|
||||
TimedTaskManager.getInstance()
|
||||
.addTask("CheckHostnameAndCameraNames", this::checkHostnameAndCameraNames, 10000);
|
||||
}
|
||||
@@ -380,23 +379,6 @@ public class NetworkTablesManager {
|
||||
broadcastVersion();
|
||||
}
|
||||
|
||||
// So it seems like if Photon starts before the robot NT server does, and both aren't static IP,
|
||||
// it'll never connect. This hack works around it by restarting the client/server while the nt
|
||||
// instance isn't connected, same as clicking the save button in the settings menu (or restarting
|
||||
// the service)
|
||||
private void ntTick() {
|
||||
if (!ntInstance.isConnected()
|
||||
&& !ConfigManager.getInstance().getConfig().getNetworkConfig().runNTServer) {
|
||||
setConfig(ConfigManager.getInstance().getConfig().getNetworkConfig());
|
||||
}
|
||||
|
||||
if (!ntInstance.isConnected() && !m_isRetryingConnection) {
|
||||
m_isRetryingConnection = true;
|
||||
logger.error(
|
||||
"[NetworkTablesManager] Could not connect to the robot! Will retry in the background...");
|
||||
}
|
||||
}
|
||||
|
||||
public long getTimeSinceLastPong() {
|
||||
return m_timeSync.getTimeSinceLastPong();
|
||||
}
|
||||
|
||||
@@ -449,7 +449,7 @@ public class SystemMonitor {
|
||||
/**
|
||||
* Returns the total GPU memory in MiB.
|
||||
*
|
||||
* @return The total GPU memory in MiB, or -1.0 if not avaialable on this platform.
|
||||
* @return The total GPU memory in MiB, or -1.0 if not available on this platform.
|
||||
*/
|
||||
public double getGpuMem() {
|
||||
return -1.0;
|
||||
|
||||
@@ -38,8 +38,6 @@ public class HardwareConfigTest {
|
||||
var config =
|
||||
new ObjectMapper().readValue(TestUtils.getHardwareConfigJson(), HardwareConfig.class);
|
||||
assertEquals(config.deviceName, "PhotonVision");
|
||||
assertEquals(config.deviceLogoPath, "photonvision.png");
|
||||
assertEquals(config.supportURL, "https://support.photonvision.com");
|
||||
// Ensure defaults are not null
|
||||
assertArrayEquals(config.ledPins.stream().mapToInt(i -> i).toArray(), new int[] {2, 13});
|
||||
NativeDeviceFactoryInterface deviceFactory = HardwareManager.configureCustomGPIO(config);
|
||||
|
||||
@@ -1,7 +1,5 @@
|
||||
{
|
||||
"deviceName": "PhotonVision",
|
||||
"deviceLogoPath": "photonvision.png",
|
||||
"supportURL": "https://support.photonvision.com",
|
||||
"ledPins" : [2, 13],
|
||||
"statusRGBPins" : [-1, -1, -1],
|
||||
"ledsCanDim" : true,
|
||||
|
||||
Reference in New Issue
Block a user