Closed lin-name closed 1 year ago
Hello!
I'm afraid I haven't run this code in quite some time, so my debugging abilities might be limited :). But a few things jump out to me:
1) Are the units and dimensions roughly the same in your input data? X/Y/Z not being the same meaning could cause this (we assume Z is forward); so could the distance from the camera not being within the range of min_sensordistance and max_sensordistance.
2) Is the data in an organized point cloud? That is, the cloud itself has a width and height attribute?
3) If all else fails, you should try running the integrate script with the --cloud-only
option enabled. This will aggregate just point clouds together, which should let you know if it's reading the data correctly (at which point it's just a TSDF setting issue) or if it's not reading it at all (at which point it's an issue with the input data).
Hope this helps!
Thanks for your advice. With the --cloud-only option, it get the aggregated point cloud right as followed:
as we can see in the image, a toy horse on a turntable, and i modify the base parameter of the camera intrinsics , image size and tsdf_size, cell_size in integrate.cpp like image above, my own camera paras and my own tsdf_size, voxel_size as well as the DepthTruncationLimits like below:
but the out mesh is mush odd, it seems the input point is partial truncated.
I have tried to modify this paras listed above again and again, but the output is still partial. How can i get a right complete mesh? Which parameter(s) count much? Looking forward for your reply. Thanks.
Hi @guan-lin,
I'm afraid I can't tell much by staring at the results. But if you shoot me an email (you can find my address on my website, sdavidmiller.com ) with the input data, I'd be happy to take a look!
Hi, I have sent you a email for the input data. Please check your email. So sorry to trouble you!
Hi guan-lin,
I haven't gotten to spend much time with the data yet (only a few minutes), but I did notice something interesting. When I ran my intrinsics tool:
./build/get_intrinsics ./guan-lin-sample/data/0000.pcd
Loading cloud ./guan-lin-sample/data/0000.pcd
Bounds:
X: [-136.757675, 105.725403]
Y: [-99.908882, 60.127434]
Z: [575.265625, 736.812500]
Width: 320
Height: 256
fx: 631.175415
fy: 631.043762
cx: 151.616364
cy: 125.248154
Total reprojection error: 0.000000
I see that your data has very large units: that Z value in particular, ranging from 500 to 700. By default, my tool is set up in a way where it assumes we're working with meters, not millimeters. So that was the first hunch that something was up.
Sure enough, even without adjusting any other parameters (not even touching intrinsics, which of course we should!), I was able to get a reasonable test output (attached) just be adding two flags:
./build/integrate --in ./guan-lin-sample/data --out=out --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 --color
Note "cloud-units" and "pose-units". In the codebase, this was a quick trick I'd baked in years ago. All it does is re-normalizes the cloud by the multiplier:
if (cloud_units != 1)
{
for (size_t i = 0; i < cloud->size (); i++)
{
pcl::PointXYZRGBA &pt = cloud->at (i);
pt.x *= cloud_units;
pt.y *= cloud_units;
pt.z *= cloud_units;
}
}
And does the same for poses:
poses[i].matrix ().topRightCorner <3, 1> () *= pose_units;
Of course, the system should work without this trick. But it hints to me that the problem is going to have something to do with TSDF voxel sizes, min_sensor_distance, and max_sensor_distance: something which is assuming a very small number (meters) and getting a very big number (millimeters). Today, with max_sensor_dist
defaulting to 3 (i.e., anything more than 3 units away gets cut off), you can see why it would return no data.
I hope this helps. I can hopefully take a look more this weekend, but I think this hint should be enough to get you started.
-Stephen
Dear Stephen, Thank you very much for your help. But i do have set the "cloud-units" and "pose-units" both to 0.001. I sent you the second email yesterday about the units: [cid:f44c133f-8e63-4851-b65b-f6a1499bba3d] Also, we can see that from the aggregated point cloud a few days ago, see the "Box dimensions" (which means the Bounding Box) in the picture below: [cid:a9de5bad-98ce-40a4-ac09-9b30612781a8]
So, the "cloud-units" and "pose-units" have been both right set to 0.001 from the beginning, and with those parameters you listed(not touching intrinsics) above:
./build/integrate --in ./guan-lin-sample/data --out=out --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 --color
the test output mesh does come out as below(the same with yours above): [cid:fda2e385-9ff9-4b32-bc75-c33607e33673] But my question is when i modify the intrinsics to myself camera_intrinsics in integrate.cpp, like: [cid:4423e9cc-e8eb-47d6-bf11-abf9a0b63d35]
And comment out the codes below:
[cid:e2007634-54d2-4527-918d-18d81be324f0]
The output mesh turns to be odd. [cid:507374f9-d753-42cf-b120-fc30bf1fe6a9]
So why your parameters
--cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 and your intrinsics:
float focal_lengthx = 525.;
float focal_lengthy = 525.;
float principal_pointx = 319.5; float principal_pointy = 239.5;
the output mesh is reasonable, but when i use
--cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 and my own intrinsics:
float focal_lengthx = 631.175415; float focal_lengthy = 631.043213; float principal_pointx = 151.61637875; float principal_pointy = 125.2481385;
and i comment out the code below:
[cid:1383c5d1-2374-41f3-9d96-1f83365ee1e4]
the output mesh is odd.
Can you try to use my own intrinsics in the camera-intrinsics.txt or the output fx, fy, cx, cy from your intrinsics tool and debug the code again?
And you will find the problem.
Maybe some parameters about the intrinsics are set fixed which is not suitable for our own modified intrinsics when integrates clouds into the tsdf, i guess.
Thank you.
Looking forward to hearing from you!
发件人: Stephen Miller @.> 发送时间: 2022年10月20日 5:28 收件人: sdmiller/cpu_tsdf @.> 抄送: guan-lin @.>; Mention @.> 主题: Re: [sdmiller/cpu_tsdf] How to run my local data? (Issue #53)
Hi guan-lin,
I haven't gotten to spend much time with the data yet (only a few minutes), but I did notice something interesting. When I ran my intrinsics tool:
./build/get_intrinsics ./guan-lin-sample/data/0000.pcd Loading cloud ./guan-lin-sample/data/0000.pcd Bounds: X: [-136.757675, 105.725403] Y: [-99.908882, 60.127434] Z: [575.265625, 736.812500] Width: 320 Height: 256 fx: 631.175415 fy: 631.043762 cx: 151.616364 cy: 125.248154 Total reprojection error: 0.000000
I see that your data has very large units: that Z value in particular, ranging from 500 to 700. By default, my tool is set up in a way where it assumes we're working with meters, not millimeters. So that was the first hunch that something was up.
Sure enough, even without adjusting any other parameters (not even touching intrinsics, which of course we should!), I was able to get a reasonable test output (attached) just be adding two flags:
./build/integrate --in ./guan-lin-sample/data --out=out --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 --color
[guan-lin-mesh]https://user-images.githubusercontent.com/353593/196807924-c938a139-a44a-48ab-9bdd-2b50bf72ad5a.png
Note "cloud-units" and "pose-units". In the codebase, this was a quick trick I'd baked in years ago. All it does is re-normalizes the cloud by the multiplier:
if (cloud_units != 1) { for (size_t i = 0; i < cloud->size (); i++) { pcl::PointXYZRGBA &pt = cloud->at (i); pt.x = cloud_units; pt.y = cloud_units; pt.z *= cloud_units; } }
And does the same for poses:
poses[i].matrix ().topRightCorner <3, 1> () *= pose_units;
Of course, the system should work without this trick. But it hints to me that the problem is going to have something to do with TSDF voxel sizes, min_sensor_distance, and max_sensor_distance: something which is assuming a very small number (meters) and getting a very big number (millimeters). Today, with max_sensor_dist defaulting to 3 (i.e., anything more than 3 units away gets cut off), you can see why it would return no data.
I hope this helps. I can hopefully take a look more this weekend, but I think this hint should be enough to get you started.
-Stephen
― Reply to this email directly, view it on GitHubhttps://github.com/sdmiller/cpu_tsdf/issues/53#issuecomment-1284593139, or unsubscribehttps://github.com/notifications/unsubscribe-auth/APUZ32EBT6OYX5JJNJY3TN3WEBRX3ANCNFSM6AAAAAARAUI4M4. You are receiving this because you were mentioned.Message ID: @.***>
Hi @guan-lin,
Sorry about that! I'm afraid I never received, or at least didn't notice, your second email. I am using the same parameters as you and am able to reproduce your issues: stay tuned.
P.S. It doesn't look like the images you meant to attach worked in this GitHub post. Could you try to upload them again?
Hi Stephen, Sorry about the images. I replied with the email, the images display correctly, but does not attached in the GitHub. So, here is the original text of the message: ------------------------------------------------------------------------------------------ But i do have set the "cloud-units" and "pose-units" both to 0.001. I sent you the second email yesterday about the units:
Also, we can see that from the aggregated point cloud a few days ago, see the "Box dimensions" (which means the Bounding Box) in the picture below:
So, the "cloud-units" and "pose-units" have been both right set to 0.001 from the beginning, and with those parameters you listed(not touching intrinsics) above:
_./build/integrate --in ./guan-lin-sample/data --out=out --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 --color the test output mesh does come out as below(the same with yours above): But my question is when i modify the intrinsics to myself camera_intrinsics in integrate.cpp, like: And comment out the codes below: The output mesh turns to be odd. So why your parameters --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 and your intrinsics: float focal_lengthx = 525.; float focal_lengthy = 525.; float principal_pointx = 319.5; float principal_pointy = 239.5; the output mesh is reasonable, but when i use --cloud-units=0.001 --pose-units=0.001 --width=320 --height=256 and my own intrinsics: float focal_lengthx = 631.175415; float focal_lengthy = 631.043213; float principal_pointx = 151.61637875; float principal_pointy = 125.2481385; and i comment out the code below: the output mesh is odd.
Can you try to use my own intrinsics in the camera-intrinsics.txt or the output fx, fy, cx, cy from your intrinsics tool and debug the code again?
And you will find the problem.
Maybe some parameters about the intrinsics are set fixed which is not suitable for our own modified intrinsics when integrates clouds into the tsdf, i guess.
By the way, based on my own intrinsics, i just tried to modified those parameters: the tsdf_size, cell_size and trunc_dist_neg
The out mesh sees to be slightly refined(because of a samller voxel size comes out a higher resolution ), but is still incomplete(still truncated):
It sees that Modifying the trunc_dist_neg parameter counts much. May the trunc_dist_neg caused the truncation? But a negative value of the trunc_dist_neg can not run for the project. I will continue debugging this data these days.
Hope to get good news.
Hi @guan-lin,
I haven't solved the bug yet, but I believe I have identified it. The problem seems to be in the Frustum Culling logic: an optimization which makes this run faster, by not bothering to integrate on voxels which are out of the field of view.
Here's how I did it, in the getFrustumCulledVoxels
function of src/lib/tsdf_volume_octree.cpp
// Fake logic: don't cull anything based on focal length
fc.setHorizontalFOV (180);
fc.setVerticalFOV (180);
// Set the FOV based on focal length and image size
//fc.setHorizontalFOV (1.1 * 2*fabs(atan(0.5*image_width_/focal_length_x_) * 180 / M_PI));
//fc.setVerticalFOV (1.1 * 2*fabs(atan(0.5*image_height_/focal_length_y_) * 180 / M_PI));
Using your parameters and simply commenting out the culling logic as done above, I'm able to get a rather beautiful mesh:
I'll need to debug to understand why the field of view logic is failing...my guess is something about this ogic isn't handling particular field of views and is accidentally cutting them off too aggressively. Either that, or pcl::FrustumCulling is expecting poses in a different way than I was aware of 10 years ago. But since it will take some visual debugging to solve that, I probably won't get to it until the weekend.
In the meantime, I hope the patch I gave you above can help you move forward! Will keep you posted on the ultimate fix.
Hi Stephen, Yes, Modifying the parameter of the FrustumCulling works well! Thank you very much! As we know, Voxels completely outside the view of the frustum will not be displayed when rendering. This is the crux of this problem.
Beside, I have another questions about parameter setting, the tsdf_size, which represents the range in the x, y, z directions of the object.
As shown above, the value of the tsdf_size uesd in the code is several times larger than the actual object size, and object is not always equal in this three directions in size. I am wondering if it possible to set this parameter by referring to the bounding box of the aggregated point cloud of the actual object,in this case,a smaller and more effective space can produce a more refined(with higher resolution) model. This is just an extremely simple idea of mine, wish a catalyst for a more optimized tsdf application. Thank you, Stephen.
Looking forward for your achievements!
Hi @guan-lin,
Quick update. I don't believe the FrustumCulling logic itself is wrong, so much as it behaves very badly with some initial values I set. I'll explain once I have a more clever fix :) But for now, if you revert the above changes (i.e. let src/lib/tsdf_volume_octree.cpp
be exactly as it used to be), you can get a decent output by simply adding this to integrate.cpp
:
float maxCellSize = 0.1f; //10 cm voxels are as big as we need to go, as the data is quite small
tsdf->setMaxVoxelSize (maxCellSize, maxCellSize, maxCellSize);
Essentially, my algorithm works by saying "Most voxels can be very large: there's no reason to have ultra high resolution until we see data. Once we intersect with a ray from the depth map, then we can iteratively make smaller and smaller voxels to show details"
The problem is, I cull voxels based on their center point: if the center of the voxel is not in the field of view of the camera, I ignore it altogether. This was not a problem with the Kinect, where the field of view is quite large: most things we are "looking at" would have been retained, and whatever was at the periphery was likely bad data to begin with. But with your sensor, the small field of view likely means it is missing many many voxels it should have hit, simply because the maximum size (currently 0.5 meters by default) is so large, the center point of the voxel is no longer in the field of view of the camera (even though much of the voxel is in the field of view).
Eventually I'll come up with some smarter initializations to make this unnecessary, and also try to rework the FrustumCulling logic to say "is any of the voxel in the field of view?" rather than "is the center of the voxel in the field of view?". But for now, the setMaxVoxelSize
parameter should solve this for you.
To make this easier, I've added a --max-cell-size
parameter to the integrate script. See this PR for the changes: https://github.com/sdmiller/cpu_tsdf/pull/55
Hi, Stephen Thanks for your meaningful work of this project. I have build this project on Wins10 with VS2019 successfully, run the Augmented ICL-NUIM dataset , and get right output. But when i use my own local data(obtained from my own scanner with images (320*256) and poses correspondingly, transform the image into point clouds with the my intrinsics_files ), and i try to modify the base parameter of the camera intrinsics , image size and tsdf_size, cell_size in integrate.cpp like below:
and i try to modify the tsdf_size, cell_size many times, but it cames out like below:
Why there is no *.ply mesh files in the --out path?
Looking forward for your reply. Thanks.