Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 1 | #include "frc971/vision/visualize_robot.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 2 | |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 3 | #include "glog/logging.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 4 | #include <opencv2/calib3d.hpp> |
| 5 | #include <opencv2/core/eigen.hpp> |
| 6 | #include <opencv2/highgui/highgui.hpp> |
| 7 | #include <opencv2/imgproc.hpp> |
| 8 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame^] | 9 | namespace frc971::vision { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 10 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 11 | void VisualizeRobot::SetDefaultViewpoint(int image_width, double focal_length) { |
| 12 | // 10 meters above the origin, rotated so the camera faces straight down |
| 13 | Eigen::Translation3d camera_trans(0, 0, 10.0); |
| 14 | Eigen::AngleAxisd camera_rot(M_PI, Eigen::Vector3d::UnitX()); |
| 15 | Eigen::Affine3d camera_viewpoint = camera_trans * camera_rot; |
| 16 | SetViewpoint(camera_viewpoint); |
| 17 | |
| 18 | cv::Mat camera_mat; |
| 19 | double half_width = static_cast<double>(image_width) / 2.0; |
| 20 | double intr[] = {focal_length, 0.0, half_width, 0.0, focal_length, |
| 21 | half_width, 0.0, 0.0, 1.0}; |
| 22 | camera_mat = cv::Mat(3, 3, CV_64FC1, intr); |
| 23 | SetCameraParameters(camera_mat); |
| 24 | |
| 25 | cv::Mat dist_coeffs = cv::Mat(1, 5, CV_64F, 0.0); |
| 26 | SetDistortionCoefficients(dist_coeffs); |
| 27 | } |
| 28 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 29 | cv::Point VisualizeRobot::ProjectPoint(Eigen::Vector3d T_world_point) { |
| 30 | // Map 3D point in world coordinates to camera frame |
| 31 | Eigen::Vector3d T_camera_point = H_world_viewpoint_.inverse() * T_world_point; |
| 32 | |
| 33 | cv::Vec3d T_camera_point_cv; |
| 34 | cv::eigen2cv(T_camera_point, T_camera_point_cv); |
| 35 | |
| 36 | // Project 3d point in camera frame via camera intrinsics |
| 37 | cv::Mat proj_point = camera_mat_ * cv::Mat(T_camera_point_cv); |
| 38 | cv::Point projected_point( |
| 39 | proj_point.at<double>(0, 0) / proj_point.at<double>(0, 2), |
| 40 | proj_point.at<double>(0, 1) / proj_point.at<double>(0, 2)); |
| 41 | return projected_point; |
| 42 | } |
| 43 | |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 44 | void VisualizeRobot::DrawLine(Eigen::Vector3d start3d, Eigen::Vector3d end3d, |
| 45 | cv::Scalar color) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 46 | cv::Point start2d = ProjectPoint(start3d); |
| 47 | cv::Point end2d = ProjectPoint(end3d); |
| 48 | |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 49 | cv::line(image_, start2d, end2d, color); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 50 | } |
| 51 | |
| 52 | void VisualizeRobot::DrawFrameAxes(Eigen::Affine3d H_world_target, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 53 | std::string label, cv::Scalar label_color, |
| 54 | double axis_scale) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 55 | // Map origin to display from global (world) frame to camera frame |
| 56 | Eigen::Affine3d H_viewpoint_target = |
| 57 | H_world_viewpoint_.inverse() * H_world_target; |
| 58 | |
| 59 | // Extract into OpenCV vectors |
| 60 | cv::Mat H_viewpoint_target_mat; |
| 61 | cv::eigen2cv(H_viewpoint_target.matrix(), H_viewpoint_target_mat); |
| 62 | |
| 63 | // Convert to opencv R, T for using drawFrameAxes |
| 64 | cv::Vec3d rvec, tvec; |
| 65 | tvec = H_viewpoint_target_mat(cv::Rect(3, 0, 1, 3)); |
| 66 | cv::Mat r_mat = H_viewpoint_target_mat(cv::Rect(0, 0, 3, 3)); |
| 67 | cv::Rodrigues(r_mat, rvec); |
| 68 | |
| 69 | cv::drawFrameAxes(image_, camera_mat_, dist_coeffs_, rvec, tvec, axis_scale); |
| 70 | |
| 71 | if (label != "") { |
| 72 | // Grab x axis direction |
| 73 | cv::Vec3d label_offset = r_mat.col(0); |
| 74 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 75 | // Find 3D coordinate of point at the end of the x-axis, and put label there |
| 76 | // Bump it just a few (5) pixels to the right, to make it read easier |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 77 | cv::Mat label_coord_res = |
| 78 | camera_mat_ * cv::Mat(tvec + label_offset * axis_scale); |
| 79 | cv::Vec3d label_coord = label_coord_res.col(0); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 80 | label_coord[0] = label_coord[0] / label_coord[2] + 5; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 81 | label_coord[1] = label_coord[1] / label_coord[2]; |
| 82 | cv::putText(image_, label, cv::Point(label_coord[0], label_coord[1]), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 83 | cv::FONT_HERSHEY_PLAIN, 1.0, label_color); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 84 | } |
| 85 | } |
| 86 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 87 | void VisualizeRobot::DrawRobotOutline(Eigen::Affine3d H_world_robot, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 88 | std::string label, cv::Scalar color) { |
| 89 | DrawFrameAxes(H_world_robot, label, color); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 90 | const double kBotHalfWidth = 0.75 / 2.0; |
| 91 | const double kBotHalfLength = 1.0 / 2.0; |
| 92 | // Compute coordinates for front/rear and right/left corners |
| 93 | Eigen::Vector3d fr_corner = |
| 94 | H_world_robot * Eigen::Vector3d(kBotHalfLength, kBotHalfWidth, 0); |
| 95 | Eigen::Vector3d fl_corner = |
| 96 | H_world_robot * Eigen::Vector3d(kBotHalfLength, -kBotHalfWidth, 0); |
| 97 | Eigen::Vector3d rl_corner = |
| 98 | H_world_robot * Eigen::Vector3d(-kBotHalfLength, -kBotHalfWidth, 0); |
| 99 | Eigen::Vector3d rr_corner = |
| 100 | H_world_robot * Eigen::Vector3d(-kBotHalfLength, kBotHalfWidth, 0); |
| 101 | |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 102 | DrawLine(fr_corner, fl_corner, color); |
| 103 | DrawLine(fl_corner, rl_corner, color); |
| 104 | DrawLine(rl_corner, rr_corner, color); |
| 105 | DrawLine(rr_corner, fr_corner, color); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 106 | } |
| 107 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame^] | 108 | } // namespace frc971::vision |