Skip to content

Commit

Permalink
fda
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Aug 2, 2024
1 parent 94d1d65 commit a4a896d
Show file tree
Hide file tree
Showing 7 changed files with 43 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,10 @@ public int getNumBytesRead() {
return readPos + 1;
}

public int getSize() {
return packetData.length;
}

/**
* Returns the packet data.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ public T get() {
packet.clear();

packet.setData(subscriber.get(new byte[] {}));
if (packet.getNumBytesWritten() < 1) return defaultValue;
if (packet.getSize() < 1) return defaultValue;

return serde.unpack(packet);
}
Expand Down
20 changes: 2 additions & 18 deletions photonlib-cpp-examples/aimattarget/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -68,36 +68,21 @@ wpi.sim.addDriverstation()
model {
components {
frcUserProgram(NativeExecutableSpec) {
// We don't need to build for roborio -- if we do, we need to install
// a roborio toolchain every time we build in CI
// Ideally, we'd be able to set the roborio toolchain as optional, but
// I can't figure out how to set that environment variable from build.gradle
// (see https://github.com/wpilibsuite/native-utils/blob/2917c69fb5094e36d499c465f047dab81c68446c/ToolchainPlugin/src/main/java/edu/wpi/first/toolchain/ToolchainGraphBuildService.java#L71)
// for now, commented out

// targetPlatform wpi.platforms.roborio

if (includeDesktopSupport) {
targetPlatform wpi.platforms.desktop
}
targetPlatform wpi.platforms.roborio
targetPlatform wpi.platforms.desktop

sources.cpp {
source {
srcDir 'src/main/cpp'
include '**/*.cpp', '**/*.cc'
}
exportedHeaders {
srcDir 'src/main/include'
}
}

// Set deploy task to deploy this component
deployArtifact.component = it

// Enable run tasks for this component
wpi.cpp.enableExternalTasks(it)

// Enable simulation for this component
wpi.sim.enable(it)
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
wpi.cpp.vendor.cpp(it)
Expand All @@ -115,7 +100,6 @@ model {
}
}

// Enable run tasks for this component
wpi.cpp.enableExternalTasks(it)

wpi.cpp.vendor.cpp(it)
Expand Down
12 changes: 11 additions & 1 deletion photonlib-cpp-examples/aimattarget/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,20 @@
#include "Robot.h"

#include <photon/PhotonUtils.h>

#include <units/time.h>
#include <frc/Timer.h>
#include <frc/smartdashboard/SmartDashboard.h>

void Robot::RobotPeriodic() {
photon::PhotonCamera::SetVersionCheckEnabled(false);

auto start = frc::Timer::GetFPGATimestamp();
photon::PhotonPipelineResult result = camera.GetLatestResult();
auto end = frc::Timer::GetFPGATimestamp();

printf("DT is %iuS for %i targets\n",(int)units::microsecond_t(end - start).to<double>(), result.GetTargets().size());
}

void Robot::TeleopPeriodic() {
double forwardSpeed = -xboxController.GetRightY();
double rotationSpeed;
Expand Down
3 changes: 2 additions & 1 deletion photonlib-cpp-examples/aimattarget/src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,11 @@
class Robot : public frc::TimedRobot {
public:
void TeleopPeriodic() override;
void RobotPeriodic() override;

private:
// Change this to match the name of your camera as shown in the web UI
photon::PhotonCamera camera{"Microsoft_LifeCam_HD-3000"};
photon::PhotonCamera camera{"WPI2024"};
// PID constants should be tuned per robot
frc::PIDController controller{.1, 0, 0};

Expand Down
10 changes: 10 additions & 0 deletions photonlib-java-examples/aimattarget/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,16 @@ def ROBOT_MAIN_CLASS = "frc.robot.Main"

apply from: "${rootDir}/../shared/examples_common.gradle"

ext {
wpilibVersion = "2025.0.0-alpha-1"
wpimathVersion = wpilibVersion
openCVversion = "4.8.0-2"
}

wpi.getVersions().getOpencvVersion().convention(openCVversion);
wpi.getVersions().getWpilibVersion().convention(wpilibVersion);
wpi.getVersions().getWpimathVersion().convention(wpimathVersion);

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
deploy {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,12 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import org.photonvision.PhotonCamera;

/**
Expand All @@ -49,7 +52,7 @@ public class Robot extends TimedRobot {
final double GOAL_RANGE_METERS = Units.feetToMeters(3);

// Change this to match the name of your camera as shown in the web UI
PhotonCamera camera = new PhotonCamera("YOUR_CAMERA_NAME_HERE");
PhotonCamera camera = new PhotonCamera("Microsoft_LifeCam_HD-3000");

// PID constants should be tuned per robot
final double LINEAR_P = 0.1;
Expand All @@ -67,6 +70,15 @@ public class Robot extends TimedRobot {
PWMVictorSPX rightMotor = new PWMVictorSPX(1);
DifferentialDrive drive = new DifferentialDrive(leftMotor, rightMotor);

@Override
public void robotPeriodic() {
var start = Timer.getFPGATimestamp();
var res = camera.getLatestResult();
var end = Timer.getFPGATimestamp();
System.out.println("dt: " + (int)((end - start)*1e6) + "uS for targets: " + res.getTargets().size());
SmartDashboard.putNumber("decodeTime", (int)((end-start)*1e6));
}

@Override
public void teleopPeriodic() {
double forwardSpeed;
Expand Down

0 comments on commit a4a896d

Please sign in to comment.