Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 19 additions & 0 deletions docs/DeadeyeSettings/deadeye.service
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
[Unit]
Description=Deadeye
After=docker.service
Requires=docker.service

[Service]
Type=oneshot
RemainAfterExit=yes
ExecStart=/bin/bash -c '\
CAMERA_DEV=$(readlink --canonicalize --no-newline /dev/v4l/by-id/usb-Microsoft_Microsoft®_LifeCam_HD-3000-video-index0) \
docker compose -f /home/orangepi/deadeye/docker-compose.yml up --detach \
'
ExecStop=/bin/bash -c '\
CAMERA_DEV=$(readlink --canonicalize --no-newline /dev/v4l/by-id/usb-Microsoft_Microsoft®_LifeCam_HD-3000-video-index0) \
docker compose -f /home/orangepi/deadeye/docker-compose.yml stop \
'

[Install]
WantedBy=multi-user.target
55 changes: 55 additions & 0 deletions docs/DeadeyeSettings/docker-compose.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
version: "3.4"

x-common-environment: &common-environment
DEADEYE_NT_SERVER: 10.27.67.2
DEADEYE_NT_PORT: 1735

x-common-restart: &common-restart
restart: on-failure

volumes:
upload_data:

services:
daemon:
image: j3ff/deadeye-daemon
privileged: true
ports:
- 5805:5805
- 5806:5806
- 5807:5807
- 5808:5808
- 5809:5809
volumes:
- upload_data:/upload
- type: bind
source: /home/orangepi/deadeye/logs
target: /var/opt/deadeye
devices:
- /dev/gpiochip0
- "${CAMERA_DEV}:/dev/deadeye"
environment:
<<: *common-environment
DEADEYE_STREAM_HOST: 10.27.67.11
<<: *common-restart
admin:
image: j3ff/deadeye-admin
ports:
- 5000:5000
volumes:
- upload_data:/upload
environment:
<<: *common-environment
PYTHONPATH: /app
FLASK_ENV: production
DEADEYE_ADMIN_PORT: 5000
DEADEYE_NT_WAIT_MS: 500
DEADEYE_UPLOAD_DIR: /upload
stop_grace_period: 1s
stop_signal: SIGINT
<<: *common-restart
web:
image: j3ff/deadeye-web
ports:
- "0.0.0.0:80:80"
<<: *common-restart
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,9 @@ public void robotPeriodic() {
}

@Override
public void disabledInit() {}
public void disabledInit() {
m_robotContainer.setCamEnabled(false);
}

@Override
public void disabledPeriodic() {}
Expand All @@ -98,6 +100,7 @@ public void autonomousExit() {}

@Override
public void teleopInit() {
m_robotContainer.setCamEnabled(true);
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
Expand Down
11 changes: 9 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,19 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.subsystems.drive.DriveSubsystem;
import frc.robot.subsystems.vision.DeadeyeSubsystem;
import frc.robot.subsystems.vision.VisionSubsystem;

public class RobotContainer {

VisionSubsystem visionSubsystem;
DriveSubsystem driveSubsystem;
DeadeyeSubsystem deadeye;

public RobotContainer() {
DriveSubsystem driveSubsystem = new DriveSubsystem();
VisionSubsystem visionSubsystem = new VisionSubsystem(driveSubsystem);
deadeye = new DeadeyeSubsystem();
driveSubsystem = new DriveSubsystem();
visionSubsystem = new VisionSubsystem(driveSubsystem);
configureBindings();
}

Expand All @@ -25,4 +28,8 @@ private void configureBindings() {}
public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
}

public void setCamEnabled(boolean val) {
deadeye.setCamEnabled(val);
}
}
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/constants/DriveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -144,12 +144,12 @@ public static TrajectoryConfig getDefaultTrajectoryConfig() {

public static TalonSRXConfiguration getAzimuthTalonConfig() {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'getAzimuthTalonConfig'");
return new TalonSRXConfiguration();
}

public static TalonFXConfiguration getDriveTalonConfig() {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'getDriveTalonConfig'");
return new TalonFXConfiguration();
}

// // Azimuth Talon Config
Expand Down
86 changes: 86 additions & 0 deletions src/main/java/frc/robot/subsystems/vision/DeadeyeSubsystem.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
package frc.robot.subsystems.vision;

import java.util.List;
import java.util.Set;
import org.strykeforce.deadeye.Deadeye;
import org.strykeforce.deadeye.Rect;
import org.strykeforce.deadeye.TargetListTargetData;
import org.strykeforce.telemetry.TelemetryService;
import org.strykeforce.telemetry.measurable.MeasurableSubsystem;
import org.strykeforce.telemetry.measurable.Measure;

public class DeadeyeSubsystem extends MeasurableSubsystem {

Deadeye<TargetListTargetData> cam;

TargetListTargetData data = new TargetListTargetData();

int borderLengthX = 0;
int border1 = 0;
int border2 = 0;

public DeadeyeSubsystem() {
cam = new Deadeye<>("W0", TargetListTargetData.class);
borderLengthX = cam.getCapture().width / 3;
border1 = borderLengthX;
border2 = borderLengthX + border1;
}

public boolean isCamEnabled() {
return cam.getEnabled();
}

public void setCamEnabled(boolean val) {
cam.setEnabled(val);
}

public TargetListTargetData getTargetListData() {
return data;
}

public boolean isNoteRight() {
List<Rect> list = data.targets;

for (Rect rect : list) {
if (rect.topLeft.x >= border2) return true;
}
return false;
}

public boolean isNoteMid() {
List<Rect> list = data.targets;

for (Rect rect : list) {
if (rect.topLeft.x >= border1 && rect.bottomRight.x <= border2) return true;
}
return false;
}

public boolean isNoteLeft() {
List<Rect> list = data.targets;

for (Rect rect : list) {
if (rect.bottomRight.x <= border1) return true;
}
return false;
}

@Override
public void periodic() {
data = cam.getTargetData();

System.err.println(isNoteLeft() + " " + isNoteMid() + " " + isNoteRight());
}

@Override
public Set<Measure> getMeasures() {
// TODO Auto-generated method stub
return null;
}

@Override
public void registerWith(TelemetryService telemetryService) {
// TODO Auto-generated method stub
super.registerWith(telemetryService);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,6 @@ public class VisionSubsystem extends SubsystemBase {
int offWheels = 0;
Logger logger;

// Deadeye<TargetListTargetData> cam = new Deadeye<TargetListTargetData>("A0",
// TargetListTargetData.class, NetworkTableInstance.getDefault(), null);

private Matrix<N3, N1> adaptiveVisionMatrix;

// Constructor
Expand Down Expand Up @@ -120,8 +117,6 @@ private boolean isPoseValidWithoutWheels(WallEyeResult test) {
@Override
public void periodic() {

// cam.getEnabled();

// If enough time elapses trust vision or if enough time elapses reset the counter
if ((getSeconds() - timeLastVision > VisionConstants.kMaxTimeNoVision)
&& (curState != VisionStates.TRUSTVISION)) {
Expand Down
4 changes: 2 additions & 2 deletions vendordeps/deadeye.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "deadeye.json",
"name": "StrykeForce-Deadeye",
"version": "22.2.0",
"version": "22.1.0",
"uuid": "a8620993-3ffc-425e-95d9-a5e73eabef40",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,7 +12,7 @@
{
"groupId": "org.strykeforce",
"artifactId": "deadeye",
"version": "22.2.0"
"version": "22.1.0"
}
],
"jniDependencies": [],
Expand Down