Closed yanconglin closed 1 year ago
Hey,
this is hard to say without having the data at hand. Can you specify which data you used?
Are these the first two frames of the sequence? Is the car already in motion?
yes, I have shared the code snippet and data with you. The data contains 5 consecutive frames from waymo. Here is a mini example: kiss_icp_waymo_failure
Thank you!
I think I found the problem. When estimating the first relative pose, we do not have a good initial guess since our prediction model requires at least two estimated poses (assuming no other sensors like IMU or wheel odometry). Therefore, we initialize our estimation with an identity pose. KISS-ICP finds a local minimum by aligning the scan lines as you can see in your image. We found that KISS-ICP usually recovers from this after some frames (check for example KITTI odometry sequence 12). In your case, 5 frames is probably not enough. Have you tried running it on the whole sequence?
A fast way to improve this is to increase the initial_threshold
parameter. If you for example set it to 10, you will 1. keep all correspondences and 2. reduce their suppression by the robust kernel. Using the default parameters and increasing the initial threshold to 10, the pipeline already recovers after a couple of frames:
However, these are rather edge cases for which you might need to find a more customized initialization phase or the integration of other sensors.
many thanks for the reply.
Strange, increasing "initial_threshold: 10.0" does not help on my local machine. Can you please share with me the config file?
have not tested on a longer sequence yet. Unfortunately, the benchmark is setup in such a way that every 5 frames are a clip. I will have a test later and let you know the result.
Are you using our pipeline and visualizer? I did not use the code you sent me except the data loading part to convert the point clouds to ply
files. I used this config with only the initial_threshold
parameter changed.
I am using class KISS_ICP, with my own datalodaer which directly takes as input the given '.npz' file as indicated in the code snippet.
In the snippet you sent me you are importing KissICP
but using the egomotion
class instead.
well, I renamed "KISS_ICP" class to "egomotion" class for the clarity (for the project I am working on). The "egomotion" class is simply a copy of the "KISS_ICP" class, because I do not want to alternate the KISS_ICP codebase. sorry for the confusion
Ah okay! I did not compare if it's exactly the same.
There seems to be a bug in the parser.py: https://github.com/PRBonn/kiss-icp/blob/1b0529169b2461272a97e959e2a9deea57dbb661/python/kiss_icp/config/parser.py#L70
Set deskew=True manually, I got an error message after 2nd frame:
deskew_frame = kiss_icp_pybind._deskew_scan(
TypeError: _deskew_scan(): incompatible function arguments. The following argument types are supported:
1. (frame: kiss_icp.pybind.kiss_icp_pybind._Vector3dVector, timestamps: List[float], start_pose: numpy.ndarray[numpy.float64[4, 4]], finish_pose: numpy.ndarray[numpy.float64[4, 4]]) -> kiss_icp.pybind.kiss_icp_pybind._Vector3dVector
Invoked with: kwargs: frame=std::vector<Eigen::Vector3d> with 136095 elements.
Use numpy.asarray() to access data., timestamps=2, start_pose=array([[1., 0., 0., 0.],
[0., 1., 0., 0.],
[0., 0., 1., 0.],
[0., 0., 0., 1.]]), finish_pose=array([[ 9.99999822e-01, -4.88604132e-04, 3.41008581e-04,
-2.64622212e-02],
[ 4.88578179e-04, 9.99999878e-01, 7.61847811e-05,
-2.12635982e-02],
[-3.41045764e-04, -7.60181582e-05, 9.99999939e-01,
-2.09292144e-02],
[ 0.00000000e+00, 0.00000000e+00, 0.00000000e+00,
1.00000000e+00]])
Did you forget to `#include <pybind11/stl.h>`? Or <pybind11/complex.h>,
<pybind11/functional.h>, <pybind11/chrono.h>, etc. Some automatic
conversions are optional and require extra headers to be included
when compiling your pybind11 module.
You are passing the wrong timestamps. This is supposed to be a N x 1
numpy array of the individual timestamps for each of the N
points in the frame.
Hi, again, I would like to ask if KISS-ICP is deterministic, as I obtained slightly different results on the same sequence. I wonder if there is a way to fix the randomness or am I making a mistake? This would be great for debugging, since KISS-ICP is the very first step of a complicated framework.
What kind of randomness are you observing, so how much does it affect the results?
Hi, I am using KISS-ICP for ego-motion estimation. each time it outputs a slightly different result. Currently, I am debugging my model, which requires a deterministic pose from ego-motion estimation.
I moved this to a new issue since this is already closed, see https://github.com/PRBonn/kiss-icp/issues/165
Thank you for releasing the tool. Recently I am tryin KISS_ICP on waymo for ego motion estimation. However, I find several failure case where the model goes substantially wrong. Attached please find an example. Could you please tell me how to fix this issue (e.g., picking the correct parameters)?
The figure shows two registered frames (colored in blue and green). As you can see the the non-ground points do not align.