Skip to content

Commit 490a9b9

Browse files
authored
Merge branch 'main' into fix-ground-alignment-bug
2 parents cbdbaa2 + 6104907 commit 490a9b9

11 files changed

Lines changed: 39 additions & 52 deletions

File tree

cpp/3rdparty/opencv/opencv.cmake

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,7 @@ set(CMAKE_BUILD_TYPE "Release" CACHE STRING "CMake build type")
5454

5555
message(STATUS "Fetching OpenCV from Github")
5656
include(FetchContent)
57-
FetchContent_Declare(opencv GIT_REPOSITORY https://github.com/opencv/opencv.git GIT_TAG 4.x
58-
GIT_SHALLOW TRUE GIT_PROGRESS TRUE)
57+
FetchContent_Declare(opencv URL https://github.com/opencv/opencv/archive/refs/tags/4.11.0.tar.gz)
5958
FetchContent_MakeAvailable(opencv)
6059
# OpenCV_INCLUDE_DIRS is set by OpenCVConfig.cmake and is unavailable after simply building
6160
set(OpenCV_INCLUDE_DIRS "${opencv_SOURCE_DIR}/include")

cpp/3rdparty/sophus/sophus.cmake

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,6 @@ set(SOPHUS_USE_BASIC_LOGGING ON CACHE BOOL "Don't use fmt for Sophus libraru")
2525
set(BUILD_SOPHUS_TESTS OFF CACHE BOOL "Don't build Sophus tests")
2626
set(BUILD_SOPHUS_EXAMPLES OFF CACHE BOOL "Don't build Sophus Examples")
2727

28-
FetchContent_Declare(
29-
sophus SYSTEM URL https://github.com/strasdat/Sophus/archive/refs/tags/1.22.10.tar.gz
30-
PATCH_COMMAND patch -p1 < ${CMAKE_CURRENT_LIST_DIR}/sophus.patch UPDATE_DISCONNECTED 1)
31-
28+
FetchContent_Declare(sophus SYSTEM
29+
URL https://github.com/strasdat/Sophus/archive/refs/tags/1.24.6.tar.gz)
3230
FetchContent_MakeAvailable(sophus)

cpp/3rdparty/sophus/sophus.patch

Lines changed: 0 additions & 12 deletions
This file was deleted.

cpp/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
# SOFTWARE.
2323

2424
cmake_minimum_required(VERSION 3.16...3.26)
25-
project(map_closures_cpp VERSION 2.0.0 LANGUAGES CXX)
25+
project(map_closures_cpp VERSION 2.0.1 LANGUAGES CXX)
2626

2727
option(USE_SYSTEM_EIGEN3 "Use system pre-installed Eigen" ON)
2828
option(USE_SYSTEM_OPENCV "Use system pre-installed OpenCV" ON)

cpp/map_closures/AlignRansac2D.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ Eigen::Isometry2d KabschUmeyamaAlignment2D(
5555
Eigen::JacobiSVD<Eigen::Matrix2d> svd(covariance_matrix,
5656
Eigen::ComputeFullU | Eigen::ComputeFullV);
5757
Eigen::Isometry2d T = Eigen::Isometry2d::Identity();
58-
const Eigen::Matrix2d &&R = svd.matrixV() * svd.matrixU().transpose();
58+
const Eigen::Matrix2d &R = svd.matrixV() * svd.matrixU().transpose();
5959
T.linear() = R.determinant() > 0 ? R : -R;
6060
T.translation() = mean.query - R * mean.ref;
6161

@@ -93,7 +93,7 @@ std::pair<Eigen::Isometry2d, std::size_t> RansacAlignment2D(
9393

9494
std::sample(keypoint_pairs.begin(), keypoint_pairs.end(), sample_keypoint_pairs.begin(), 2,
9595
std::mt19937{std::random_device{}()});
96-
auto T = KabschUmeyamaAlignment2D(sample_keypoint_pairs);
96+
const auto &T = KabschUmeyamaAlignment2D(sample_keypoint_pairs);
9797

9898
int index = 0;
9999
std::for_each(keypoint_pairs.cbegin(), keypoint_pairs.cend(),
@@ -108,13 +108,13 @@ std::pair<Eigen::Isometry2d, std::size_t> RansacAlignment2D(
108108
optimal_inlier_indices = inlier_indices;
109109
}
110110
}
111-
111+
optimal_inlier_indices.shrink_to_fit();
112112
const std::size_t num_inliers = optimal_inlier_indices.size();
113113
std::vector<PointPair> inlier_keypoint_pairs(num_inliers);
114114
std::transform(optimal_inlier_indices.cbegin(), optimal_inlier_indices.cend(),
115115
inlier_keypoint_pairs.begin(),
116116
[&](const auto index) { return keypoint_pairs[index]; });
117-
Eigen::Isometry2d T = KabschUmeyamaAlignment2D(inlier_keypoint_pairs);
117+
const Eigen::Isometry2d &T = KabschUmeyamaAlignment2D(inlier_keypoint_pairs);
118118
return {T, num_inliers};
119119
}
120120
} // namespace map_closures

cpp/map_closures/DensityMap.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ DensityMap GenerateDensityMap(const std::vector<Eigen::Vector3d> &pcd,
6565
};
6666
std::vector<Eigen::Array2i> pixels(pcd.size());
6767
std::transform(pcd.cbegin(), pcd.cend(), pixels.begin(), [&](const Eigen::Vector3d &point) {
68-
const auto pixel = Discretize2D(point);
68+
const auto &pixel = Discretize2D(point);
6969
lower_bound_coordinates = lower_bound_coordinates.min(pixel);
7070
upper_bound_coordinates = upper_bound_coordinates.max(pixel);
7171
return pixel;

cpp/map_closures/GroundAlign.cpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -86,18 +86,19 @@ std::vector<Eigen::Vector3d> ComputeLowestPoints(const std::vector<Eigen::Vector
8686
};
8787

8888
std::for_each(pointcloud.cbegin(), pointcloud.cend(), [&](const Eigen::Vector3d &point) {
89-
auto pixel = PointToPixel(point);
89+
const auto &pixel = PointToPixel(point);
9090
if (lowest_point_hash_map.find(pixel) == lowest_point_hash_map.cend()) {
91-
lowest_point_hash_map.insert({pixel, point});
91+
if (point.z() < 0) {
92+
lowest_point_hash_map.emplace(pixel, point);
93+
}
9294
} else if (point.z() < lowest_point_hash_map[pixel].z()) {
9395
lowest_point_hash_map[pixel] = point;
9496
}
9597
});
9698

97-
std::vector<Eigen::Vector3d> low_lying_points;
98-
low_lying_points.reserve(lowest_point_hash_map.size());
99-
std::for_each(lowest_point_hash_map.cbegin(), lowest_point_hash_map.cend(),
100-
[&](const auto &entry) { low_lying_points.emplace_back(entry.second); });
99+
std::vector<Eigen::Vector3d> low_lying_points(lowest_point_hash_map.size());
100+
std::transform(lowest_point_hash_map.cbegin(), lowest_point_hash_map.cend(),
101+
low_lying_points.begin(), [](const auto &entry) { return entry.second; });
101102
return low_lying_points;
102103
}
103104
} // namespace
@@ -110,7 +111,7 @@ Eigen::Matrix4d AlignToLocalGround(const std::vector<Eigen::Vector3d> &pointclou
110111

111112
for (int iters = 0; iters < max_iterations; iters++) {
112113
const auto &[H, b] = BuildLinearSystem(low_lying_points, resolution);
113-
const Eigen::Vector3d dx = H.ldlt().solve(-b);
114+
const Eigen::Vector3d &dx = H.ldlt().solve(-b);
114115
Eigen::Matrix<double, 6, 1> se3 = Eigen::Matrix<double, 6, 1>::Zero();
115116
se3.block<3, 1>(2, 0) = dx;
116117
Sophus::SE3d estimation(Sophus::SE3d::exp(se3));

cpp/map_closures/MapClosures.cpp

Lines changed: 19 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -69,17 +69,20 @@ MapClosures::MapClosures(const Config &config) : config_(config) {
6969

7070
void MapClosures::MatchAndAddToDatabase(const int id,
7171
const std::vector<Eigen::Vector3d> &local_map) {
72-
Eigen::Matrix4d T_ground = AlignToLocalGround(local_map, ground_alignment_resolution);
72+
const Eigen::Matrix4d &T_ground = AlignToLocalGround(local_map, ground_alignment_resolution);
7373
DensityMap density_map = GenerateDensityMap(local_map, T_ground, config_.density_map_resolution,
7474
config_.density_threshold);
7575
cv::Mat orb_descriptors;
7676
std::vector<cv::KeyPoint> orb_keypoints;
77+
orb_keypoints.reserve(nfeatures);
7778
orb_extractor_->detectAndCompute(density_map.grid, cv::noArray(), orb_keypoints,
7879
orb_descriptors);
80+
orb_keypoints.shrink_to_fit();
7981

80-
auto matcher = cv::BFMatcher(cv::NORM_HAMMING);
81-
std::vector<std::vector<cv::DMatch>> bf_matches;
82-
matcher.knnMatch(orb_descriptors, orb_descriptors, bf_matches, 2);
82+
const auto self_matcher = cv::BFMatcher(cv::NORM_HAMMING);
83+
std::vector<std::vector<cv::DMatch>> self_matches;
84+
self_matches.reserve(orb_keypoints.size());
85+
self_matcher.knnMatch(orb_descriptors, orb_descriptors, self_matches, 2);
8386

8487
std::for_each(orb_keypoints.begin(), orb_keypoints.end(), [&](cv::KeyPoint &keypoint) {
8588
keypoint.pt.x = keypoint.pt.x + static_cast<float>(density_map.lower_bound.y());
@@ -90,10 +93,10 @@ void MapClosures::MatchAndAddToDatabase(const int id,
9093

9194
std::vector<Matchable *> hbst_matchable;
9295
hbst_matchable.reserve(orb_descriptors.rows);
93-
std::for_each(bf_matches.cbegin(), bf_matches.cend(), [&](const auto &bf_match) {
94-
if (bf_match[1].distance > self_similarity_threshold) {
95-
auto index_descriptor = bf_match[0].queryIdx;
96-
auto keypoint = orb_keypoints[index_descriptor];
96+
std::for_each(self_matches.cbegin(), self_matches.cend(), [&](const auto &self_match) {
97+
if (self_match[1].distance > self_similarity_threshold) {
98+
const auto index_descriptor = self_match[0].queryIdx;
99+
const auto &keypoint = orb_keypoints[index_descriptor];
97100
hbst_matchable.emplace_back(
98101
new Matchable(keypoint, orb_descriptors.row(index_descriptor), id));
99102
}
@@ -169,20 +172,18 @@ std::vector<ClosureCandidate> MapClosures::GetTopKClosures(
169172
[&](const auto &descriptor_match) {
170173
const auto ref_id = static_cast<int>(descriptor_match.first);
171174
if (is_far_enough(ref_id, query_id)) {
172-
ClosureCandidate closure =
173-
ValidateClosure(descriptor_match.first, query_id);
175+
const ClosureCandidate &closure = ValidateClosure(ref_id, query_id);
174176
if (closure.number_of_inliers > min_no_of_matches) {
175177
closures.emplace_back(closure);
176178
}
177179
}
178180
});
179-
if (k == -1) return closures;
180-
181-
std::vector<ClosureCandidate> top_k_closures;
182-
top_k_closures.reserve(std::min(k, static_cast<int>(closures.size())));
183-
std::sort(closures.begin(), closures.end(), compare_closure_candidates);
184-
std::copy_n(closures.cbegin(), std::min(k, static_cast<int>(closures.size())),
185-
std::back_inserter(top_k_closures));
186-
return top_k_closures;
181+
closures.shrink_to_fit();
182+
183+
if (k != -1) {
184+
std::sort(closures.begin(), closures.end(), compare_closure_candidates);
185+
closures.resize(std::min(k, static_cast<int>(closures.size())));
186+
}
187+
return closures;
187188
}
188189
} // namespace map_closures

python/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
2222
# SOFTWARE.
2323
cmake_minimum_required(VERSION 3.16...3.26)
24-
project(map_closure_pybind VERSION 2.0.0 LANGUAGES CXX)
24+
project(map_closure_pybind VERSION 2.0.1 LANGUAGES CXX)
2525

2626
# Set build type
2727
set(CMAKE_BUILD_TYPE Release)

python/map_closures/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,4 +21,4 @@
2121
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
2222
# SOFTWARE.
2323

24-
__version__ = "2.0.0"
24+
__version__ = "2.0.1"

0 commit comments

Comments
 (0)