blob: 391a0304ebdf0156c5402ef4ed1d56cf6a721bb7 [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) {
34 camera_mat_ = camera_intrinsics;
35 }
36
37 // Set distortion coefficients (defaults to 0)
38 void SetDistortionCoefficients(cv::Mat dist_coeffs) {
39 dist_coeffs_ = dist_coeffs;
40 }
41
42 // Helper function to project a point in 3D to the virtual image coordinates
43 cv::Point ProjectPoint(Eigen::Vector3d point3d);
44
45 // Draw a line connecting two 3D points
46 void DrawLine(Eigen::Vector3d start, Eigen::Vector3d end);
47
48 // Draw coordinate frame for a target frame relative to the world frame
49 // Axes are drawn (x,y,z) -> (red, green, blue)
50 void DrawFrameAxes(Eigen::Affine3d H_world_target, std::string label = "",
51 double axis_scale = 0.25);
52
53 // TODO<Jim>: Need to implement this, and maybe DrawRobotOutline
54 void DrawBoardOutline(Eigen::Affine3d H_world_board, std::string label = "");
55
56 Eigen::Affine3d H_world_viewpoint_; // Where to view the world from
57 cv::Mat image_; // Image to draw on
58 cv::Mat camera_mat_; // Virtual camera intrinsics (defines fov, center)
59 cv::Mat dist_coeffs_; // Distortion coefficients, if desired (only used in
60 // DrawFrameAxes
61};
62} // namespace vision
63} // namespace frc971
64
65#endif // FRC971_VISION_VISUALIZE_ROBOT_H_