blob: f5e75af6789980429089e56a594ba8ac5dcd45b2 [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
27 // Set the viewpoint of the camera relative to a global origin
28 void SetViewpoint(Eigen::Affine3d view_origin) {
29 H_world_viewpoint_ = view_origin;
30 }
31
32 // Set camera parameters (for projection into a virtual view)
33 void SetCameraParameters(cv::Mat camera_intrinsics) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070034 camera_mat_ = camera_intrinsics.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080035 }
36
37 // Set distortion coefficients (defaults to 0)
38 void SetDistortionCoefficients(cv::Mat dist_coeffs) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070039 dist_coeffs_ = dist_coeffs.clone();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080040 }
41
Jim Ostrowski49be8232023-03-23 01:00:14 -070042 // Sets up a default camera view 10 m above the origin, pointing down
43 // Uses image_width and focal_length to define a default camera projection
44 // matrix
45 void SetDefaultViewpoint(int image_width = 1000,
46 double focal_length = 1000.0);
47
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080048 // Helper function to project a point in 3D to the virtual image coordinates
49 cv::Point ProjectPoint(Eigen::Vector3d point3d);
50
51 // Draw a line connecting two 3D points
52 void DrawLine(Eigen::Vector3d start, Eigen::Vector3d end);
53
54 // Draw coordinate frame for a target frame relative to the world frame
55 // Axes are drawn (x,y,z) -> (red, green, blue)
56 void DrawFrameAxes(Eigen::Affine3d H_world_target, std::string label = "",
57 double axis_scale = 0.25);
58
Jim Ostrowski49be8232023-03-23 01:00:14 -070059 // TODO<Jim>: Also implement DrawBoardOutline? Maybe one function w/
60 // parameters?
61 void DrawRobotOutline(Eigen::Affine3d H_world_robot, std::string label = "");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080062
63 Eigen::Affine3d H_world_viewpoint_; // Where to view the world from
64 cv::Mat image_; // Image to draw on
65 cv::Mat camera_mat_; // Virtual camera intrinsics (defines fov, center)
66 cv::Mat dist_coeffs_; // Distortion coefficients, if desired (only used in
67 // DrawFrameAxes
68};
69} // namespace vision
70} // namespace frc971
71
72#endif // FRC971_VISION_VISUALIZE_ROBOT_H_