cpu_tsdf icon indicating copy to clipboard operation
cpu_tsdf copied to clipboard

Question about cpu_tsdf::TSDFVolumeOctree::getFrustumCulledVoxels

Open hitsjt opened this issue 7 years ago • 3 comments

I am now reading your code to work out how tsdf works,and I can not understand the function getFrustumCulledVoxels.

In this function,there is a variable named cam2robot,what does it mean?

thank you.

hitsjt avatar Oct 26 '16 07:10 hitsjt

Hi @hitsjt ,

So the getFrustumCulledVoxels function is simply trying to minimize wasted time. Since we know the focal parameters and location of the camera, we know which voxels are not in its field of view. This means we can "cull" (i.e. trim down) only to the voxels we actually will need to update.

When we deal with poses, we tend to use what I'd call "Computer Vision" coordinates: X is right, Y is down, Z is forward. The PCL class we use for computing the view frustum, pcl::FrustumCulling, seems to use what I'd call "Robotics" coordinates, flipping X and Z and negating Y. This is just a coordinate transform from one arbitrary system to another:

Eigen::Matrix4f trans_robot = trans.matrix ().cast () * cam2robot;

sdmiller avatar Oct 26 '16 18:10 sdmiller

Thank you sdmiller! I still have more questions.

  • In function template <typename PointT, typename NormalT> int cpu_tsdf::TSDFVolumeOctree::updateVoxel ( const cpu_tsdf::OctreeNode::Ptr &voxel, const pcl::PointCloud<PointT> &cloud, const pcl::PointCloud<NormalT> &normals, const Eigen::Affine3f &trans_inv),
    • you transformed voxel center to current frame,and reproject it to get the current observation,am i right?
    • Then you do float d_new = (pt.z - v_g.z);to get the new distance,why is that?
    • and then what is the purpose of checking split in the following code?
  • Question about the coordinates If i am not wrong ,you put the whole volume center at (2,2,2),but where is the cam?

Thank you!

hitsjt avatar Oct 31 '16 03:10 hitsjt

@hitsjt sorry! This is why I shouldn't have turned github alerts off :(.

I'm guessing by now your questions are no longer relevant, but for posterity:

  • Yes, I transform the voxel center to the current frame and reproject it to get a new observation
  • This new "distance" is the new observation of d, where d is "how far, in the Z dimension, is the point from the voxel center?" If the point had been exactly at the voxel center, this would be an observation of 0, or a perfect reading of the surface.
  • My split-checking is all something I came up with, to try to make these things fit in memory. I keep big voxels and only iteratively make them smaller as needed. So if a point falls within a voxel, I check to see if I need to split it, then recursively check each split voxel for their own readings.
  • The coordinates are a bit arbitrary, just things I happened to notice work well for walking around a room with a Kinect. The camera is always at the origin (0,0,0) for me when I begin, but of course, you input that yourself whenever you call integrateCloud(). In general people record things by standing a bit away and pointing. So assuming it was about 2 meters in front of the camera seemed to work well.

sdmiller avatar Feb 07 '17 19:02 sdmiller