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