Skip to content

Commit

Permalink
rename edge to boundary
Browse files Browse the repository at this point in the history
  • Loading branch information
yuecideng committed Mar 19, 2022
1 parent ee581ff commit 5ac35c2
Show file tree
Hide file tree
Showing 10 changed files with 43 additions and 36 deletions.
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ Core modules:
2. Crop ROI of point clouds.
3. Project point clouds into a plane.
- `features`:
1. Edge points detection from point clouds.
1. Boundary points detection from point clouds.
- `registration`:
1. Corresponding matching with descriptors.
2. 3D rigid transformation solver including SVD, RANSAC and [TEASERPP](https://github.com/MIT-SPARK/TEASER-plusplus).
Expand Down Expand Up @@ -89,10 +89,10 @@ pcd_plane = m3d.preprocessing.project_into_plane(pcd)
```

```python
# edge points detection
index = m3d.features.detect_edge_points(
# boundary points detection
index = m3d.features.detect_boundary_points(
pcd, o3d.geometry.KDTreeSearchParamHybrid(0.02, 30))
edges = pcd.select_by_index(index)
boundary = pcd.select_by_index(index)
```

```python
Expand Down
6 changes: 3 additions & 3 deletions examples/cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ target_link_libraries(ppf_estimator PUBLIC misc3d::misc3d)
add_executable(preprocessing preprocessing.cpp)
target_link_libraries(preprocessing PUBLIC misc3d::misc3d)

add_executable(ransac_and_edge ransac_and_edge.cpp)
target_link_libraries(ransac_and_edge PUBLIC misc3d::misc3d)
add_executable(ransac_and_boundary ransac_and_boundary.cpp)
target_link_libraries(ransac_and_boundary PUBLIC misc3d::misc3d)

add_executable(segmentation segmentation.cpp)
target_link_libraries(segmentation PUBLIC misc3d::misc3d)
Expand All @@ -20,5 +20,5 @@ add_executable(transform_estimation transform_estimation.cpp)
target_link_libraries(transform_estimation PUBLIC misc3d::misc3d)

install(TARGETS farthest_point_sampling normal_estimation ppf_estimator
preprocessing ransac_and_edge segmentation transform_estimation
preprocessing ransac_and_boundary segmentation transform_estimation
RUNTIME DESTINATION "${CMAKE_INSTALL_PREFIX}/misc3d/bin")
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
#include <memory>

#include <misc3d/common/ransac.h>
#include <misc3d/features/edge_detection.h>
#include <misc3d/features/boundary_detection.h>
#include <misc3d/utils.h>
#include <misc3d/vis/vis_utils.h>
#include <open3d/camera/PinholeCameraIntrinsic.h>
Expand Down Expand Up @@ -43,20 +43,20 @@ int main(int argc, char *argv[]) {

auto pcd_plane = pcd_down->SelectByIndex(inliers);
timer.Start();
auto indices = misc3d::features::DetectEdgePoints(
auto indices = misc3d::features::DetectBoundaryPoints(
*pcd_plane, open3d::geometry::KDTreeSearchParamHybrid(0.02, 30));
std::cout << "Time cost for edge detection: " << timer.Stop() << std::endl;
std::cout << "Time cost for boundary detection: " << timer.Stop() << std::endl;

auto pcd_edges = pcd_plane->SelectByIndex(indices);
auto boundary = pcd_plane->SelectByIndex(indices);

auto vis = std::make_shared<open3d::visualization::Visualizer>();
vis->CreateVisualizerWindow("Ransac and edge detection", 1920, 1200);
vis->CreateVisualizerWindow("Ransac and boundary detection", 1920, 1200);
misc3d::vis::DrawGeometry3D(vis, pcd_down, {0.5, 0.5, 0.5});
misc3d::vis::DrawGeometry3D(vis, pcd_plane);
auto bbox = std::make_shared<open3d::geometry::OrientedBoundingBox>(
pcd_plane->GetOrientedBoundingBox());
misc3d::vis::DrawGeometry3D(vis, bbox, {0, 1, 0});
misc3d::vis::DrawGeometry3D(vis, pcd_edges, {1, 0, 0});
misc3d::vis::DrawGeometry3D(vis, boundary, {1, 0, 0});
vis->Run();

return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@


vis = o3d.visualization.Visualizer()
vis.create_window("Segmentation", 1920, 1200)
vis.create_window("Ransac and Bounary Detection", 1920, 1200)

depth = o3d.io.read_image('../data/indoor/depth/depth_0.png')
color = o3d.io.read_image('../data/indoor/color/color_0.png')
Expand All @@ -33,17 +33,17 @@
plane = pcd.select_by_index(index)

t1 = time.time()
index = m3d.features.detect_edge_points(
index = m3d.features.detect_boundary_points(
plane, o3d.geometry.KDTreeSearchParamHybrid(0.02, 30))
print('Edges detection time: %.3f' % (time.time() - t1))
print('Boundary detection time: %.3f' % (time.time() - t1))

edges = plane.select_by_index(index)
boundary = plane.select_by_index(index)

# scene points painted with gray
bbox = plane.get_oriented_bounding_box()
m3d.vis.draw_geometry3d(vis, pcd, color=(0.5, 0.5, 0.5))
m3d.vis.draw_geometry3d(vis, bbox, color=(0, 1, 0))
m3d.vis.draw_geometry3d(vis, plane)
m3d.vis.draw_geometry3d(vis, edges, color=(1, 0, 0), size=5)
m3d.vis.draw_geometry3d(vis, boundary, color=(1, 0, 0), size=5)

vis.run()
11 changes: 9 additions & 2 deletions include/misc3d/common/knn.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,14 @@ namespace misc3d {

namespace common {

/**
* @brief This is a K nearest neighbor search class based on annoy.
* It is recommanded to use this class instead of the KDTreeFlann class when the
* feature dimension is large, eg. for descriptor-based feature matching usage
* As for point cloud based nearest neighbor search, the KDTreeFlann class is
* more suitable.
*
*/
class KNearestSearch {
public:
KNearestSearch();
Expand All @@ -21,8 +29,7 @@ class KNearestSearch {

KNearestSearch(const Eigen::MatrixXd &data, int n_trees = 4);

KNearestSearch(const open3d::geometry::Geometry &geometry,
int n_trees = 4);
KNearestSearch(const open3d::geometry::Geometry &geometry, int n_trees = 4);

KNearestSearch(const open3d::pipelines::registration::Feature &feature,
int n_trees = 4);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ namespace misc3d {
namespace features {

/**
* @brief Detect edges from point clouds
* @brief Detect boundary from point clouds
*
* @param pc
* @param param nearest neighbor search parameter
* @param angle_threshold angle threshold to decide if a point is a boundary point
* @return std::vector<size_t>
*/
std::vector<size_t> DetectEdgePoints(
std::vector<size_t> DetectBoundaryPoints(
const open3d::geometry::PointCloud& pc,
const open3d::geometry::KDTreeSearchParam& param, double angle_threshold = 90.0);

Expand Down
6 changes: 3 additions & 3 deletions python/py_features.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <py_misc3d.h>

#include <misc3d/features/edge_detection.h>
#include <misc3d/features/boundary_detection.h>
#include <misc3d/utils.h>

namespace misc3d {
Expand All @@ -9,11 +9,11 @@ namespace features {

void pybind_features(py::module& m) {
m.def(
"detect_edge_points",
"detect_boundary_points",
[](const PointCloudPtr& pc,
const open3d::geometry::KDTreeSearchParam& param,
double angle_threshold) {
return DetectEdgePoints(*pc, param, angle_threshold);
return DetectBoundaryPoints(*pc, param, angle_threshold);
},
py::arg("pc"),
py::arg("param") = open3d::geometry::KDTreeSearchParamHybrid(0.01, 30),
Expand Down
2 changes: 1 addition & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ set(SRCS utils.cpp
filter.cpp
normal_estimation.cpp
proximity_extraction.cpp
edge_detection.cpp
boundary_detection.cpp
transform_estimation.cpp
correspondence_matching.cpp
ppf_estimation.cpp
Expand Down
16 changes: 8 additions & 8 deletions src/edge_detection.cpp → src/boundary_detection.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include <misc3d/features/edge_detection.h>
#include <misc3d/features/boundary_detection.h>
#include <misc3d/logging.h>

namespace misc3d {
Expand Down Expand Up @@ -59,14 +59,14 @@ bool IsBoundaryPoint(const open3d::geometry::PointCloud& pc,
return false;
}

std::vector<size_t> DetectEdgePoints(
std::vector<size_t> DetectBoundaryPoints(
const open3d::geometry::PointCloud& pc,
const open3d::geometry::KDTreeSearchParam& param, double angle_threshold) {
std::vector<size_t> edge_indices;
std::vector<size_t> boundary_indices;
if (!pc.HasPoints()) {
misc3d::LogError("No PointCloud data.");

return edge_indices;
return boundary_indices;
}

open3d::geometry::PointCloud pc_(pc);
Expand Down Expand Up @@ -94,14 +94,14 @@ std::vector<size_t> DetectEdgePoints(
if (IsBoundaryPoint(pc_, pc_.points_[idx], ret_indices, u, v,
angle_threshold)) {
#pragma omp critical
{ edge_indices.push_back(idx); }
{ boundary_indices.push_back(idx); }
}
}

misc3d::LogInfo("Found {} edge points from {} input points.",
edge_indices.size(), num);
misc3d::LogInfo("Found {} boundary points from {} input points.",
boundary_indices.size(), num);

return edge_indices;
return boundary_indices;
}

} // namespace features
Expand Down
4 changes: 2 additions & 2 deletions src/ppf_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include <stack>
#include <unordered_map>

#include <misc3d/features/edge_detection.h>
#include <misc3d/features/boundary_detection.h>
#include <misc3d/logging.h>
#include <misc3d/pose_estimation/data_structure.h>
#include <misc3d/pose_estimation/ppf_estimation.h>
Expand Down Expand Up @@ -1148,7 +1148,7 @@ void PPFEstimator::Impl::CalcModelNormalAndSampling(
void PPFEstimator::Impl::ExtractEdges(const open3d::geometry::PointCloud &pc,
double radius,
std::vector<size_t> &edge_ind) {
edge_ind = features::DetectEdgePoints(
edge_ind = features::DetectBoundaryPoints(
pc, open3d::geometry::KDTreeSearchParamHybrid(
radius, config_.edge_param_.pts_num));
}
Expand Down

0 comments on commit 5ac35c2

Please sign in to comment.