@@ -40,28 +40,43 @@ geometry_msgs::msg::Transform tf_from_cv(const cv::Mat_<double>& tvec, const cv:
40
40
return t;
41
41
}
42
42
43
- pose_estimation_f apriltag_homography = [](apriltag_detection_t * const detection, const std::array<double , 4 >& intr, double tagsize) -> geometry_msgs::msg::Transform {
43
+ geometry_msgs::msg::Transform
44
+ homography (apriltag_detection_t * const detection, const std::array<double , 4 >& intr, double tagsize)
45
+ {
44
46
apriltag_detection_info_t info = {detection, tagsize, intr[0 ], intr[1 ], intr[2 ], intr[3 ]};
45
47
46
48
apriltag_pose_t pose;
47
49
estimate_pose_for_tag_homography (&info, &pose);
48
50
49
51
return tf_from_apriltag_pose (pose);
50
- };
51
-
52
- pose_estimation_f solve_pnp = [](apriltag_detection_t * const detection, const std::array<double , 4 >& intr, double tagsize) -> geometry_msgs::msg::Transform {
53
- const double half_tagsize = 0.5 * tagsize;
54
- const std::vector<cv::Point3d> objectPoints{{-half_tagsize, -half_tagsize, 0 }, {+half_tagsize, -half_tagsize, 0 }, {+half_tagsize, +half_tagsize, 0 }, {-half_tagsize, +half_tagsize, 0 }};
52
+ }
55
53
56
- std::vector<cv::Point2d> imagePoints;
57
- constexpr double tag_x[4 ] = {-1 , 1 , 1 , -1 };
58
- constexpr double tag_y[4 ] = {1 , 1 , -1 , -1 };
59
- for (int i = 0 ; i < 4 ; i++) {
60
- // Homography projection taking tag local frame coordinates to image pixels
61
- double im_x, im_y;
62
- homography_project (detection->H , tag_x[i], tag_y[i], &im_x, &im_y);
63
- imagePoints.push_back (cv::Point2d (im_x, im_y));
64
- }
54
+ geometry_msgs::msg::Transform
55
+ pnp (apriltag_detection_t * const detection, const std::array<double , 4 >& intr, double tagsize)
56
+ {
57
+ const std::vector<cv::Point3d> objectPoints{
58
+ {-tagsize / 2 , -tagsize / 2 , 0 },
59
+ {+tagsize / 2 , -tagsize / 2 , 0 },
60
+ {+tagsize / 2 , +tagsize / 2 , 0 },
61
+ {-tagsize / 2 , +tagsize / 2 , 0 },
62
+ };
63
+
64
+ // std::vector<cv::Point2d> imagePoints;
65
+ // constexpr double tag_x[4] = {-1, 1, 1, -1};
66
+ // constexpr double tag_y[4] = {1, 1, -1, -1};
67
+ // for(int i = 0; i < 4; i++) {
68
+ // // Homography projection taking tag local frame coordinates to image pixels
69
+ // double im_x, im_y;
70
+ // homography_project(detection->H, tag_x[i], tag_y[i], &im_x, &im_y);
71
+ // imagePoints.push_back(cv::Point2d(im_x, im_y));
72
+ // }
73
+
74
+ const std::vector<cv::Point2d> imagePoints{
75
+ {detection->p [0 ][0 ], detection->p [0 ][1 ]},
76
+ {detection->p [1 ][0 ], detection->p [1 ][1 ]},
77
+ {detection->p [2 ][0 ], detection->p [2 ][1 ]},
78
+ {detection->p [3 ][0 ], detection->p [3 ][1 ]},
79
+ };
65
80
66
81
cv::Mat rvec, tvec;
67
82
cv::Matx33d cameraMatrix;
@@ -73,9 +88,9 @@ pose_estimation_f solve_pnp = [](apriltag_detection_t* const detection, const st
73
88
cv::solvePnP (objectPoints, imagePoints, cameraMatrix, {}, rvec, tvec);
74
89
75
90
return tf_from_cv (tvec, rvec);
76
- };
91
+ }
77
92
78
93
const std::unordered_map<std::string, pose_estimation_f> pose_estimation_methods{
79
- {" homography" , apriltag_homography },
80
- {" pnp" , solve_pnp },
94
+ {" homography" , homography },
95
+ {" pnp" , pnp },
81
96
};
0 commit comments