blob: 0bbe507a9052d5ecf29968ddf387b0002ce621e1 [file] [log] [blame]
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08001#include "frc971/vision/visualize_robot.h"
2#include "glog/logging.h"
3
4#include <opencv2/calib3d.hpp>
5#include <opencv2/core/eigen.hpp>
6#include <opencv2/highgui/highgui.hpp>
7#include <opencv2/imgproc.hpp>
8
9namespace frc971 {
10namespace vision {
11
12cv::Point VisualizeRobot::ProjectPoint(Eigen::Vector3d T_world_point) {
13 // Map 3D point in world coordinates to camera frame
14 Eigen::Vector3d T_camera_point = H_world_viewpoint_.inverse() * T_world_point;
15
16 cv::Vec3d T_camera_point_cv;
17 cv::eigen2cv(T_camera_point, T_camera_point_cv);
18
19 // Project 3d point in camera frame via camera intrinsics
20 cv::Mat proj_point = camera_mat_ * cv::Mat(T_camera_point_cv);
21 cv::Point projected_point(
22 proj_point.at<double>(0, 0) / proj_point.at<double>(0, 2),
23 proj_point.at<double>(0, 1) / proj_point.at<double>(0, 2));
24 return projected_point;
25}
26
27void VisualizeRobot::DrawLine(Eigen::Vector3d start3d, Eigen::Vector3d end3d) {
28 cv::Point start2d = ProjectPoint(start3d);
29 cv::Point end2d = ProjectPoint(end3d);
30
31 cv::line(image_, start2d, end2d, cv::Scalar(0, 0, 255));
32}
33
34void VisualizeRobot::DrawFrameAxes(Eigen::Affine3d H_world_target,
35 std::string label, double axis_scale) {
36 // Map origin to display from global (world) frame to camera frame
37 Eigen::Affine3d H_viewpoint_target =
38 H_world_viewpoint_.inverse() * H_world_target;
39
40 // Extract into OpenCV vectors
41 cv::Mat H_viewpoint_target_mat;
42 cv::eigen2cv(H_viewpoint_target.matrix(), H_viewpoint_target_mat);
43
44 // Convert to opencv R, T for using drawFrameAxes
45 cv::Vec3d rvec, tvec;
46 tvec = H_viewpoint_target_mat(cv::Rect(3, 0, 1, 3));
47 cv::Mat r_mat = H_viewpoint_target_mat(cv::Rect(0, 0, 3, 3));
48 cv::Rodrigues(r_mat, rvec);
49
50 cv::drawFrameAxes(image_, camera_mat_, dist_coeffs_, rvec, tvec, axis_scale);
51
52 if (label != "") {
53 // Grab x axis direction
54 cv::Vec3d label_offset = r_mat.col(0);
55
56 // Find 3D coordinate of point at the end of the x-axis, and project it
57 cv::Mat label_coord_res =
58 camera_mat_ * cv::Mat(tvec + label_offset * axis_scale);
59 cv::Vec3d label_coord = label_coord_res.col(0);
60 label_coord[0] = label_coord[0] / label_coord[2];
61 label_coord[1] = label_coord[1] / label_coord[2];
62 cv::putText(image_, label, cv::Point(label_coord[0], label_coord[1]),
63 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(0, 0, 255));
64 }
65}
66
67void VisualizeRobot::DrawBoardOutline(Eigen::Affine3d H_world_board,
68 std::string label) {
69 LOG(INFO) << "Not yet implemented; drawing axes only";
70 DrawFrameAxes(H_world_board, label);
71}
72
73} // namespace vision
74} // namespace frc971