blob: c679dbaf7589c30b57731b0491be69227ae0aea9 [file] [log] [blame]
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08001#ifndef FRC971_VISION_VISUALIZE_ROBOT_H_
2#define FRC971_VISION_VISUALIZE_ROBOT_H_
3
Philipp Schrader790cb542023-07-05 21:06:52 -07004#include "Eigen/Dense"
5#include "Eigen/Geometry"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08006#include <opencv2/core.hpp>
7#include <opencv2/highgui.hpp>
8#include <opencv2/imgproc.hpp>
9
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080010namespace frc971 {
11namespace vision {
12
13// Helper class to visualize the coordinate frames associated with
14// the robot Based on a virtual camera viewpoint, and camera model,
15// this class can be used to draw 3D coordinate frames in a virtual
16// camera view.
17//
18// Mostly useful just for doing all the projection calculations
19// Leverages Eigen for transforms and opencv for drawing axes
20
21class VisualizeRobot {
22 public:
milind-u2ab4db12023-03-25 21:59:23 -070023 VisualizeRobot(cv::Size default_size = cv::Size(1280, 720))
24 : default_size_(default_size) {}
25
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080026 // Set image on which to draw
27 void SetImage(cv::Mat image) { image_ = image; }
28
milind-ua30a4a12023-03-24 20:49:41 -070029 // Sets image to all black.
milind-u2ab4db12023-03-25 21:59:23 -070030 // Uses default_size_ if no image has been set yet, else image_.size()
31 void ClearImage() {
32 auto image_size = (image_.data == nullptr ? default_size_ : image_.size());
milind-ua30a4a12023-03-24 20:49:41 -070033 cv::Mat black_image_mat = cv::Mat::zeros(image_size, CV_8UC3);
34 SetImage(black_image_mat);
35 }
36
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080037 // Set the viewpoint of the camera relative to a global origin
38 void SetViewpoint(Eigen::Affine3d view_origin) {
39 H_world_viewpoint_ = view_origin;
40 }
41
42 // Set camera parameters (for projection into a virtual view)
43 void SetCameraParameters(cv::Mat camera_intrinsics) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070044 camera_mat_ = camera_intrinsics.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080045 }
46
47 // Set distortion coefficients (defaults to 0)
48 void SetDistortionCoefficients(cv::Mat dist_coeffs) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070049 dist_coeffs_ = dist_coeffs.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080050 }
51
Jim Ostrowski49be8232023-03-23 01:00:14 -070052 // Sets up a default camera view 10 m above the origin, pointing down
53 // Uses image_width and focal_length to define a default camera projection
54 // matrix
55 void SetDefaultViewpoint(int image_width = 1000,
56 double focal_length = 1000.0);
57
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080058 // Helper function to project a point in 3D to the virtual image coordinates
59 cv::Point ProjectPoint(Eigen::Vector3d point3d);
60
61 // Draw a line connecting two 3D points
milind-ua30a4a12023-03-24 20:49:41 -070062 void DrawLine(Eigen::Vector3d start, Eigen::Vector3d end,
63 cv::Scalar color = cv::Scalar(0, 200, 0));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080064
65 // Draw coordinate frame for a target frame relative to the world frame
66 // Axes are drawn (x,y,z) -> (red, green, blue)
67 void DrawFrameAxes(Eigen::Affine3d H_world_target, std::string label = "",
milind-ua30a4a12023-03-24 20:49:41 -070068 cv::Scalar label_color = cv::Scalar(0, 0, 255),
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080069 double axis_scale = 0.25);
70
Jim Ostrowski49be8232023-03-23 01:00:14 -070071 // TODO<Jim>: Also implement DrawBoardOutline? Maybe one function w/
72 // parameters?
milind-ua30a4a12023-03-24 20:49:41 -070073 void DrawRobotOutline(Eigen::Affine3d H_world_robot, std::string label = "",
74 cv::Scalar color = cv::Scalar(0, 200, 0));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080075
76 Eigen::Affine3d H_world_viewpoint_; // Where to view the world from
77 cv::Mat image_; // Image to draw on
milind-u2ab4db12023-03-25 21:59:23 -070078 cv::Mat camera_mat_; // Virtual camera intrinsics (defines fov, center)
79 cv::Mat dist_coeffs_; // Distortion coefficients, if desired (only used in
80 // DrawFrameAxes
81 cv::Size default_size_; // Default image size
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080082};
83} // namespace vision
84} // namespace frc971
85
86#endif // FRC971_VISION_VISUALIZE_ROBOT_H_