mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
[photon-targeting] Move C++ targeting classes to photon-targetting (#1009)
* add classes to targeting and update gradle * rename me * Finish cleanup * Formatting fixes * just use common.gradle * Update build.gradle * Update config.gradle * remove typo * simplify * Add Packet Headers * move simulation classes into simulation folder * draw in dependency * fix * Everything working minus tests cause im lazy * formatting fixes REMEMBER TO REMOVE UNUSED IMPORTS, IM JUST TOO LAZY TO CHECK RN * move packet test to targeting * Formatting fixes * remove TargetCorner from c++ im not 100% sure but just doing std::pair<double, double> is sufficient and shouldnt conflict with protobuf * think i added packet * fix namespace issue * organize imports in photon-targeting * Formatting fixes * remove ctors * fix typo * Add PNP and Multitag packet tests * revert TargetCorner class * Add Test placeholders * remove annoying print * Reorganize build and publish process channeling inner Thad * add targeting as flag * Update config.gradle * fix issue with platform binaries not building * Update photonlib.json.in casing still needs to be checked * add minimum level back * add back UTF-8 encoding of javadoc * simplify publish model for photon-lib * fix windows symbol generation * formatting fixes * move task from main gradle to config * Update config.gradle
This commit is contained in:
@@ -24,7 +24,7 @@
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <photonlib/PhotonUtils.h>
|
||||
#include <photon/PhotonUtils.h>
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
double forwardSpeed;
|
||||
@@ -37,7 +37,7 @@ void Robot::TeleopPeriodic() {
|
||||
|
||||
if (result.HasTargets()) {
|
||||
// First calculate range
|
||||
units::meter_t range = photonlib::PhotonUtils::CalculateDistanceToTarget(
|
||||
units::meter_t range = photon::PhotonUtils::CalculateDistanceToTarget(
|
||||
CAMERA_HEIGHT, TARGET_HEIGHT, CAMERA_PITCH,
|
||||
units::degree_t{result.GetBestTarget().GetPitch()});
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photonlib/PhotonCamera.h>
|
||||
#include <photon/PhotonCamera.h>
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
@@ -60,7 +60,7 @@ class Robot : public frc::TimedRobot {
|
||||
frc::PIDController turnController{ANGULAR_P, 0.0, ANGULAR_D};
|
||||
|
||||
// Change this to match the name of your camera
|
||||
photonlib::PhotonCamera camera{"photonvision"};
|
||||
photon::PhotonCamera camera{"photonvision"};
|
||||
|
||||
frc::XboxController xboxController{0};
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <photonlib/PhotonUtils.h>
|
||||
#include <photon/PhotonUtils.h>
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
double forwardSpeed = -xboxController.GetRightY();
|
||||
@@ -33,7 +33,7 @@ void Robot::TeleopPeriodic() {
|
||||
if (xboxController.GetAButton()) {
|
||||
// Vision-alignment mode
|
||||
// Query the latest result from PhotonVision
|
||||
photonlib::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
photon::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
|
||||
if (result.HasTargets()) {
|
||||
// Rotation speed is the output of the PID controller
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photonlib/PhotonCamera.h>
|
||||
#include <photon/PhotonCamera.h>
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
@@ -40,7 +40,7 @@ class Robot : public frc::TimedRobot {
|
||||
|
||||
private:
|
||||
// Change this to match the name of your camera
|
||||
photonlib::PhotonCamera camera{"photonvision"};
|
||||
photon::PhotonCamera camera{"photonvision"};
|
||||
// PID constants should be tuned per robot
|
||||
frc::PIDController controller{.1, 0, 0};
|
||||
|
||||
|
||||
@@ -24,8 +24,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photonlib/PhotonCamera.h>
|
||||
#include <photonlib/PhotonPoseEstimator.h>
|
||||
#include <photon/PhotonCamera.h>
|
||||
#include <photon/PhotonPoseEstimator.h>
|
||||
|
||||
#include <utility>
|
||||
|
||||
@@ -34,12 +34,12 @@
|
||||
|
||||
class PhotonCameraWrapper {
|
||||
public:
|
||||
photonlib::PhotonPoseEstimator m_poseEstimator{
|
||||
photon::PhotonPoseEstimator m_poseEstimator{
|
||||
frc::LoadAprilTagLayoutField(frc::AprilTagField::k2023ChargedUp),
|
||||
photonlib::MULTI_TAG_PNP_ON_RIO,
|
||||
std::move(photonlib::PhotonCamera{"WPI2023"}), frc::Transform3d{}};
|
||||
photon::MULTI_TAG_PNP_ON_RIO, std::move(photon::PhotonCamera{"WPI2023"}),
|
||||
frc::Transform3d{}};
|
||||
|
||||
inline std::optional<photonlib::EstimatedRobotPose> Update(
|
||||
inline std::optional<photon::EstimatedRobotPose> Update(
|
||||
frc::Pose2d estimatedPose) {
|
||||
m_poseEstimator.SetReferencePose(frc::Pose3d(estimatedPose));
|
||||
return m_poseEstimator.Update();
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photonlib/PhotonCamera.h>
|
||||
#include <photon/PhotonCamera.h>
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <photonlib/PhotonUtils.h>
|
||||
#include <photon/PhotonUtils.h>
|
||||
|
||||
void Robot::TeleopPeriodic() {
|
||||
double forwardSpeed;
|
||||
@@ -33,11 +33,11 @@ void Robot::TeleopPeriodic() {
|
||||
if (xboxController.GetAButton()) {
|
||||
// Vision-alignment mode
|
||||
// Query the latest result from PhotonVision
|
||||
photonlib::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
photon::PhotonPipelineResult result = camera.GetLatestResult();
|
||||
|
||||
if (result.HasTargets()) {
|
||||
// First calculate range
|
||||
units::meter_t range = photonlib::PhotonUtils::CalculateDistanceToTarget(
|
||||
units::meter_t range = photon::PhotonUtils::CalculateDistanceToTarget(
|
||||
CAMERA_HEIGHT, TARGET_HEIGHT, CAMERA_PITCH,
|
||||
units::degree_t{result.GetBestTarget().GetPitch()});
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <photonlib/PhotonCamera.h>
|
||||
#include <photon/PhotonCamera.h>
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc/XboxController.h>
|
||||
@@ -56,7 +56,7 @@ class Robot : public frc::TimedRobot {
|
||||
frc::PIDController controller{P_GAIN, 0.0, D_GAIN};
|
||||
|
||||
// Change this to match the name of your camera
|
||||
photonlib::PhotonCamera camera{"photonvision"};
|
||||
photon::PhotonCamera camera{"photonvision"};
|
||||
|
||||
frc::XboxController xboxController{0};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user