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