diff --git a/WORKSPACE b/WORKSPACE index 069442be..bb6e8f7f 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -136,9 +136,11 @@ http_archive( # Note that rules_python must be loaded before protobuf http_archive( name = "rules_python", - sha256 = "c68bdc4fbec25de5b5493b8819cfc877c4ea299c0dcb15c244c5a00208cde311", - strip_prefix = "rules_python-0.31.0", - url = "https://github.com/bazelbuild/rules_python/releases/download/0.31.0/rules_python-0.31.0.tar.gz", + sha256 = "690e0141724abb568267e003c7b6d9a54925df40c275a870a4d934161dc9dd53", + strip_prefix = "rules_python-0.40.0", + url = "https://github.com/bazelbuild/rules_python/releases/download/0.40.0/rules_python-0.40.0.tar.gz", + patch_args = ["-p1"], + patches = ["//third_party:rules_python_0001-disable-user-site-package.patch"], ) load("@rules_python//python:repositories.bzl", "py_repositories", "python_register_multi_toolchains") @@ -470,7 +472,10 @@ http_archive( strip_prefix = "gtsam-4.2.0", urls = ["https://github.com/borglab/gtsam/archive/4.2.0.tar.gz"], patch_args=["-p1"], - patches = ["//third_party:gtsam_0001-remove-redundant-template-params.patch"], + patches = [ + "//third_party:gtsam_0001-remove-redundant-template-params.patch", + "//third_party:gtsam_0002-remove-trivial-copy-constructor.patch", + ], ) http_archive( @@ -524,3 +529,17 @@ http_archive( "//third_party:kimera_vio_0002-add-override-markers.patch", ] ) + +http_archive( + name = "nlohmann_json", + urls = ["https://github.com/nlohmann/json/archive/refs/tags/v3.11.3.zip"], + strip_prefix = "json-3.11.3", + integrity = "sha256-BAIrBdgG61/3MCPCgLaGl9Erk+G3JnoLIqGjnsdXgGk=", +) + +http_archive( + name = "spectacular_log_snippet", + urls = ["https://www.dropbox.com/scl/fi/2u4ec000kx24980t7ifjz/recording_2024-11-21_13-36-30.zip?rlkey=ojw96yykmw9crtqs15kbxwnvp&st=gjcrawhw&dl=1"], + build_file = "//third_party:BUILD.zip_file", + integrity = "sha256-K+KFNzufwccL4vEJLErEtNKNVjnWStClXVF2mKpI6lI=" +) diff --git a/common/math/cubic_hermite_spline.hh b/common/math/cubic_hermite_spline.hh index acc51345..1365f599 100644 --- a/common/math/cubic_hermite_spline.hh +++ b/common/math/cubic_hermite_spline.hh @@ -10,9 +10,11 @@ namespace robot::math { // Interpolate between data points using piecewise cubic polynomials -template +template class CubicHermiteSpline { public: + CubicHermiteSpline() {} + CubicHermiteSpline(std::vector ts, std::vector xs) : ts_(std::move(ts)), xs_(std::move(xs)) { CHECK(std::is_sorted(ts_.begin(), ts_.end()), "Input times must be sorted!", ts_); @@ -48,7 +50,7 @@ class CubicHermiteSpline { const X segment_slope = (end_val - start_val) / segment_length; - const X start_slope = [&]() { + const X start_slope = [&]() -> X { if (iter - 1 == ts_.begin()) { return segment_slope; } @@ -60,7 +62,7 @@ class CubicHermiteSpline { return 0.5 * (pre_slope + segment_slope); }(); - const X end_slope = [&]() { + const X end_slope = [&]() -> X { if (iter + 1 == ts_.end()) { return segment_slope; } @@ -87,6 +89,9 @@ class CubicHermiteSpline { coeffs[2] * end_val + coeffs[3] * segment_length * end_slope; } + const T &min_time() const { return ts_.front(); }; + const T &max_time() const { return ts_.back(); }; + const std::vector &ts() const { return ts_; } const std::vector &xs() const { return xs_; } diff --git a/common/python/BUILD b/common/python/BUILD index f063a22e..588daa99 100644 --- a/common/python/BUILD +++ b/common/python/BUILD @@ -65,3 +65,8 @@ py_test_3_8( main = "pybind_example_test.py", data = [":pybind_example_python.so"], ) + +py_test( + name = "hermeticity_test", + srcs = ["hermeticity_test.py"], +) diff --git a/common/python/hermeticity_test.py b/common/python/hermeticity_test.py new file mode 100644 index 00000000..49236de3 --- /dev/null +++ b/common/python/hermeticity_test.py @@ -0,0 +1,12 @@ + +import unittest + +import sys + +class HermeticityTest(unittest.TestCase): + def test_no_user_site_packages(self): + for p in sys.path: + self.assertNotIn('.local/lib', p) + +if __name__ == "__main__": + unittest.main() diff --git a/experimental/learn_descriptors/BUILD b/experimental/learn_descriptors/BUILD index 95dd425b..cc3983df 100644 --- a/experimental/learn_descriptors/BUILD +++ b/experimental/learn_descriptors/BUILD @@ -34,3 +34,13 @@ cc_test( ":visual_odometry" ] ) + +cc_test( + name = "gtsam_test", + srcs = ["gtsam_test.cc"], + deps = [ + "@com_google_googletest//:gtest_main", + "@gtsam//:gtsam", + ":learn_descriptors" + ] +) diff --git a/experimental/learn_descriptors/gtsam_test.cc b/experimental/learn_descriptors/gtsam_test.cc new file mode 100644 index 00000000..53ee67b4 --- /dev/null +++ b/experimental/learn_descriptors/gtsam_test.cc @@ -0,0 +1,107 @@ +#include +#include + +#include "Eigen/Core" +#include "gtest/gtest.h" +#include "gtsam/geometry/Point3.h" +#include "gtsam/geometry/Pose3.h" +#include "gtsam/inference/Symbol.h" +#include "gtsam/nonlinear/LevenbergMarquardtOptimizer.h" +#include "gtsam/nonlinear/Values.h" +#include "gtsam/slam/GeneralSFMFactor.h" +#include "gtsam/slam/PriorFactor.h" +#include "gtsam/slam/ProjectionFactor.h" + +class GtsamTestHelper { + public: + static bool pixel_in_range(Eigen::Vector2d pixel, size_t img_width, size_t img_height) { + return pixel[0] > 0 && pixel[0] < img_width && pixel[1] > 0 && pixel[1] < img_height; + } +}; + +namespace robot::experimental::gtsam_testing { + +TEST(GtsamTesting, gtsam_simple_cube) { + std::vector cube_W; + float cube_size = 1.0f; + cube_W.push_back(gtsam::Point3(0, 0, 0)); + cube_W.push_back(gtsam::Point3(cube_size, 0, 0)); + cube_W.push_back(gtsam::Point3(cube_size, cube_size, 0)); + cube_W.push_back(gtsam::Point3(0, cube_size, 0)); + cube_W.push_back(gtsam::Point3(0, 0, cube_size)); + cube_W.push_back(gtsam::Point3(cube_size, 0, cube_size)); + cube_W.push_back(gtsam::Point3(cube_size, cube_size, cube_size)); + cube_W.push_back(gtsam::Point3(0, cube_size, cube_size)); + + const size_t img_width = 640; + const size_t img_height = 480; + const double fx = 500.0; + const double fy = fx; + const double cx = img_width / 2.0; + const double cy = img_height / 2.0; + + gtsam::Values initial; + gtsam::NonlinearFactorGraph graph; + + gtsam::Cal3_S2::shared_ptr K(new gtsam::Cal3_S2(fx, fy, 0, cx, cy)); + initial.insert(gtsam::Symbol('K', 0), *K); + + auto poseNoise = gtsam::noiseModel::Diagonal::Sigmas(gtsam::Vector6::Constant(0.1)); + auto measurementNoise = gtsam::noiseModel::Isotropic::Sigma(2, 1.0); + std::vector poses; + std::vector> cameras; + + Eigen::Matrix3d rotation0( + Eigen::AngleAxis(M_PI / 2, Eigen::Vector3d(0, 0, 1)).toRotationMatrix() * + Eigen::AngleAxis(-M_PI / 2, Eigen::Vector3d(1, 0, 0)).toRotationMatrix()); + gtsam::Pose3 pose0(gtsam::Rot3(rotation0), gtsam::Point3(4, 0, 0)); + gtsam::PinholeCamera camera0(pose0, *K); + graph.emplace_shared>(gtsam::Symbol('x', 0), pose0, poseNoise); + poses.push_back(pose0); + cameras.push_back(camera0); + + gtsam::Pose3 pose1( + gtsam::Rot3(Eigen::AngleAxis(M_PI / 2, Eigen::Vector3d(0, 0, 1)).toRotationMatrix() * + rotation0), + gtsam::Point3(0, 4, 0)); + gtsam::PinholeCamera camera1(pose1, *K); + graph.emplace_shared>(gtsam::Symbol('x', 1), pose1, poseNoise); + poses.push_back(pose1); + cameras.push_back(camera1); + + for (size_t i = 0; i < poses.size(); i++) { + initial.insert(gtsam::Symbol('x', i), poses[i]); + } + for (size_t i = 0; i < cube_W.size(); i++) { + initial.insert(gtsam::Symbol('L', i), gtsam::Point3(0, 0, 0)); + for (size_t j = 0; j < poses.size(); j++) { + gtsam::Point2 pixel_p_cube_C = cameras[j].project(cube_W[i]); + if (GtsamTestHelper::pixel_in_range(pixel_p_cube_C, img_width, img_height)) { + graph.emplace_shared>( + pixel_p_cube_C, measurementNoise, gtsam::Symbol('x', j), gtsam::Symbol('L', i), + gtsam::Symbol('K', 0)); + } + } + } + + gtsam::LevenbergMarquardtOptimizer optimizer(graph, initial); + gtsam::Values result = optimizer.optimize(); + + // result.print("Optimized Results:\n"); + + constexpr double TOL = 1e-3; + for (size_t i = 0; i < poses.size(); i++) { + gtsam::Pose3 result_pose = result.at(gtsam::Symbol('x', i)); + EXPECT_NEAR(poses[i].translation()[0], result_pose.translation()[0], TOL); + EXPECT_NEAR(poses[i].translation()[1], result_pose.translation()[1], TOL); + EXPECT_NEAR(poses[i].translation()[2], result_pose.translation()[2], TOL); + EXPECT_TRUE(poses[i].rotation().matrix().isApprox(result_pose.rotation().matrix(), TOL)); + } + for (size_t i = 0; i < cube_W.size(); i++) { + gtsam::Point3 result_point = result.at(gtsam::Symbol('L', i)); + EXPECT_NEAR(cube_W[i][0], result_point[0], TOL); + EXPECT_NEAR(cube_W[i][1], result_point[1], TOL); + EXPECT_NEAR(cube_W[i][2], result_point[2], TOL); + } +} +} // namespace robot::experimental::gtsam_testing \ No newline at end of file diff --git a/experimental/overhead_matching/BUILD b/experimental/overhead_matching/BUILD new file mode 100644 index 00000000..9b5dac35 --- /dev/null +++ b/experimental/overhead_matching/BUILD @@ -0,0 +1,27 @@ + +cc_library( + name = "spectacular_log", + hdrs = ["spectacular_log.hh"], + srcs = ["spectacular_log.cc"], + deps = [ + "@eigen", + "@nlohmann_json//:json", + "@opencv", + "@fmt", + "//common:argument_wrapper", + "//common:check", + "//common/time:robot_time", + "//common/math:cubic_hermite_spline", + ] +) + +cc_test( + name = "spectacular_log_test", + srcs = ["spectacular_log_test.cc"], + data = ["@spectacular_log_snippet//:files"], + deps = [ + ":spectacular_log", + "@com_google_googletest//:gtest_main", + "@fmt", + ] +) diff --git a/experimental/overhead_matching/spectacular_log.cc b/experimental/overhead_matching/spectacular_log.cc new file mode 100644 index 00000000..52a4f823 --- /dev/null +++ b/experimental/overhead_matching/spectacular_log.cc @@ -0,0 +1,206 @@ + +#include "experimental/overhead_matching/spectacular_log.hh" + +#include +#include +#include +#include +#include +#include +#include + +#include "Eigen/Core" +#include "common/argument_wrapper.hh" +#include "common/check.hh" +#include "common/math/cubic_hermite_spline.hh" +#include "common/time/robot_time.hh" +#include "fmt/format.h" +#include "nlohmann/json.hpp" +#include "opencv2/imgcodecs.hpp" + +namespace fs = std::filesystem; +using json = nlohmann::json; + +namespace robot::experimental::overhead_matching { + +namespace { + +struct AccelMeasurement { + double time_of_validity_s; + Eigen::Vector3d accel_mpss; +}; + +struct GyroMeasurement { + double time_of_validity_s; + Eigen::Vector3d angular_vel_radps; +}; + +struct LogData { + std::vector accel; + std::vector gyro; + std::vector frames; +}; + +LogData read_jsonl(const fs::path &file_path) { + CHECK(fs::exists(file_path), "jsonl path does not exist", file_path); + std::ifstream in_file(file_path); + CHECK(in_file.is_open(), "Could not open file", file_path); + + LogData out; + for (std::string line; std::getline(in_file, line);) { + const auto j = json::parse(line); + const double time_of_validity_s = j["time"].get(); + if (j.contains("sensor")) { + const auto &sensor_data = j["sensor"]; + const auto &v = sensor_data["values"]; + if (sensor_data["type"] == "accelerometer") { + out.accel.emplace_back(AccelMeasurement{ + .time_of_validity_s = time_of_validity_s, + .accel_mpss = Eigen::Vector3d{v.at(0).get(), v.at(1).get(), + v.at(2).get()}, + }); + } else if (sensor_data["type"] == "gyroscope") { + out.gyro.emplace_back(GyroMeasurement{ + .time_of_validity_s = time_of_validity_s, + .angular_vel_radps = + Eigen::Vector3d{v.at(0).get(), v.at(1).get(), + v.at(2).get()}, + }); + } + } else if (j.contains("frames")) { + const int frame_number = j["number"].get(); + std::array calibration; + { + const auto &frame = j["frames"].at(0); + const auto &calib_info = frame["calibration"]; + CHECK(frame["colorFormat"] == "rgb"); + + calibration[0].focal_length = {calib_info["focalLengthX"].get(), + calib_info["focalLengthY"].get()}; + calibration[0].principal_point = {calib_info["principalPointX"].get(), + calib_info["principalPointY"].get()}; + calibration[0].exposure_time_s = frame["exposureTimeSeconds"].get(); + } + { + const auto &frame = j["frames"].at(1); + const auto &calib_info = frame["calibration"]; + CHECK(frame["colorFormat"] == "gray"); + + calibration[1].focal_length = {calib_info["focalLengthX"].get(), + calib_info["focalLengthY"].get()}; + calibration[1].principal_point = {calib_info["principalPointX"].get(), + calib_info["principalPointY"].get()}; + calibration[1].depth_scale = frame["depthScale"].get(); + } + + out.frames.push_back(detail::FrameInfo{ + .time_of_validity_s = time_of_validity_s, + .frame_number = frame_number, + .calibration = calibration, + }); + } + } + return out; +} + +template +math::CubicHermiteSpline make_spline(const std::vector &frames, + const auto &accessor) { + std::vector ts; + std::vector xs; + ts.reserve(frames.size()); + xs.reserve(frames.size()); + + for (const auto &frame : frames) { + ts.push_back(frame.time_of_validity_s); + xs.push_back(accessor(frame)); + } + return math::CubicHermiteSpline(ts, xs); +} + +void seek_to_frame(const int frame_id, InOut video) { + const int current_frame_id = video->get(cv::CAP_PROP_POS_FRAMES); + + if (current_frame_id > frame_id) { + video->set(cv::CAP_PROP_POS_FRAMES, 0); + } + + while (video->get(cv::CAP_PROP_POS_FRAMES) != frame_id) { + video->grab(); + } +} + +} // namespace + +SpectacularLog::SpectacularLog(const fs::path &path) : log_path_(path) { + const auto data_path = log_path_ / "data.jsonl"; + LogData log_data = read_jsonl(data_path); + gyro_spline_ = + make_spline(log_data.gyro, [](const auto &frame) { return frame.angular_vel_radps; }); + accel_spline_ = make_spline(log_data.accel, [](const auto &frame) { return frame.accel_mpss; }); + frame_info_ = std::move(log_data.frames); +} + +std::optional SpectacularLog::get_imu_sample(const time::RobotTimestamp &t) const { + if (t < min_imu_time() || t > max_imu_time()) { + return std::nullopt; + } + + return {{ + .time_of_validity = t, + .accel_mpss = accel_spline_(std::chrono::duration(t.time_since_epoch()).count()), + .gyro_radps = gyro_spline_(std::chrono::duration(t.time_since_epoch()).count()), + }}; +} + +std::optional SpectacularLog::get_frame(const int frame_id) const { + if (frame_id < 0 || frame_id >= frame_info_.size()) { + return std::nullopt; + } + + const auto &frame_info = frame_info_.at(frame_id); + + // Read the desired rgb frame + if (video_ == nullptr) { + const fs::path rgb_path = log_path_ / "data.mov"; + video_ = std::make_unique(rgb_path.string(), cv::CAP_FFMPEG); + } + cv::Mat rgb_frame; + seek_to_frame(frame_info.frame_number, make_in_out(*video_)); + video_->read(rgb_frame); + + // Read the desired depth frame + const fs::path depth_frame_path = + log_path_ / "frames2" / fmt::format("{:08d}.png", frame_info.frame_number); + cv::Mat depth_frame = cv::imread(depth_frame_path.string(), cv::IMREAD_GRAYSCALE); + + return {{ + .time_of_validity = + time::as_duration(frame_info.time_of_validity_s) + time::RobotTimestamp(), + .rgb_frame = std::move(rgb_frame), + .depth_frame = std::move(depth_frame), + .rgb_calibration = frame_info.calibration.at(0), + .depth_calibration = frame_info.calibration.at(1), + }}; +} + +time::RobotTimestamp SpectacularLog::min_imu_time() const { + const double later_time_s = std::max(gyro_spline_.min_time(), accel_spline_.min_time()); + return time::as_duration(later_time_s + 1e-6) + time::RobotTimestamp(); +} + +time::RobotTimestamp SpectacularLog::max_imu_time() const { + const double earlier_time_s = std::min(gyro_spline_.max_time(), accel_spline_.max_time()); + return time::as_duration(earlier_time_s - 1e-6) + time::RobotTimestamp(); +} + +time::RobotTimestamp SpectacularLog::min_frame_time() const { + return time::as_duration(frame_info_.front().time_of_validity_s) + time::RobotTimestamp(); +} + +time::RobotTimestamp SpectacularLog::max_frame_time() const { + return time::as_duration(frame_info_.back().time_of_validity_s) + time::RobotTimestamp(); +} + +int SpectacularLog::num_frames() const { return frame_info_.size(); } +} // namespace robot::experimental::overhead_matching diff --git a/experimental/overhead_matching/spectacular_log.hh b/experimental/overhead_matching/spectacular_log.hh new file mode 100644 index 00000000..bc8f39f4 --- /dev/null +++ b/experimental/overhead_matching/spectacular_log.hh @@ -0,0 +1,71 @@ + +#pragma once + +#include +#include + +#include "Eigen/Core" +#include "common/math/cubic_hermite_spline.hh" +#include "common/time/robot_time.hh" +#include "opencv2/core/mat.hpp" +#include "opencv2/videoio.hpp" + +namespace robot::experimental::overhead_matching { + +struct FrameCalibration { + Eigen::Vector2d focal_length; + Eigen::Vector2d principal_point; + + std::optional exposure_time_s; + std::optional depth_scale; +}; + +struct FrameGroup { + time::RobotTimestamp time_of_validity; + cv::Mat rgb_frame; + cv::Mat depth_frame; + + FrameCalibration rgb_calibration; + FrameCalibration depth_calibration; +}; + +struct ImuSample { + time::RobotTimestamp time_of_validity; + Eigen::Vector3d accel_mpss; + Eigen::Vector3d gyro_radps; +}; + +namespace detail { +struct FrameInfo { + double time_of_validity_s; + int frame_number; + std::array calibration; +}; +} // namespace detail + +class SpectacularLog { + public: + explicit SpectacularLog(const std::filesystem::path &log_path); + + std::optional get_imu_sample(const time::RobotTimestamp &t) const; + std::optional get_frame(const int frame_id) const; + + const math::CubicHermiteSpline &gyro_spline() const { return gyro_spline_; } + const math::CubicHermiteSpline &accel_spline() const { return accel_spline_; } + + time::RobotTimestamp min_imu_time() const; + time::RobotTimestamp max_imu_time() const; + + time::RobotTimestamp min_frame_time() const; + time::RobotTimestamp max_frame_time() const; + + int num_frames() const; + + private: + std::filesystem::path log_path_; + math::CubicHermiteSpline gyro_spline_; + math::CubicHermiteSpline accel_spline_; + std::vector frame_info_; + mutable std::unique_ptr video_; +}; +} // namespace robot::experimental::overhead_matching diff --git a/experimental/overhead_matching/spectacular_log_test.cc b/experimental/overhead_matching/spectacular_log_test.cc new file mode 100644 index 00000000..4fd26f0a --- /dev/null +++ b/experimental/overhead_matching/spectacular_log_test.cc @@ -0,0 +1,74 @@ + +#include "experimental/overhead_matching/spectacular_log.hh" + +#include +#include + +#include "fmt/format.h" +#include "gtest/gtest.h" +#include "opencv2/opencv.hpp" + +namespace robot::experimental::overhead_matching { + +bool images_equal(cv::Mat img1, cv::Mat img2) { + if (img1.size() != img2.size() || img1.type() != img2.type()) { + return false; + } + cv::Mat diff; + cv::absdiff(img1, img2, diff); + diff = diff.reshape(1); + return cv::countNonZero(diff) == 0; +} + +std::ostream &operator<<(std::ostream &out, const time::RobotTimestamp &t) { + std::ostringstream ss; + ss << std::fixed << std::setprecision(9) + << std::chrono::duration(t.time_since_epoch()).count(); + out << ss.str(); + return out; +} + +TEST(SpectacularLogTest, happy_case) { + // Setup + const std::filesystem::path log_path( + "external/spectacular_log_snippet/recording_2024-11-21_13-36-30"); + SpectacularLog log(log_path); + // Action + + std::cout << "imu time: (" << log.min_imu_time() << ", " << log.max_imu_time() << ")" + << " frame time: (" << log.min_frame_time() << ", " << log.max_frame_time() << ")" + << std::endl; + + std::cout << "IMU Samples" << std::endl; + for (time::RobotTimestamp t = log.min_imu_time(); + t < std::min(log.min_imu_time() + time::as_duration(5.0), log.max_imu_time()); + t += time::as_duration(0.1)) { + const auto sample = log.get_imu_sample(t); + if (sample.has_value()) { + std::cout << "t: " << sample->time_of_validity + << " accel: " << sample->accel_mpss.transpose() + << " gyro: " << sample->gyro_radps.transpose() << std::endl; + } + } + + cv::VideoCapture video(log_path / "data.mov", cv::CAP_FFMPEG); + constexpr int FRAME_SKIP = 50; + cv::Mat expected_frame; + for (int frame_id = 0; frame_id < log.num_frames(); frame_id += FRAME_SKIP) { + video.read(expected_frame); + + const auto frame = log.get_frame(frame_id).value(); + + const std::filesystem::path depth_path(log_path / + fmt::format("frames2/{:08d}.png", frame_id)); + const cv::Mat depth_frame = cv::imread(depth_path, cv::IMREAD_GRAYSCALE); + + EXPECT_TRUE(images_equal(expected_frame, frame.rgb_frame)); + EXPECT_TRUE(images_equal(depth_frame, frame.depth_frame)); + + for (int i = 0; i < FRAME_SKIP - 1; i++) { + video.grab(); + } + } +} +} // namespace robot::experimental::overhead_matching diff --git a/setup.sh b/setup.sh index 2edc96d3..104dbf18 100755 --- a/setup.sh +++ b/setup.sh @@ -15,5 +15,5 @@ sudo apt-get update sudo DEBIAN_FRONTEND=noninteractive apt-get -y install clang clang-15 clang-format-15 libxcursor-dev \ libxrandr-dev libxinerama-dev libxi-dev freeglut3-dev libstdc++-12-dev gcc-11 g++-11 libtbb-dev \ libfmt-dev libspdlog-dev libvtk9-dev coinor-libipopt-dev coinor-libclp-dev \ - libgirepository1.0-dev libcairo2-dev + libgirepository1.0-dev libcairo2-dev libcanberra-gtk-module diff --git a/third_party/BUILD.opencv b/third_party/BUILD.opencv index 59613539..ce7ef340 100644 --- a/third_party/BUILD.opencv +++ b/third_party/BUILD.opencv @@ -15,6 +15,7 @@ SHARED_LIBS = [ "libopencv_flann.so", "libopencv_calib3d.so", "libopencv_video.so", + "libopencv_videoio.so", "libopencv_viz.so", "libopencv_rgbd.so", ] @@ -23,7 +24,7 @@ cmake( name = "opencv", generate_args = [ "-GNinja", - "-DBUILD_LIST=core,highgui,imgcodecs,imgproc,python3,features2d,flann,calib3d,video,viz,rgbd", + "-DBUILD_LIST=core,highgui,imgcodecs,imgproc,python3,features2d,flann,calib3d,video,videoio,viz,rgbd", "-DCMAKE_CXX_STANDARD=20", "-DCMAKE_CXX_FLAGS=-Wno-deprecated-enum-enum-conversion", "-DCMAKE_CXX_STANDARD_LIBRARIES=-lstdc++", diff --git a/third_party/BUILD.zip_file b/third_party/BUILD.zip_file new file mode 100644 index 00000000..4d001592 --- /dev/null +++ b/third_party/BUILD.zip_file @@ -0,0 +1,6 @@ + +filegroup( + name = "files", + srcs = glob(["**/*"]), + visibility = ["//visibility:public"], +) diff --git a/third_party/gtsam_0002-remove-trivial-copy-constructor.patch b/third_party/gtsam_0002-remove-trivial-copy-constructor.patch new file mode 100644 index 00000000..d01194d1 --- /dev/null +++ b/third_party/gtsam_0002-remove-trivial-copy-constructor.patch @@ -0,0 +1,16 @@ +diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h +index 678df8376..b840ed488 100644 +--- a/gtsam/geometry/Pose3.h ++++ b/gtsam/geometry/Pose3.h +@@ -54,11 +54,6 @@ public: + /** Default constructor is origin */ + Pose3() : R_(traits::Identity()), t_(traits::Identity()) {} + +- /** Copy constructor */ +- Pose3(const Pose3& pose) : +- R_(pose.R_), t_(pose.t_) { +- } +- + /** Construct from R,t */ + Pose3(const Rot3& R, const Point3& t) : + R_(R), t_(t) { diff --git a/third_party/rules_python_0001-disable-user-site-package.patch b/third_party/rules_python_0001-disable-user-site-package.patch new file mode 100644 index 00000000..d5ee089b --- /dev/null +++ b/third_party/rules_python_0001-disable-user-site-package.patch @@ -0,0 +1,12 @@ +diff --git a/python/private/hermetic_runtime_repo_setup.bzl b/python/private/hermetic_runtime_repo_setup.bzl +index d041be5..dbf20b3 100644 +--- a/python/private/hermetic_runtime_repo_setup.bzl ++++ b/python/private/hermetic_runtime_repo_setup.bzl +@@ -199,6 +199,7 @@ def define_hermetic_runtime_toolchain_impl( + _IS_FREETHREADED: "cpython-{major}{minor}t".format(**version_dict), + "//conditions:default": "cpython-{major}{minor}".format(**version_dict), + }), ++ stub_shebang="#! /usr/bin/env -S PYTHONNOUSERSITE=1 python", + ) + + py_runtime_pair(