#include <vector>
#include <Eigen/Core>
#include <frc/apriltag/AprilTag.h>
#include <frc/apriltag/AprilTagFieldLayout.h>
#include "TargetModel.h"
#include "photon/targeting/PhotonTrackedTarget.h"
#include "photon/targeting/PnpResult.h"
Go to the source code of this file.
|
| std::vector< frc::AprilTag > | photon::VisionEstimation::GetVisibleLayoutTags (const std::vector< PhotonTrackedTarget > &visTags, const frc::AprilTagFieldLayout &layout) |
| |
| std::optional< photon::PnpResult > | photon::VisionEstimation::EstimateCamPosePNP (const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, const std::vector< PhotonTrackedTarget > &visTags, const frc::AprilTagFieldLayout &layout, const TargetModel &tagModel) |
| |
| std::optional< photon::PnpResult > | photon::VisionEstimation::EstimateRobotPoseConstrainedSolvePNP (const Eigen::Matrix< double, 3, 3 > &cameraMatrix, const Eigen::Matrix< double, 8, 1 > &distCoeffs, const std::vector< photon::PhotonTrackedTarget > &visTags, const frc::Transform3d &robot2Camera, const frc::Pose3d &robotPoseSeed, const frc::AprilTagFieldLayout &layout, const photon::TargetModel &tagModel, bool headingFree, frc::Rotation2d gyroTheta, double gyroErrorScaleFac) |
| |