blob: d0217442df9ff2286831df2f2e9e2a067322733d [file] [log] [blame]
Jim Ostrowski479bd1c2024-03-01 00:21:13 -08001#include <cmath>
2#include <filesystem>
3#include <regex>
4
5#include "Eigen/Dense"
6#include "Eigen/Geometry"
7#include "absl/strings/str_format.h"
8
9#include "aos/configuration.h"
10#include "aos/events/event_loop.h"
11#include "aos/flatbuffer_merge.h"
12#include "aos/init.h"
13#include "aos/network/team_number.h"
14#include "aos/time/time.h"
15#include "aos/util/file.h"
16#include "frc971/vision/calibration_generated.h"
Jim Ostrowski33208982024-03-02 15:01:45 -080017#include "frc971/vision/vision_util_lib.h"
Jim Ostrowski479bd1c2024-03-01 00:21:13 -080018
19// This is a helper program to build and rename calibration files
20// You can:
21// (1) pass it in a new set of orin #, team #, camera #, to rename the file
22// (2) Pass in extrinsics to set the extrinsics
23// By default, writes to /tmp, but will write to calib_files folder if
24// full path is given and calibration_folder is blank
25
26DEFINE_string(orig_calib_file, "",
27 "Intrinsics to use for estimating board pose prior to solving "
28 "for the new intrinsics.");
29DEFINE_string(calibration_folder, "/tmp", "Folder to place calibration files.");
Jim Ostrowskiad9129f2024-03-01 11:17:50 -080030DEFINE_string(node_name, "",
31 "Node name to use, e.g. orin1, imu; unchanged if blank");
Jim Ostrowski479bd1c2024-03-01 00:21:13 -080032DEFINE_int32(team_number, -1, "Team number to use; unchanged if -1");
33DEFINE_int32(camera_number, -1, "Camera number to use; unchanged if -1");
34
35DEFINE_bool(set_extrinsics, true, "Set to false to ignore extrinsic data");
36DEFINE_bool(use_inches, true,
37 "Whether to use inches as units (meters if false)");
38DEFINE_bool(use_degrees, true,
39 "Whether to use degrees as units (radians if false)");
40DEFINE_double(camera_x, 0.0, "x location of camera");
41DEFINE_double(camera_y, 0.0, "y location of camera");
42DEFINE_double(camera_z, 0.0, "z location of camera");
43// Don't currently allow for roll of cameras
44DEFINE_double(camera_yaw, 0.0, "yaw of camera about robot z axis");
45DEFINE_double(camera_pitch, 0.0, "pitch of camera relative to robot y axis");
46// TODO: This could be done by setting the pixel size and using the intrinsics
47DEFINE_double(focal_length, 0.002, "Focal length in meters");
48
49namespace frc971::vision {
50namespace {
51
52// TODO: Put this in vision_util_lib? Except, it depends on Eigen
53std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) {
54 std::vector<float> data;
55 for (int row = 0; row < 4; ++row) {
56 for (int col = 0; col < 4; ++col) {
57 data.push_back(H(row, col));
58 }
59 }
60 return data;
61}
62
63// Merge the original calibration file with all its changes
64aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> BuildCalibration(
65 const frc971::vision::calibration::CameraCalibration *calibration,
66 std::string node_name, uint16_t camera_number, uint16_t team_number) {
67 aos::FlatbufferDetachedBuffer<frc971::vision::calibration::CameraCalibration>
68 cal_copy = aos::RecursiveCopyFlatBuffer(calibration);
69
70 flatbuffers::FlatBufferBuilder fbb;
71 flatbuffers::Offset<flatbuffers::String> node_name_offset =
72 fbb.CreateString(absl::StrFormat("%s", node_name.c_str()));
73
74 // If we're told to set the extrinsics, clear old and add in new
75 flatbuffers::Offset<calibration::TransformationMatrix>
76 fixed_extrinsics_offset;
77 if (FLAGS_set_extrinsics) {
78 cal_copy.mutable_message()->clear_fixed_extrinsics();
79 Eigen::Affine3d extrinsic_matrix;
80 // Convert to metric
81 double translation_scale = (FLAGS_use_inches ? 0.0254 : 1.0);
82 Eigen::Translation3d translation(FLAGS_camera_x * translation_scale,
83 FLAGS_camera_y * translation_scale,
84 FLAGS_camera_z * translation_scale);
85
86 // convert to radians
87 double angle_scale = (FLAGS_use_degrees ? M_PI / 180.0 : 1.0);
88 // The rotation that takes robot coordinates (x forward, z up) to camera
89 // coordiantes (z forward, x right)
90 Eigen::Quaterniond R_robo_cam =
91 Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitZ()) *
92 Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitX());
93 Eigen::AngleAxisd pitchAngle(FLAGS_camera_pitch * angle_scale,
94 Eigen::Vector3d::UnitY());
95 Eigen::AngleAxisd yawAngle(FLAGS_camera_yaw * angle_scale,
96 Eigen::Vector3d::UnitZ());
97
98 Eigen::Quaterniond rotation = yawAngle * pitchAngle * R_robo_cam;
99 Eigen::Vector3d focal_length_offset =
100 (rotation * Eigen::Translation3d(0.0, 0.0, FLAGS_focal_length))
101 .translation();
102 translation = translation * Eigen::Translation3d(focal_length_offset);
103
104 extrinsic_matrix = translation * rotation;
105 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
106 fbb.CreateVector(
107 frc971::vision::MatrixToVector(extrinsic_matrix.matrix()));
108 calibration::TransformationMatrix::Builder matrix_builder(fbb);
109 matrix_builder.add_data(data_offset);
110 fixed_extrinsics_offset = matrix_builder.Finish();
111 }
112
113 calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
114 camera_calibration_builder.add_node_name(node_name_offset);
115 camera_calibration_builder.add_team_number(team_number);
116 if (FLAGS_set_extrinsics) {
117 camera_calibration_builder.add_fixed_extrinsics(fixed_extrinsics_offset);
118 }
119 camera_calibration_builder.add_camera_number(camera_number);
120 fbb.Finish(camera_calibration_builder.Finish());
121
122 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> updated_cal =
123 fbb.Release();
124
125 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
126 merged_calibration =
127 aos::MergeFlatBuffers(&cal_copy.message(), &updated_cal.message());
128 return merged_calibration;
129}
130
131void Main(std::string orig_calib_filename) {
132 LOG(INFO) << "Reading from file: " << orig_calib_filename;
133 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
134 base_calibration =
135 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
136 orig_calib_filename);
137
138 // Populate the new variables from command-line or from base_calibration
Jim Ostrowski479bd1c2024-03-01 00:21:13 -0800139 std::string node_name =
Jim Ostrowskiad9129f2024-03-01 11:17:50 -0800140 (FLAGS_node_name == "" ? base_calibration.message().node_name()->str()
141 : FLAGS_node_name);
Jim Ostrowski479bd1c2024-03-01 00:21:13 -0800142 int team_number =
143 (FLAGS_team_number == -1 ? base_calibration.message().team_number()
144 : FLAGS_team_number);
145 int camera_number =
146 (FLAGS_camera_number == -1 ? base_calibration.message().camera_number()
147 : FLAGS_camera_number);
148 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
149 new_calibration = BuildCalibration(&base_calibration.message(), node_name,
150 camera_number, team_number);
151
152 // Set a new timestamp on the file, but leave calibration_timestamp unchanged
153 const aos::realtime_clock::time_point realtime_now =
154 aos::realtime_clock::now();
155 std::stringstream time_ss;
156 time_ss << realtime_now;
157 // Use the camera_id that is set in the json file (not the filename)
158 std::string camera_id = base_calibration.message().camera_id()->str();
159
160 const std::string dirname =
161 (FLAGS_calibration_folder == ""
162 ? std::filesystem::path(orig_calib_filename).parent_path().string()
163 : FLAGS_calibration_folder);
Jim Ostrowski33208982024-03-02 15:01:45 -0800164 const std::string new_calib_filename = frc971::vision::CalibrationFilename(
165 dirname, node_name.c_str(), team_number, camera_number, camera_id.c_str(),
166 time_ss.str());
Jim Ostrowski479bd1c2024-03-01 00:21:13 -0800167
168 VLOG(1) << "From: " << orig_calib_filename << " -> "
169 << aos::FlatbufferToJson(base_calibration, {.multi_line = true});
170
171 VLOG(1) << "Writing: " << new_calib_filename << " -> "
172 << aos::FlatbufferToJson(new_calibration, {.multi_line = true});
173
174 LOG(INFO) << "Writing to file: " << new_calib_filename;
175 aos::util::WriteStringToFileOrDie(
176 new_calib_filename,
177 aos::FlatbufferToJson(new_calibration, {.multi_line = true}));
178}
179
180} // namespace
181} // namespace frc971::vision
182
183int main(int argc, char **argv) {
184 aos::InitGoogle(&argc, &argv);
185 CHECK(argc == 2) << "Must supply a starting calibration filename";
186 std::string filename = argv[1];
187 frc971::vision::Main(filename);
188}