Clean up C++ headers (#2402)

This commit is contained in:
Gold856
2026-03-19 02:10:04 -04:00
committed by GitHub
parent 12446a6c44
commit d4bfe643d5
45 changed files with 31 additions and 161 deletions

View File

@@ -35,11 +35,10 @@
#include <hal/FRCUsageReporting.h>
#include <net/TimeSyncServer.h>
#include <opencv2/core.hpp>
#include <opencv2/core/mat.hpp>
#include <opencv2/core/utility.hpp>
#include <wpi/json.h>
#include "PhotonVersion.h"
#include "opencv2/core/utility.hpp"
#include "photon/dataflow/structures/Packet.h"
static constexpr units::second_t WARN_DEBOUNCE_SEC = 5_s;

View File

@@ -26,7 +26,6 @@
#include <limits>
#include <optional>
#include <span>
#include <utility>
#include <vector>

View File

@@ -32,6 +32,11 @@
#include <frc/apriltag/AprilTagFieldLayout.h>
#include <frc/apriltag/AprilTagFields.h>
#include "photon/estimation/CameraTargetRelation.h"
#include "photon/estimation/RotTrlTransform3d.h"
#include "photon/estimation/VisionEstimation.h"
#include "photon/simulation/VideoSimUtil.h"
namespace photon {
PhotonCameraSim::PhotonCameraSim(PhotonCamera* camera)
: PhotonCameraSim(camera, photon::SimCameraProperties::PERFECT_90DEG(),

View File

@@ -28,6 +28,8 @@
#include <utility>
#include <vector>
#include <frc/Errors.h>
using namespace photon;
void SimCameraProperties::SetCalibration(int width, int height,

View File

@@ -31,7 +31,6 @@
#include <frc/Alert.h>
#include <networktables/BooleanTopic.h>
#include <networktables/DoubleArrayTopic.h>
#include <networktables/DoubleTopic.h>
#include <networktables/IntegerTopic.h>
#include <networktables/MultiSubscriber.h>
#include <networktables/NetworkTable.h>

View File

@@ -29,7 +29,7 @@
#include <frc/geometry/Rotation3d.h>
#include <frc/geometry/Transform3d.h>
#include <frc/interpolation/TimeInterpolatableBuffer.h>
#include <opencv2/core/mat.hpp>
#include <wpi/SmallVector.h>
#include "photon/PhotonCamera.h"
#include "photon/targeting/PhotonPipelineResult.h"

View File

@@ -26,11 +26,7 @@
#include <cmath>
#include "photon/dataflow/structures/Packet.h"
#include "photon/targeting/MultiTargetPNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/PnpResult.h"
namespace photon {

View File

@@ -32,12 +32,6 @@
#include <units/length.h>
#include <units/math.h>
#include "photon/dataflow/structures/Packet.h"
#include "photon/targeting/MultiTargetPNPResult.h"
#include "photon/targeting/PhotonPipelineResult.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/PnpResult.h"
namespace photon {
class PhotonUtils {
public:

View File

@@ -24,23 +24,15 @@
#pragma once
#include <algorithm>
#include <limits>
#include <string>
#include <utility>
#include <vector>
#include <cameraserver/CameraServer.h>
#include <frc/Timer.h>
#include <frc/apriltag/AprilTagFieldLayout.h>
#include <frc/apriltag/AprilTagFields.h>
#include <photon/PhotonCamera.h>
#include <photon/PhotonTargetSortMode.h>
#include <photon/estimation/CameraTargetRelation.h>
#include <photon/estimation/VisionEstimation.h>
#include <photon/networktables/NTTopicSet.h>
#include <photon/simulation/SimCameraProperties.h>
#include <photon/simulation/VideoSimUtil.h>
#include <photon/simulation/VisionTargetSim.h>
#include <units/math.h>
#include <wpi/timestamp.h>

View File

@@ -24,15 +24,12 @@
#pragma once
#include <algorithm>
#include <random>
#include <string>
#include <utility>
#include <vector>
#include <Eigen/Core>
#include <frc/Errors.h>
#include <frc/MathUtil.h>
#include <frc/geometry/Rotation2d.h>
#include <frc/geometry/Translation3d.h>
#include <photon/estimation/OpenCVHelp.h>

View File

@@ -38,8 +38,7 @@
#include <opencv2/objdetect.hpp>
#include <units/length.h>
#include "SimCameraProperties.h"
#include "photon/estimation/RotTrlTransform3d.h"
#include "photon/simulation/SimCameraProperties.h"
namespace mathutil {
template <typename T>

View File

@@ -24,7 +24,6 @@
#include "photon/PhotonPoseEstimator.h"
#include <map>
#include <utility>
#include <vector>

View File

@@ -22,12 +22,11 @@
* SOFTWARE.
*/
#include <iostream>
#include <gtest/gtest.h>
#include <wpi/print.h>
#include "PhotonVersion.h"
TEST(VersionTest, PrintVersion) {
std::cout << photon::PhotonVersion::versionString << std::endl;
wpi::println("{}", photon::PhotonVersion::versionString);
}

View File

@@ -24,8 +24,6 @@
#include "photon/simulation/VisionSystemSim.h"
#include <chrono>
#include <thread>
#include <tuple>
#include <vector>
@@ -33,6 +31,7 @@
#include <wpi/deprecated.h>
#include "photon/PhotonUtils.h"
#include "photon/estimation/VisionEstimation.h"
// Ignore GetLatestResult warnings
WPI_IGNORE_DEPRECATED

View File

@@ -17,20 +17,14 @@
#include "net/TimeSyncClient.h"
#include <atomic>
#include <chrono>
#include <cstdlib>
#include <cstring>
#include <ctime>
#include <iostream>
#include <mutex>
#include <thread>
#include <Eigen/Core>
#include <wpi/Logger.h>
#include <wpi/print.h>
#include <wpi/struct/Struct.h>
#include <wpinet/UDPClient.h>
#include <wpinet/uv/util.h>
#include "ntcore_cpp.h"

View File

@@ -17,22 +17,18 @@
#include "net/TimeSyncServer.h"
#include <atomic>
#include <chrono>
#include <cstdlib>
#include <cstring>
#include <ctime>
#include <iostream>
#include <mutex>
#include <thread>
#include <ntcore_cpp.h>
#include <wpi/Logger.h>
#include <wpi/print.h>
#include <wpi/struct/Struct.h>
#include <wpinet/UDPClient.h>
#include <wpinet/uv/util.h>
#include "ntcore_cpp.h"
#include "net/TimeSyncStructs.h"
static void ServerLoggerFunc(unsigned int level, const char* file,
unsigned int line, const char* msg) {

View File

@@ -17,11 +17,8 @@
#include "photon/constrained_solvepnp/wrap/casadi_wrapper.h"
#include <chrono>
#include <cstdio>
#include <iostream>
#include <optional>
#include <vector>
#include <Eigen/Cholesky>
#include <Eigen/Core>
@@ -192,10 +189,10 @@ constrained_solvepnp::do_optimization(
fmt::println("{} tags", nTags);
// fmt::println("nstate {}", nState);
std::cout << "robot2camera:\n" << robot2camera << std::endl;
std::cout << "x guess:\n" << x_guess << std::endl;
std::cout << "field2pt:\n" << field2points << std::endl;
std::cout << "observations:\n" << point_observations << std::endl;
fmt::println("robot2camera:\n{}", robot2camera);
fmt::println("x guess:\n{}", x_guess);
fmt::println("field2pt:\n{}", field2points);
fmt::println("observations:\n{}", point_observations);
fmt::println("---------^^^^^^^^---------");
}
@@ -252,7 +249,7 @@ constrained_solvepnp::do_optimization(
auto H_ldlt = H.ldlt();
if (H_ldlt.info() != Eigen::Success) {
std::cerr << "LDLT decomp failed! H=" << std::endl << H << std::endl;
fmt::println(stderr, "LDLT decomp failed! H=\n{}", H);
return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE};
}
@@ -276,7 +273,7 @@ constrained_solvepnp::do_optimization(
H_ldlt = H_reg.ldlt();
if (H_ldlt.info() != Eigen::Success) {
std::cerr << "LDLT decomp failed! H=" << std::endl << H << std::endl;
fmt::println(stderr, "LDLT decomp failed! H=\n{}", H);
return wpi::unexpected{slp::ExitStatus::LOCALLY_INFEASIBLE};
}

View File

@@ -17,13 +17,10 @@
#include "photon/estimation/VisionEstimation.h"
#include <iostream>
#include <utility>
#include <vector>
#include "photon/constrained_solvepnp/wrap/casadi_wrapper.h"
#include "photon/estimation/OpenCVHelp.h"
#include "photon/targeting/MultiTargetPNPResult.h"
namespace photon {
namespace VisionEstimation {

View File

@@ -17,14 +17,4 @@
#include "photon/targeting/PhotonTrackedTarget.h"
#include <algorithm>
#include <iostream>
#include <utility>
#include <vector>
#include <frc/geometry/Translation2d.h>
#include <wpi/SmallVector.h>
static constexpr const uint8_t MAX_CORNERS = 8;
namespace photon {} // namespace photon

View File

@@ -17,31 +17,21 @@
#pragma once
#include <atomic>
#include <chrono>
#include <cstdlib>
#include <cstring>
#include <ctime>
#include <functional>
#include <iostream>
#include <memory>
#include <mutex>
#include <string>
#include <thread>
#include <frc/filter/MedianFilter.h>
#include <wpi/Logger.h>
#include <wpi/print.h>
#include <wpi/static_circular_buffer.h>
#include <wpi/struct/Struct.h>
#include <wpinet/EventLoopRunner.h>
#include <wpinet/UDPClient.h>
#include <wpinet/uv/Buffer.h>
#include <wpinet/uv/Timer.h>
#include <wpinet/uv/Udp.h>
#include "TimeSyncStructs.h"
#include "ntcore_cpp.h"
namespace wpi {
namespace tsp {

View File

@@ -17,30 +17,18 @@
#pragma once
#include <atomic>
#include <chrono>
#include <cstdlib>
#include <cstring>
#include <ctime>
#include <functional>
#include <iostream>
#include <memory>
#include <mutex>
#include <string>
#include <thread>
#include <wpi/Logger.h>
#include <wpi/print.h>
#include <wpi/struct/Struct.h>
#include <wpinet/EventLoopRunner.h>
#include <wpinet/UDPClient.h>
#include <wpinet/uv/Buffer.h>
#include <wpinet/uv/Timer.h>
#include <wpinet/uv/Udp.h>
#include "TimeSyncStructs.h"
#include "ntcore_cpp.h"
namespace wpi {
namespace tsp {

View File

@@ -17,17 +17,13 @@
#pragma once
#include <algorithm>
#include <bit>
#include <cstring>
#include <iostream>
#include <concepts>
#include <cstdint>
#include <optional>
#include <span>
#include <string>
#include <string_view>
#include <vector>
#include <wpi/Demangle.h>
#include <wpi/ct_string.h>
#include <wpi/struct/Struct.h>
namespace photon {

View File

@@ -30,7 +30,6 @@
#define OPENCV_DISABLE_EIGEN_TENSOR_SUPPORT
#include <opencv2/core/eigen.hpp>
#include "photon/targeting/MultiTargetPNPResult.h"
#include "photon/targeting/PnpResult.h"
#include "photon/targeting/TargetCorner.h"

View File

@@ -102,7 +102,5 @@ class NTTopicSet {
cameraDistortionPublisher =
subTable->GetDoubleArrayTopic("cameraDistortion").Publish();
}
private:
};
} // namespace photon

View File

@@ -19,11 +19,6 @@
#include <utility>
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>
#include "PnpResult.h"
#include "photon/dataflow/structures/Packet.h"
#include "photon/struct/MultiTargetPNPResultStruct.h"
namespace photon {

View File

@@ -18,16 +18,13 @@
#pragma once
#include <span>
#include <string>
#include <utility>
#include <units/time.h>
#include <wpi/SmallVector.h>
#include "MultiTargetPNPResult.h"
#include "PhotonTrackedTarget.h"
#include "fmt/base.h"
#include "photon/dataflow/structures/Packet.h"
#include "photon/struct/PhotonPipelineResultStruct.h"
namespace photon {

View File

@@ -17,13 +17,10 @@
#pragma once
#include <cstddef>
#include <string>
#include <utility>
#include <vector>
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>
#include "photon/struct/PhotonTrackedTargetStruct.h"

View File

@@ -19,9 +19,6 @@
#include <utility>
#include <frc/geometry/Transform3d.h>
#include "photon/dataflow/structures/Packet.h"
#include "photon/struct/PnpResultStruct.h"
namespace photon {

View File

@@ -15,13 +15,9 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#include <iostream>
#include <span>
#include <vector>
#include <fmt/core.h>
#include <fmt/ranges.h>
#include "org_photonvision_jni_ConstrainedSolvepnpJni.h"
#include "photon/constrained_solvepnp/wrap/casadi_wrapper.h"
@@ -72,18 +68,6 @@ Java_org_photonvision_jni_ConstrainedSolvepnpJni_do_1optimization
pointObservationsMat(pointObservationsVec.data(), 2,
pointObservationsVec.size() / 2);
#if 0
fmt::println("======================================================");
fmt::println("Got robot2camera raw {}", robot2cameraVec);
fmt::println("Camera cal {} {} {} {}", cameraCal_.fx, cameraCal_.fy,
cameraCal_.cx, cameraCal_.cy);
fmt::println("{} tags", nTags);
std::cout << "robot2camera:\n" << robot2cameraMat << std::endl;
std::cout << "x guess:\n" << xGuessMat << std::endl;
std::cout << "field2pt:\n" << field2pointsMat << std::endl;
std::cout << "observations:\n" << pointObservationsMat << std::endl;
#endif
wpi::expected<constrained_solvepnp::RobotStateMat, slp::ExitStatus> result =
constrained_solvepnp::do_optimization(
headingFree, nTags, cameraCal_, robot2cameraMat, xGuessMat,

View File

@@ -15,8 +15,6 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#include <cstdio>
#include <org_photonvision_jni_TimeSyncClient.h>
#include <org_photonvision_jni_TimeSyncServer.h>

View File

@@ -15,12 +15,9 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#include <chrono>
#include <cstdio>
#include <iostream>
#include <vector>
#include <frc/fmt/Eigen.h>
#include <gtest/gtest.h>
#include <wpi/print.h>
#include <wpi/timestamp.h>
#include "photon/constrained_solvepnp/wrap/casadi_wrapper.h"
@@ -169,11 +166,10 @@ void print_cost(casadi_real robot_x, casadi_real robot_y,
x_guess, field2points, point_observations, 0, 0);
auto end = wpi::Now();
std::cout << i << "," << static_cast<bool>(x_out) << "," << end - start
<< std::endl;
std::cout << "Solution:"
<< x_out.value_or(constrained_solvepnp::RobotStateMat::Identity())
<< std::endl;
wpi::println("{},{},{}", i, static_cast<bool>(x_out), end - start);
wpi::println(
"Solution: {}",
x_out.value_or(constrained_solvepnp::RobotStateMat::Identity()));
// std::cout << "iter "
// << i
// // << "\nGuess:\n" << x_guess << "\n Optimized ->\n"

View File

@@ -19,6 +19,7 @@
#include <hal/HAL.h>
#include <net/TimeSyncClient.h>
#include <net/TimeSyncServer.h>
#include <wpi/print.h>
TEST(TimeSyncProtocolTest, Smoketest) {
using namespace wpi::tsp;

View File

@@ -24,8 +24,6 @@
#include "Robot.h"
#include <iostream>
#include <frc/simulation/BatterySim.h>
#include <frc/simulation/RoboRioSim.h>
#include <photon/PhotonUtils.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveDrive.h"
#include <iostream>
#include <string>
#include <frc/TimedRobot.h>

View File

@@ -24,8 +24,6 @@
#include "subsystems/SwerveDriveSim.h"
#include <iostream>
#include <frc/RobotController.h>
#include <frc/system/Discretization.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveModule.h"
#include <iostream>
#include <string>
#include <frc/MathUtil.h>

View File

@@ -24,8 +24,6 @@
#include "Robot.h"
#include <iostream>
#include <frc/simulation/BatterySim.h>
#include <frc/simulation/RoboRioSim.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveDrive.h"
#include <iostream>
#include <string>
#include <frc/TimedRobot.h>

View File

@@ -24,8 +24,6 @@
#include "subsystems/SwerveDriveSim.h"
#include <iostream>
#include <frc/RobotController.h>
#include <frc/system/Discretization.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveModule.h"
#include <iostream>
#include <string>
#include <frc/MathUtil.h>

View File

@@ -24,8 +24,6 @@
#include "Robot.h"
#include <iostream>
#include <frc/simulation/BatterySim.h>
#include <frc/simulation/RoboRioSim.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveDrive.h"
#include <iostream>
#include <string>
#include <frc/TimedRobot.h>

View File

@@ -24,8 +24,6 @@
#include "subsystems/SwerveDriveSim.h"
#include <iostream>
#include <frc/RobotController.h>
#include <frc/system/Discretization.h>

View File

@@ -24,7 +24,6 @@
#include "subsystems/SwerveModule.h"
#include <iostream>
#include <string>
#include <frc/MathUtil.h>

View File

@@ -16,7 +16,6 @@
*/
#include <string.h>
#include <regex>
/*
* Autogenerated file! Do not manually edit this file. This version is