Comments (7)
Ok, this might sound a but counter-intuitive, but for the sake of speed I never updated the points in the cloud after removing the ground from the range image. So the cloud is still the same, but every cloud has a range image attached to it, so the image attached to it is not without ground. After your changes this image will contain ground only, but the cloud does not change.
I set the image here:
from depth_clustering.
@niosus Thanks for your clarification.
I see that everything is based on the range image for fast computation. What I understand so far for removing ground is as follows:
- You remove the ground based on the range image in
depth_ground_remover
. The processed range image (should contain non-zero values for non-ground points and zero values for ground point) is sent toimage_based_clusterer
image_based_clusterer
first labels the received range image. It will only label non-ground points (depth pixels with non-zero value). Then it creates a container to store labels and their corresponding points and after that, send the container to the next client.
My approach is like this:
- I remove all the non-ground points (switch
==
to!=
). The processed range image contains only the ground (with non-zero values; non-ground points are marked as zero) and is sent to the next step. - I skip the labeling procedure and create a container which stores only 1 label and all the ground points from the received range image.
I create the container like this:
void OnNewObjectReceived(const Cloud& cloud, const int sender_id) override {
// generate a projection from a point cloud
if (!cloud.projection_ptr()) {
fprintf(stderr, "ERROR: projection not initialized in cloud.\n");
fprintf(stderr, "INFO: cannot label this cloud.\n");
return;
}
time_utils::Timer timer;
// create 3d clusters from image labels
std::unordered_map<uint16_t, Cloud> clusters;
// assign an arbitrary ground label
uint16_t label = 2;
// this depth image should contain only ground points
const cv::Mat& img_ground = cloud.projection_ptr()->depth_image();
for (int row = 0; row < img_ground.rows; ++row) {
for (int col = 0; col < img_ground.cols; ++col) {
const auto& point_container = cloud.projection_ptr()->at(row, col);
if (point_container.IsEmpty()) {
// this is ok, just continue, nothing interesting here, no points.
continue;
}
if (img_ground.at<float>(row, col) == 0) {
// skip non-ground points
continue;
}
for (const auto& point_idx : point_container.points()) {
const auto& point = cloud.points()[point_idx];
clusters[label].push_back(point);
}
}
}
fprintf(stderr, "INFO: prepared ground clusters in: %lu us\n",
timer.measure());
this->ShareDataWithAllClients(clusters);
fprintf(stderr, "INFO: ground clusters shared: %lu us\n", timer.measure());
}
I am not sure what I miss here so that the processed pointcloud is exactly as the original?
from depth_clustering.
@niosus any advice, please :)
from depth_clustering.
@tuandle I'm sorry, I am currently really in a complete lack of time to debug your problem. The idea that you have is valid and should theoretically work, but I cannot look for an error in your code right now. I will keep it here and if I find the time I will look into this, but I cannot promise when this might happen. Sorry for that.
from depth_clustering.
@niosus no problem, thank you for your help anyway :)
from depth_clustering.
@niosus the _para._step is 870, does that means for speed up, you do not use all the points into process?
from depth_clustering.
@tuandle Hi I would like to recreate the same thing:
Just printing publishing/ printing the removed ground of the point cloud to evaluate it against other algorithms.
Have you found a solution/implementation yet?
from depth_clustering.
Related Issues (20)
- visualisation of clusters HOT 2
- Implementation on velodyne lidar HOT 5
- How to cluster your own point cloud data and visualize HOT 1
- Status of this package HOT 1
- assertion on unaligned arrays HOT 1
- Release for ROS Noetic HOT 4
- Can't achieve the same effect with my own data HOT 1
- Query on Cluster Visualization HOT 2
- Feature Request: Support ROS pointclouds from Ouster 128-beam LIDAR HOT 1
- Using two 16 line radar fusion data as input HOT 1
- build error HOT 7
- running in real time HOT 1
- running in real time HOT 3
- subscribing to clusters
- compile err error: ‘boost::filesystem’ has not been declared
- Opencv verison
- kitti dataset test error HOT 3
- Get labeled point cloud object HOT 2
- Interesting issue when using ProjectionParams::FromConfigFile method HOT 1
- 3 MEMS combined pointcloud HOT 1
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from depth_clustering.