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