Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 1 | #include <math.h> |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 2 | |
| 3 | #include "Eigen/Dense" |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 4 | #include "absl/log/check.h" |
| 5 | #include "absl/log/log.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 6 | #include <opencv2/aruco.hpp> |
| 7 | #include <opencv2/aruco/charuco.hpp> |
| 8 | #include <opencv2/calib3d.hpp> |
| 9 | #include <opencv2/core/eigen.hpp> |
| 10 | #include <opencv2/highgui/highgui.hpp> |
| 11 | #include <opencv2/imgproc.hpp> |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 12 | |
| 13 | #include "aos/init.h" |
| 14 | #include "aos/logging/logging.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 15 | #include "aos/time/time.h" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 16 | #include "frc971/vision/visualize_robot.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 17 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 18 | namespace frc971::vision { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 19 | |
| 20 | // Show / test the basics of visualizing the robot frames |
| 21 | void Main(int /*argc*/, char ** /* argv */) { |
| 22 | VisualizeRobot vis_robot; |
| 23 | |
| 24 | int image_width = 500; |
| 25 | cv::Mat image_mat = |
| 26 | cv::Mat::zeros(cv::Size(image_width, image_width), CV_8UC3); |
| 27 | vis_robot.SetImage(image_mat); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 28 | double focal_length = 1000.0; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 29 | vis_robot.SetDefaultViewpoint(image_width, focal_length); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 30 | |
| 31 | // Go around the clock and plot the coordinate frame at different rotations |
| 32 | for (int i = 0; i < 12; i++) { |
| 33 | double angle = M_PI * double(i) / 6.0; |
| 34 | Eigen::Vector3d trans; |
| 35 | trans << 1.0 * cos(angle), 1.0 * sin(angle), 0.0; |
| 36 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 37 | Eigen::Affine3d offset_rotate_origin = |
| 38 | Eigen::Translation3d(trans) * |
| 39 | Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitX()); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 40 | |
| 41 | vis_robot.DrawFrameAxes(offset_rotate_origin, std::to_string(i)); |
| 42 | } |
| 43 | |
| 44 | // Display the result |
| 45 | cv::imshow("Display", image_mat); |
| 46 | cv::waitKey(); |
| 47 | } |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 48 | } // namespace frc971::vision |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 49 | |
| 50 | int main(int argc, char **argv) { |
| 51 | aos::InitGoogle(&argc, &argv); |
| 52 | |
| 53 | frc971::vision::Main(argc, argv); |
| 54 | } |