blob: 52a7695c1f7460fc34a298e6789179702a8acdbe [file] [log] [blame]
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08001#include "frc971/vision/visualize_robot.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08002
Austin Schuh99f7c6a2024-06-25 22:07:44 -07003#include "absl/log/check.h"
4#include "absl/log/log.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08005#include <opencv2/calib3d.hpp>
6#include <opencv2/core/eigen.hpp>
7#include <opencv2/highgui/highgui.hpp>
8#include <opencv2/imgproc.hpp>
9
Stephan Pleinesf63bde82024-01-13 15:59:33 -080010namespace frc971::vision {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080011
Jim Ostrowski49be8232023-03-23 01:00:14 -070012void VisualizeRobot::SetDefaultViewpoint(int image_width, double focal_length) {
13 // 10 meters above the origin, rotated so the camera faces straight down
14 Eigen::Translation3d camera_trans(0, 0, 10.0);
15 Eigen::AngleAxisd camera_rot(M_PI, Eigen::Vector3d::UnitX());
16 Eigen::Affine3d camera_viewpoint = camera_trans * camera_rot;
17 SetViewpoint(camera_viewpoint);
18
19 cv::Mat camera_mat;
20 double half_width = static_cast<double>(image_width) / 2.0;
21 double intr[] = {focal_length, 0.0, half_width, 0.0, focal_length,
22 half_width, 0.0, 0.0, 1.0};
23 camera_mat = cv::Mat(3, 3, CV_64FC1, intr);
24 SetCameraParameters(camera_mat);
25
26 cv::Mat dist_coeffs = cv::Mat(1, 5, CV_64F, 0.0);
27 SetDistortionCoefficients(dist_coeffs);
28}
29
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080030cv::Point VisualizeRobot::ProjectPoint(Eigen::Vector3d T_world_point) {
31 // Map 3D point in world coordinates to camera frame
32 Eigen::Vector3d T_camera_point = H_world_viewpoint_.inverse() * T_world_point;
33
34 cv::Vec3d T_camera_point_cv;
35 cv::eigen2cv(T_camera_point, T_camera_point_cv);
36
37 // Project 3d point in camera frame via camera intrinsics
38 cv::Mat proj_point = camera_mat_ * cv::Mat(T_camera_point_cv);
39 cv::Point projected_point(
40 proj_point.at<double>(0, 0) / proj_point.at<double>(0, 2),
41 proj_point.at<double>(0, 1) / proj_point.at<double>(0, 2));
42 return projected_point;
43}
44
milind-ua30a4a12023-03-24 20:49:41 -070045void VisualizeRobot::DrawLine(Eigen::Vector3d start3d, Eigen::Vector3d end3d,
46 cv::Scalar color) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080047 cv::Point start2d = ProjectPoint(start3d);
48 cv::Point end2d = ProjectPoint(end3d);
49
milind-ua30a4a12023-03-24 20:49:41 -070050 cv::line(image_, start2d, end2d, color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080051}
52
53void VisualizeRobot::DrawFrameAxes(Eigen::Affine3d H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -070054 std::string label, cv::Scalar label_color,
55 double axis_scale) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080056 // Map origin to display from global (world) frame to camera frame
57 Eigen::Affine3d H_viewpoint_target =
58 H_world_viewpoint_.inverse() * H_world_target;
59
60 // Extract into OpenCV vectors
61 cv::Mat H_viewpoint_target_mat;
62 cv::eigen2cv(H_viewpoint_target.matrix(), H_viewpoint_target_mat);
63
64 // Convert to opencv R, T for using drawFrameAxes
65 cv::Vec3d rvec, tvec;
66 tvec = H_viewpoint_target_mat(cv::Rect(3, 0, 1, 3));
67 cv::Mat r_mat = H_viewpoint_target_mat(cv::Rect(0, 0, 3, 3));
68 cv::Rodrigues(r_mat, rvec);
69
70 cv::drawFrameAxes(image_, camera_mat_, dist_coeffs_, rvec, tvec, axis_scale);
71
72 if (label != "") {
73 // Grab x axis direction
74 cv::Vec3d label_offset = r_mat.col(0);
75
Jim Ostrowski49be8232023-03-23 01:00:14 -070076 // Find 3D coordinate of point at the end of the x-axis, and put label there
77 // Bump it just a few (5) pixels to the right, to make it read easier
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080078 cv::Mat label_coord_res =
79 camera_mat_ * cv::Mat(tvec + label_offset * axis_scale);
80 cv::Vec3d label_coord = label_coord_res.col(0);
Jim Ostrowski49be8232023-03-23 01:00:14 -070081 label_coord[0] = label_coord[0] / label_coord[2] + 5;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080082 label_coord[1] = label_coord[1] / label_coord[2];
83 cv::putText(image_, label, cv::Point(label_coord[0], label_coord[1]),
milind-ua30a4a12023-03-24 20:49:41 -070084 cv::FONT_HERSHEY_PLAIN, 1.0, label_color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080085 }
86}
87
Jim Ostrowski49be8232023-03-23 01:00:14 -070088void VisualizeRobot::DrawRobotOutline(Eigen::Affine3d H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -070089 std::string label, cv::Scalar color) {
90 DrawFrameAxes(H_world_robot, label, color);
Jim Ostrowski49be8232023-03-23 01:00:14 -070091 const double kBotHalfWidth = 0.75 / 2.0;
92 const double kBotHalfLength = 1.0 / 2.0;
93 // Compute coordinates for front/rear and right/left corners
94 Eigen::Vector3d fr_corner =
95 H_world_robot * Eigen::Vector3d(kBotHalfLength, kBotHalfWidth, 0);
96 Eigen::Vector3d fl_corner =
97 H_world_robot * Eigen::Vector3d(kBotHalfLength, -kBotHalfWidth, 0);
98 Eigen::Vector3d rl_corner =
99 H_world_robot * Eigen::Vector3d(-kBotHalfLength, -kBotHalfWidth, 0);
100 Eigen::Vector3d rr_corner =
101 H_world_robot * Eigen::Vector3d(-kBotHalfLength, kBotHalfWidth, 0);
102
milind-ua30a4a12023-03-24 20:49:41 -0700103 DrawLine(fr_corner, fl_corner, color);
104 DrawLine(fl_corner, rl_corner, color);
105 DrawLine(rl_corner, rr_corner, color);
106 DrawLine(rr_corner, fr_corner, color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800107}
108
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800109} // namespace frc971::vision