Skip to content

Commit

Permalink
Merge branch 'main' into nbuono/VO
Browse files Browse the repository at this point in the history
  • Loading branch information
PizzaRoll04 authored Nov 24, 2024
2 parents b2c4ade + 8d32967 commit f4d5a4e
Show file tree
Hide file tree
Showing 15 changed files with 580 additions and 9 deletions.
27 changes: 23 additions & 4 deletions WORKSPACE
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down Expand Up @@ -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(
Expand Down Expand Up @@ -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="
)
11 changes: 8 additions & 3 deletions common/math/cubic_hermite_spline.hh
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,11 @@
namespace robot::math {

// Interpolate between data points using piecewise cubic polynomials
template <typename T = double, typename X = double>
template <typename X = double, typename T = double>
class CubicHermiteSpline {
public:
CubicHermiteSpline() {}

CubicHermiteSpline(std::vector<T> ts, std::vector<X> xs)
: ts_(std::move(ts)), xs_(std::move(xs)) {
CHECK(std::is_sorted(ts_.begin(), ts_.end()), "Input times must be sorted!", ts_);
Expand Down Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand All @@ -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<T> &ts() const { return ts_; }
const std::vector<X> &xs() const { return xs_; }

Expand Down
5 changes: 5 additions & 0 deletions common/python/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -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"],
)
12 changes: 12 additions & 0 deletions common/python/hermeticity_test.py
Original file line number Diff line number Diff line change
@@ -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()
10 changes: 10 additions & 0 deletions experimental/learn_descriptors/BUILD
Original file line number Diff line number Diff line change
Expand Up @@ -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"
]
)
107 changes: 107 additions & 0 deletions experimental/learn_descriptors/gtsam_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
#include <iostream>
#include <vector>

#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<gtsam::Point3> 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<gtsam::Pose3> poses;
std::vector<gtsam::PinholeCamera<gtsam::Cal3_S2>> 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<gtsam::Cal3_S2> camera0(pose0, *K);
graph.emplace_shared<gtsam::PriorFactor<gtsam::Pose3>>(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<gtsam::Cal3_S2> camera1(pose1, *K);
graph.emplace_shared<gtsam::PriorFactor<gtsam::Pose3>>(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<gtsam::GeneralSFMFactor2<gtsam::Cal3_S2>>(
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::Pose3>(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::Point3>(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
27 changes: 27 additions & 0 deletions experimental/overhead_matching/BUILD
Original file line number Diff line number Diff line change
@@ -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",
]
)
Loading

0 comments on commit f4d5a4e

Please sign in to comment.