-
Notifications
You must be signed in to change notification settings - Fork 12
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Question/doubt about VDB allocation #2
Comments
For future travelers, this is the code I used to render the centroids of the VDB nodes:
void VDBMappingROS::publishInternalNodes() const {
if(m_internal_nodes_pub.getNumSubscribers() == 0) {
return;
}
ROS_INFO("Publish tree nodes centroids");
VDBMapping::GridT::Ptr grid{m_vdb_map->getMap()};
VDBMapping::PointCloudT::Ptr cloud(new VDBMapping::PointCloudT);
for (auto nodeIterator = grid->tree().cbeginNode(); nodeIterator; ++nodeIterator)
{
const openvdb::CoordBBox nodeBoundingBox{nodeIterator.getBoundingBox()};
const openvdb::Vec3f nodeCenterWorldCoordinates{grid->indexToWorld(nodeIterator.getCoord())};
const unsigned int nodeDepth{nodeIterator.getDepth()};
// Add points to point cloud.
VDBMapping::PointT point;
point.x = nodeCenterWorldCoordinates.x();
point.y = nodeCenterWorldCoordinates.y();
point.z = nodeCenterWorldCoordinates.z();
if(nodeDepth == 0) {
// Root.
// Color: Red.
point.r = 255;
point.g = 0;
point.b = 0;
} else if(nodeDepth == 1) {
// Internal node level 1.
// Color: Green.
point.r = 0;
point.g = 255;
point.b = 0;
} else if(nodeDepth == 2) {
// Internal node level 2.
// Color: Blue.
point.r = 0;
point.g = 0;
point.b = 255;
} else if(nodeDepth == 3) {
// Leaf node.
// Color: White.
point.r = 255;
point.g = 255;
point.b = 255;
} else {
// Anything else.
// Color: Gray.
point.r = 150;
point.g = 150;
point.b = 150;
}
point.a = 255.0;
cloud->points.emplace_back(std::move(point));
}
cloud->width = cloud->points.size();
cloud->height = 1;
sensor_msgs::PointCloud2 internal_nodes_cloud_msg;
pcl::toROSMsg(*cloud, internal_nodes_cloud_msg);
internal_nodes_cloud_msg.header.frame_id = m_map_frame;
internal_nodes_cloud_msg.header.stamp = ros::Time::now();
m_internal_nodes_pub.publish(internal_nodes_cloud_msg);
}
void VDBMappingROS::publishVoxels() const {
if(m_voxels_pub.getNumSubscribers() == 0) {
return;
}
ROS_INFO("Publish voxel centroids");
VDBMapping::GridT::Ptr grid{m_vdb_map->getMap()};
VDBMapping::PointCloudT::Ptr cloud(new VDBMapping::PointCloudT);
for (auto iter = grid->cbeginValueAll(); iter; ++iter)
{
const openvdb::Vec3f world_coord{grid->indexToWorld(iter.getCoord())};
const unsigned int nodeDepth{iter.getDepth()};
VDBMapping::PointT point;
point.x = world_coord.x();
point.y = world_coord.y();
point.z = world_coord.z();
if(iter.isValueOn()) {
// Active voxel.
// Color: Yellow/gold.
point.r = 255;
point.g = 215;
point.b = 0;
} else {
// Inactive voxel.
// Color: Pink-ish.
point.r = 255 - nodeDepth * 30;
point.g = 105 - nodeDepth * 10;
point.b = 180 + nodeDepth * 10;
}
point.a = 255.0;
cloud->points.emplace_back(std::move(point));
}
cloud->width = cloud->points.size();
cloud->height = 1;
sensor_msgs::PointCloud2 cloud_msg;
pcl::toROSMsg(*cloud, cloud_msg);
cloud_msg.header.frame_id = m_map_frame;
cloud_msg.header.stamp = ros::Time::now();
m_voxels_pub.publish(cloud_msg);
} |
@MGBla I put a reduced version of the code that is run in the program info a single snippet, and reported the issue into the OpenVDB upstream as well, as I was unsure of whether this is a general aspect of OpenVDB, or something specific of the code. AcademySoftwareFoundation/openvdb#1329 Thank you again for looking into it 🙂 |
Hi Yoshua, first of all I'm glad to hear that my package could help you. This is a quite interesting issue and I tested around a little with your code and tried to replicate your results as best as possible. Concerning the size of the grid, as is see it you missed one decimal and the grid is only 1.6MB However adding additional datapoints within the same leaf node (in this case coordinates below Adding additional points on leaf level Adding (0,0,7): Adding points on first level Adding (0,0,8): Adding (0,0,16): Adding point on second level Adding (0,0,128) Adding point on third level Adding (0,0,4096) with sizeof(datatype) = 0.000032 MB From this I would reason, that only the necessary nodes of the tree along the way to the leaf node are Level 2 Level 3 As a result the farther a new datapoint is away from the currently allocated grid the more the So back to your questions:
I hope this made enough sense otherwise feel free to keep up the discussion. Best wishes |
Hi @MGBla, Thank you very much for the reply and for testing the code 👍 Based on your observation that memory is only allocated when a new point is integrated into a voxel block that is far from the volume of VDB, I think there are measures I could take to account for this during live operation, including:
Regarding your observation about grids with complex types, I've read posts from the VDB authors inviting users to allocate multiple trees in parallel to represent different data fields. I can see a bit benefit in flexibility (e.g. the possibility of representing an arbitrary number of fields through new trees), and in re-using existing VDB utilities. But beyond that, this seems like a significant compute/memory overhead. What do you think? Best regards, |
Hi Yoshua, Sorry for the late reply but I had a quite stressful week. From a computational perspective having to make multiple accesses on different trees obviously costs much more than making a single access to get the single complex data type. But re-using existing VDB utilities might be a big selling point. Until know I only used morphological operators which operate as far as I know only on the active state of the grid which should also be possible with complex datatypes. But it might be interesting to explore more of the internal functionality and see what is also relevant in a mapping context. Best regards, |
Hi @MGBla, In your reply:
Did you imply that when instantiating points far away, for example, we would also get multiple tiles instantiated on the way to that point?
For example ^ Thank you in advance, |
Hi,
First of all, thank you very much for creating this package and sharing it with the community. From the paper to the code, I found strong scientific value, and in honesty, the code was a key enabler for me to run quick experiments with VDB 🙏
In order to inspect the VDB structure at a deeper level, I implemented a set of functions to render point clouds with the centroids of:
a. Root (Color: Red)
b. Internal nodes level 1 (Color: Green)
c. Internal nodes level 2 (Color: Blue)
d. Lead nodes level 2 (Color: White)
a. Active voxels (Color: Yellow)
a. Inactive voxels (Color: Pink-ish)
Problem
I ran an experiment, adding one point
(1,1,1)
into VDB in the following manner:Note that I implemented a custom data container which is literally an extended version of Vec3i with space for normals, and switched the desired resolution to 15cm. The rest of the code from vdb_mapping/vdb_mapping_ros is intact.
When I rendered the corresponding centroids, I noticed that while the internal nodes of VDB are quite sparse (literally only one active):
The inactive value-carrying nodes (internal nodes level 2 and leaf nodes) close to the leafs seem to be plenty:
Upon zooming out and increasing the visualization marker size, I could see the same pattern on internal nodes level 1 and 2:
Furthermore, I collected some metrics:
As you can see, the bounding box is minimal, only containing the point I added to the tree, and the voxel count is 1. Nonetheless, 1.6MB of memory for such a sparse tree (only one element) seems like quite a bit.
Questions
a. Could it be that OpenVDB instantiates the tree topology required for a whole sub-branch of the tree upon setting one voxel as active?
Thank you very much in advance.
Best regards,
Yoshua Nava
The text was updated successfully, but these errors were encountered: