blob: 55932ef1fa1ec71aed7a54c77ef2bd1ee77638d3 [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
3#include <opencv2/calib3d.hpp>
4#include <opencv2/core/eigen.hpp>
5#include <opencv2/highgui/highgui.hpp>
6#include <opencv2/imgproc.hpp>
7
milind-ua30a4a12023-03-24 20:49:41 -07008#include "glog/logging.h"
9
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080010namespace frc971 {
11namespace vision {
12
Jim Ostrowski49be8232023-03-23 01:00:14 -070013void VisualizeRobot::SetDefaultViewpoint(int image_width, double focal_length) {
14 // 10 meters above the origin, rotated so the camera faces straight down
15 Eigen::Translation3d camera_trans(0, 0, 10.0);
16 Eigen::AngleAxisd camera_rot(M_PI, Eigen::Vector3d::UnitX());
17 Eigen::Affine3d camera_viewpoint = camera_trans * camera_rot;
18 SetViewpoint(camera_viewpoint);
19
20 cv::Mat camera_mat;
21 double half_width = static_cast<double>(image_width) / 2.0;
22 double intr[] = {focal_length, 0.0, half_width, 0.0, focal_length,
23 half_width, 0.0, 0.0, 1.0};
24 camera_mat = cv::Mat(3, 3, CV_64FC1, intr);
25 SetCameraParameters(camera_mat);
26
27 cv::Mat dist_coeffs = cv::Mat(1, 5, CV_64F, 0.0);
28 SetDistortionCoefficients(dist_coeffs);
29}
30
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080031cv::Point VisualizeRobot::ProjectPoint(Eigen::Vector3d T_world_point) {
32 // Map 3D point in world coordinates to camera frame
33 Eigen::Vector3d T_camera_point = H_world_viewpoint_.inverse() * T_world_point;
34
35 cv::Vec3d T_camera_point_cv;
36 cv::eigen2cv(T_camera_point, T_camera_point_cv);
37
38 // Project 3d point in camera frame via camera intrinsics
39 cv::Mat proj_point = camera_mat_ * cv::Mat(T_camera_point_cv);
40 cv::Point projected_point(
41 proj_point.at<double>(0, 0) / proj_point.at<double>(0, 2),
42 proj_point.at<double>(0, 1) / proj_point.at<double>(0, 2));
43 return projected_point;
44}
45
milind-ua30a4a12023-03-24 20:49:41 -070046void VisualizeRobot::DrawLine(Eigen::Vector3d start3d, Eigen::Vector3d end3d,
47 cv::Scalar color) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080048 cv::Point start2d = ProjectPoint(start3d);
49 cv::Point end2d = ProjectPoint(end3d);
50
milind-ua30a4a12023-03-24 20:49:41 -070051 cv::line(image_, start2d, end2d, color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080052}
53
54void VisualizeRobot::DrawFrameAxes(Eigen::Affine3d H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -070055 std::string label, cv::Scalar label_color,
56 double axis_scale) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080057 // Map origin to display from global (world) frame to camera frame
58 Eigen::Affine3d H_viewpoint_target =
59 H_world_viewpoint_.inverse() * H_world_target;
60
61 // Extract into OpenCV vectors
62 cv::Mat H_viewpoint_target_mat;
63 cv::eigen2cv(H_viewpoint_target.matrix(), H_viewpoint_target_mat);
64
65 // Convert to opencv R, T for using drawFrameAxes
66 cv::Vec3d rvec, tvec;
67 tvec = H_viewpoint_target_mat(cv::Rect(3, 0, 1, 3));
68 cv::Mat r_mat = H_viewpoint_target_mat(cv::Rect(0, 0, 3, 3));
69 cv::Rodrigues(r_mat, rvec);
70
71 cv::drawFrameAxes(image_, camera_mat_, dist_coeffs_, rvec, tvec, axis_scale);
72
73 if (label != "") {
74 // Grab x axis direction
75 cv::Vec3d label_offset = r_mat.col(0);
76
Jim Ostrowski49be8232023-03-23 01:00:14 -070077 // Find 3D coordinate of point at the end of the x-axis, and put label there
78 // Bump it just a few (5) pixels to the right, to make it read easier
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080079 cv::Mat label_coord_res =
80 camera_mat_ * cv::Mat(tvec + label_offset * axis_scale);
81 cv::Vec3d label_coord = label_coord_res.col(0);
Jim Ostrowski49be8232023-03-23 01:00:14 -070082 label_coord[0] = label_coord[0] / label_coord[2] + 5;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080083 label_coord[1] = label_coord[1] / label_coord[2];
84 cv::putText(image_, label, cv::Point(label_coord[0], label_coord[1]),
milind-ua30a4a12023-03-24 20:49:41 -070085 cv::FONT_HERSHEY_PLAIN, 1.0, label_color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080086 }
87}
88
Jim Ostrowski49be8232023-03-23 01:00:14 -070089void VisualizeRobot::DrawRobotOutline(Eigen::Affine3d H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -070090 std::string label, cv::Scalar color) {
91 DrawFrameAxes(H_world_robot, label, color);
Jim Ostrowski49be8232023-03-23 01:00:14 -070092 const double kBotHalfWidth = 0.75 / 2.0;
93 const double kBotHalfLength = 1.0 / 2.0;
94 // Compute coordinates for front/rear and right/left corners
95 Eigen::Vector3d fr_corner =
96 H_world_robot * Eigen::Vector3d(kBotHalfLength, kBotHalfWidth, 0);
97 Eigen::Vector3d fl_corner =
98 H_world_robot * Eigen::Vector3d(kBotHalfLength, -kBotHalfWidth, 0);
99 Eigen::Vector3d rl_corner =
100 H_world_robot * Eigen::Vector3d(-kBotHalfLength, -kBotHalfWidth, 0);
101 Eigen::Vector3d rr_corner =
102 H_world_robot * Eigen::Vector3d(-kBotHalfLength, kBotHalfWidth, 0);
103
milind-ua30a4a12023-03-24 20:49:41 -0700104 DrawLine(fr_corner, fl_corner, color);
105 DrawLine(fl_corner, rl_corner, color);
106 DrawLine(rl_corner, rr_corner, color);
107 DrawLine(rr_corner, fr_corner, color);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800108}
109
110} // namespace vision
111} // namespace frc971