Comments (7)
@DarrenWong
Thanks for letting me know the issue. It's strange that the processing time varies so much and sometimes takes a second for one frame. I'll take a look at your rosbag to find the cause.
from fast_gicp.
many thanks for taking your time @koide3 , can you reproduce the issue in my experiment?
from fast_gicp.
Yes, I confirmed the reported behavior on my PC. I need a bit more time to dig into the problem.
from fast_gicp.
I guess the problem stems from the large number of input points. With voxelgrid resolution = 0.1, the number of of points becomes about 25k in average. It's a bit too much for scan matching, and the gauss newton optimizer can suffer from such many input points. By setting the resolution to 0.25 (or larger), the number of points becomes less than 15k points, and in this settings, I didn't see the problem.
Maybe we need a more stable optimizer (e.g., LM). I would implement it if I could find enough spare time.
from fast_gicp.
Got it and thansk for your reply. LM optimizer shall be better than gauss newton theoretically.
One more question, how can I set the voxelgrid resolution? I integrated the fast-gicp in hdl_slam with below registration method in here. https://github.com/koide3/hdl_graph_slam/blob/701a39e17e2be6d39261b5f27e0d1df993efbc99/src/hdl_graph_slam/registrations.cpp#L36
if(registration_method.find("VCUDA") != std::string::npos){
std::cout << "registration: GICP_VGICP" << std::endl;
boost::shared_ptr<fast_gicp::FastVGICPCuda<PointT, PointT>> gicp(new fast_gicp::FastVGICPCuda<PointT, PointT>());
gicp->setResolution(1.0);
return gicp;
}
I default set it 1.0 (is it means voxelgrid resolution = 0.1? ), I try to change to 3.0, but seems worser.
from fast_gicp.
There is a nodelet that is in charge of voxelgrid downsampling. You can change downsample_resolution
at the following line:
https://github.com/koide3/hdl_graph_slam/blob/701a39e17e2be6d39261b5f27e0d1df993efbc99/launch/hdl_graph_slam_400.launch#L28
from fast_gicp.
I changed the <param name="downsample_resolution" value="0.3" />
to 0.3.
Yes, the processing time is fast but still appears some processing time too large.
I think the root cause is the iteration too long in some frame which contains numerous cars or initial guess not well...
I agree that a stable optimizer would be better. Thanks for your helping!
MEDIAN 13.24 / MEAN 15.60 / 1002.834822
from fast_gicp.
Related Issues (20)
- Crash while using VGICP
- how to take fast_gicp in my own code? HOT 3
- About NeighborSearchMethod HOT 1
- got "for_each: failed to synchronize" in every position using "thrust::for_each" HOT 2
- doc request: aligned output point cloud must be different from source and target HOT 1
- Registration score gradually diverges. HOT 3
- cudaErrorIllegalAddress: an illegal memory access was encountered HOT 1
- I want getTransformationProbability() function in ndt_cuda HOT 1
- Unexpected Performance: Single-Threaded Faster than Multi-Threaded in Point Cloud Alignment HOT 2
- Why is the **weight** the square root of the number of points? HOT 4
- the calculation of **rho** in step_lm() seems wrong HOT 2
- set step size on ndt_cuda
- Optimization Problem for Fast GICP (OpenMP)
- any bug in ndt_cuda? HOT 1
- core dumped HOT 1
- How to implement the pcl version of GICP?
- can't build fast_gicp.lib HOT 2
- fast_gicp iteration HOT 1
- Fast-gicp DO HOT 1
- Fast-gicp DO NOT 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 fast_gicp.