blob: cd8b4d0a9fa1d2487c5502b5072f2e6dfe068052 [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
4#include <opencv2/core.hpp>
5#include <opencv2/highgui.hpp>
6#include <opencv2/imgproc.hpp>
7
8#include "Eigen/Dense"
9#include "Eigen/Geometry"
10
11namespace frc971 {
12namespace vision {
13
14// Helper class to visualize the coordinate frames associated with
15// the robot Based on a virtual camera viewpoint, and camera model,
16// this class can be used to draw 3D coordinate frames in a virtual
17// camera view.
18//
19// Mostly useful just for doing all the projection calculations
20// Leverages Eigen for transforms and opencv for drawing axes
21
22class VisualizeRobot {
23 public:
24 // Set image on which to draw
25 void SetImage(cv::Mat image) { image_ = image; }
26
milind-ua30a4a12023-03-24 20:49:41 -070027 // Sets image to all black.
28 // Uses default_size if no image has been set yet, else image_.size()
29 void ClearImage(cv::Size default_size = cv::Size(1280, 720)) {
30 auto image_size = (image_.data == nullptr ? default_size : image_.size());
31 cv::Mat black_image_mat = cv::Mat::zeros(image_size, CV_8UC3);
32 SetImage(black_image_mat);
33 }
34
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080035 // Set the viewpoint of the camera relative to a global origin
36 void SetViewpoint(Eigen::Affine3d view_origin) {
37 H_world_viewpoint_ = view_origin;
38 }
39
40 // Set camera parameters (for projection into a virtual view)
41 void SetCameraParameters(cv::Mat camera_intrinsics) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070042 camera_mat_ = camera_intrinsics.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080043 }
44
45 // Set distortion coefficients (defaults to 0)
46 void SetDistortionCoefficients(cv::Mat dist_coeffs) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070047 dist_coeffs_ = dist_coeffs.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080048 }
49
Jim Ostrowski49be8232023-03-23 01:00:14 -070050 // Sets up a default camera view 10 m above the origin, pointing down
51 // Uses image_width and focal_length to define a default camera projection
52 // matrix
53 void SetDefaultViewpoint(int image_width = 1000,
54 double focal_length = 1000.0);
55
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080056 // Helper function to project a point in 3D to the virtual image coordinates
57 cv::Point ProjectPoint(Eigen::Vector3d point3d);
58
59 // Draw a line connecting two 3D points
milind-ua30a4a12023-03-24 20:49:41 -070060 void DrawLine(Eigen::Vector3d start, Eigen::Vector3d end,
61 cv::Scalar color = cv::Scalar(0, 200, 0));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080062
63 // Draw coordinate frame for a target frame relative to the world frame
64 // Axes are drawn (x,y,z) -> (red, green, blue)
65 void DrawFrameAxes(Eigen::Affine3d H_world_target, std::string label = "",
milind-ua30a4a12023-03-24 20:49:41 -070066 cv::Scalar label_color = cv::Scalar(0, 0, 255),
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080067 double axis_scale = 0.25);
68
Jim Ostrowski49be8232023-03-23 01:00:14 -070069 // TODO<Jim>: Also implement DrawBoardOutline? Maybe one function w/
70 // parameters?
milind-ua30a4a12023-03-24 20:49:41 -070071 void DrawRobotOutline(Eigen::Affine3d H_world_robot, std::string label = "",
72 cv::Scalar color = cv::Scalar(0, 200, 0));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080073
74 Eigen::Affine3d H_world_viewpoint_; // Where to view the world from
75 cv::Mat image_; // Image to draw on
76 cv::Mat camera_mat_; // Virtual camera intrinsics (defines fov, center)
77 cv::Mat dist_coeffs_; // Distortion coefficients, if desired (only used in
78 // DrawFrameAxes
79};
80} // namespace vision
81} // namespace frc971
82
83#endif // FRC971_VISION_VISUALIZE_ROBOT_H_