blob: eb2da9a7b859dd1f91fd52e33ef9b2c6c82f1cf8 [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
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
45void VisualizeRobot::DrawLine(Eigen::Vector3d start3d, Eigen::Vector3d end3d) {
46 cv::Point start2d = ProjectPoint(start3d);
47 cv::Point end2d = ProjectPoint(end3d);
48
Jim Ostrowski49be8232023-03-23 01:00:14 -070049 cv::line(image_, start2d, end2d, cv::Scalar(0, 200, 0));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080050}
51
52void VisualizeRobot::DrawFrameAxes(Eigen::Affine3d H_world_target,
53 std::string label, double axis_scale) {
54 // Map origin to display from global (world) frame to camera frame
55 Eigen::Affine3d H_viewpoint_target =
56 H_world_viewpoint_.inverse() * H_world_target;
57
58 // Extract into OpenCV vectors
59 cv::Mat H_viewpoint_target_mat;
60 cv::eigen2cv(H_viewpoint_target.matrix(), H_viewpoint_target_mat);
61
62 // Convert to opencv R, T for using drawFrameAxes
63 cv::Vec3d rvec, tvec;
64 tvec = H_viewpoint_target_mat(cv::Rect(3, 0, 1, 3));
65 cv::Mat r_mat = H_viewpoint_target_mat(cv::Rect(0, 0, 3, 3));
66 cv::Rodrigues(r_mat, rvec);
67
68 cv::drawFrameAxes(image_, camera_mat_, dist_coeffs_, rvec, tvec, axis_scale);
69
70 if (label != "") {
71 // Grab x axis direction
72 cv::Vec3d label_offset = r_mat.col(0);
73
Jim Ostrowski49be8232023-03-23 01:00:14 -070074 // Find 3D coordinate of point at the end of the x-axis, and put label there
75 // Bump it just a few (5) pixels to the right, to make it read easier
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080076 cv::Mat label_coord_res =
77 camera_mat_ * cv::Mat(tvec + label_offset * axis_scale);
78 cv::Vec3d label_coord = label_coord_res.col(0);
Jim Ostrowski49be8232023-03-23 01:00:14 -070079 label_coord[0] = label_coord[0] / label_coord[2] + 5;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080080 label_coord[1] = label_coord[1] / label_coord[2];
81 cv::putText(image_, label, cv::Point(label_coord[0], label_coord[1]),
82 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(0, 0, 255));
83 }
84}
85
Jim Ostrowski49be8232023-03-23 01:00:14 -070086void VisualizeRobot::DrawRobotOutline(Eigen::Affine3d H_world_robot,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080087 std::string label) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070088 DrawFrameAxes(H_world_robot, label);
89 const double kBotHalfWidth = 0.75 / 2.0;
90 const double kBotHalfLength = 1.0 / 2.0;
91 // Compute coordinates for front/rear and right/left corners
92 Eigen::Vector3d fr_corner =
93 H_world_robot * Eigen::Vector3d(kBotHalfLength, kBotHalfWidth, 0);
94 Eigen::Vector3d fl_corner =
95 H_world_robot * Eigen::Vector3d(kBotHalfLength, -kBotHalfWidth, 0);
96 Eigen::Vector3d rl_corner =
97 H_world_robot * Eigen::Vector3d(-kBotHalfLength, -kBotHalfWidth, 0);
98 Eigen::Vector3d rr_corner =
99 H_world_robot * Eigen::Vector3d(-kBotHalfLength, kBotHalfWidth, 0);
100
101 DrawLine(fr_corner, fl_corner);
102 DrawLine(fl_corner, rl_corner);
103 DrawLine(rl_corner, rr_corner);
104 DrawLine(rr_corner, fr_corner);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800105}
106
107} // namespace vision
108} // namespace frc971