How to raycast occupancy? #80
-
My idea is to extract depth maps from octree map given arbitrary camera pose and intrinsics. As I understand, core functionality to accomplish this is to be able to cast ray and get coordinates of the first point whose occupancy is higher than some threshold. So my question is where to start? I found this Ray class, but not even sure if this is the right thing I need) P.S. congratulations on the great refactoring, new project structure is awesome! |
Beta Was this translation helpful? Give feedback.
Replies: 2 comments 14 replies
-
First idea is to sample points along the ray and call |
Beta Was this translation helpful? Give feedback.
-
Thanks! I'm glad to hear you like the new structure. It took some time, but it should solve all the issues you highlighted in #41 :) Ray tracing is computationally expensive, so moving critical loops to C++ to improve performance is probably worth it. You could work primarily in Python and, when needed, migrate heavy sections directly into the pywavemap interface (this is probably easier than moving them to the C++ library and then writing bindings separately). With an Editable install and You can leverage the const Point3D start_point; // the start point of your ray (usually the sensor's origin)
const Point3D end_point; // the end point of your ray (usually at a given max dist from your sensor)
const FloatingPoint occupancy_threshold = 0.1f; // threshold above which you consider a cell occupied
const FloatingPoint min_cell_width = map.getMinCellWidth();
const Ray ray(start_point, end_point, min_cell_width);
for (const Index3D& ray_voxel_index : ray) {
if (occupancy_threshold < map.getCellValue(ray_voxel_index)) {
const Point3D voxel_center = convert::indexToCenterPoint(ray_voxel_index, min_cell_width);
return (voxel_center - start_point).norm();
}
}
return (end_point - start_point).norm(); This approach ensures that you visit every voxel intersected by the ray, whereas query points found by interpolating the ray are likely to miss some voxels. Another advantage is that this way, it's easy to end the queries as soon as the nearest occupied voxel is found. |
Beta Was this translation helpful? Give feedback.
Thanks! I'm glad to hear you like the new structure. It took some time, but it should solve all the issues you highlighted in #41 :)
Ray tracing is computationally expensive, so moving critical loops to C++ to improve performance is probably worth it. You could work primarily in Python and, when needed, migrate heavy sections directly into the pywavemap interface (this is probably easier than moving them to the C++ library and then writing bindings separately). With an Editable install and
-Ceditable.rebuild=true
, any changes to the C++ code will automatically recompile when running your Python script.You can leverage the
RayIterator
to visit all voxels intersected by a ray, ordered by d…