diff --git a/src/localization/tag_estimator.cc b/src/localization/tag_estimator.cc index 3d33230..2212dff 100644 --- a/src/localization/tag_estimator.cc +++ b/src/localization/tag_estimator.cc @@ -3,12 +3,14 @@ #include #include #include +#include #include #include #include #include #include #include +#include #include #include "src/localization/position.h" @@ -144,7 +146,7 @@ TagEstimator::TagEstimator(uint image_width, uint image_height, json intrinsics, distortion_coefficients_( distortion_coefficients_from_json(intrinsics)), apriltag_dimensions_(apriltag_dimensions), - verbose_(true) { + verbose_(verbose) { apriltag_detector_ = apriltag_detector_create(); @@ -160,6 +162,13 @@ TagEstimator::TagEstimator(uint image_width, uint image_height, json intrinsics, camera_matrix_from_json(intrinsics), distortion_coefficients_from_json( intrinsics)); + + nt::NetworkTableInstance instance(nt::NetworkTableInstance::GetDefault()); + std::shared_ptr table = instance.GetTable("Orin/Odometry"); + + nt::DoubleArrayTopic odometry_pose_topic = table->GetDoubleArrayTopic("Pose"); + odometry_pose_subscriber_ = + odometry_pose_topic.Subscribe(std::vector{}); } TagEstimator::~TagEstimator() { @@ -197,12 +206,11 @@ std::vector TagEstimator::GetRawPositionEstimates( imagePoints.emplace_back(gpu_detection->p[i][0], gpu_detection->p[i][1]); } - cv::Mat rvec = cv::Mat::zeros(3, 1, CV_64FC1); // output rotation vector - cv::Mat tvec = - cv::Mat::zeros(3, 1, CV_64FC1); // output translation vector + auto [tvec, rvec] = GetTagRelitiveOdometry(gpu_detection->id); + cv::solvePnP(apriltag_dimensions_, imagePoints, camera_matrix_, - distortion_coefficients_, rvec, tvec, false, - cv::SOLVEPNP_IPPE_SQUARE); + distortion_coefficients_, rvec, tvec, true, + cv::SOLVEPNP_ITERATIVE); tag_detection_t estimate; // Currently we do not use transation z, rotation x and rotation y @@ -309,4 +317,40 @@ tag_detection_t TagEstimator::ApplyExtrinsics(tag_detection_t position) const { return position; } +// 0 -> tx +// 1 -> ty +// 2 -> tz +// 3 -> rx +// 4 -> ry +// 5 -> rz +// meters, radians +std::pair TagEstimator::GetTagRelitiveOdometry( + int tag_id) const { + std::vector odometry_pose_raw = odometry_pose_subscriber_.Get(); + frc::Transform3d odometry_pose( + frc::Translation3d(units::meter_t{odometry_pose_raw[0]}, + units::meter_t{odometry_pose_raw[1]}, + units::meter_t{odometry_pose_raw[2]}), + frc::Rotation3d(units::radian_t{odometry_pose_raw[3]}, + units::radian_t{odometry_pose_raw[4]}, + units::radian_t{odometry_pose_raw[5]})); + + frc::Pose3d tag_pose = apriltag_layout_.GetTagPose(tag_id).value(); + frc::Pose3d robot_to_tag = tag_pose.TransformBy(odometry_pose.Inverse()); + + cv::Mat tvec = cv::Mat::zeros(3, 1, CV_64FC1); + tvec.at(2) = robot_to_tag.Translation().X().value(); + tvec.at(0) = robot_to_tag.Translation().Y().value(); + tvec.at(1) = robot_to_tag.Translation().Z().value(); + + cv::Mat rvec = cv::Mat::zeros(3, 1, CV_64FC1); + rvec.at(2) = robot_to_tag.Rotation().X().value(); + rvec.at(0) = robot_to_tag.Rotation().Y().value(); + rvec.at(1) = robot_to_tag.Rotation().Z().value(); + + std::cout << "rvec = " << rvec << std::endl; + std::cout << "tvec = " << tvec << std::endl; + + return std::pair(tvec, rvec); +} } // namespace localization diff --git a/src/localization/tag_estimator.h b/src/localization/tag_estimator.h index c40cb9a..4ae6f3f 100644 --- a/src/localization/tag_estimator.h +++ b/src/localization/tag_estimator.h @@ -1,6 +1,9 @@ #pragma once #include +#include +#include +#include #include #include #include @@ -46,6 +49,7 @@ class TagEstimator { // should be pointer? // Changes the position estimate to be tag relative to absolute feild position tag_detection_t ApplyExtrinsics(tag_detection_t position) const; + std::pair GetTagRelitiveOdometry(int tag_id) const; private: json extrinsics_; @@ -55,6 +59,7 @@ class TagEstimator { cv::Mat camera_matrix_; cv::Mat distortion_coefficients_; std::vector apriltag_dimensions_; + nt::DoubleArraySubscriber odometry_pose_subscriber_; bool verbose_; }; } // namespace localization