High-level map-merging interface. More...
Classes | |
struct | map_merge_3d::MapMergingParams |
Parameters for map merging high-level interface. More... | |
Functions | |
PointCloudPtr | map_merge_3d::composeMaps (const std::vector< PointCloudConstPtr > &clouds, const std::vector< Eigen::Matrix4f > &transforms, double resolution) |
Composes the global map. More... | |
std::vector< Eigen::Matrix4f > | map_merge_3d::estimateMapsTransforms (const std::vector< PointCloudConstPtr > &clouds, const MapMergingParams ¶ms) |
Estimate transformations between n pointclouds. More... | |
std::ostream & | map_merge_3d::operator<< (std::ostream &stream, const MapMergingParams ¶ms) |
High-level map-merging interface.
High-level interface to estimate transformations between n pointclouds and compositing global map..
PointCloudPtr map_merge_3d::composeMaps | ( | const std::vector< PointCloudConstPtr > & | clouds, |
const std::vector< Eigen::Matrix4f > & | transforms, | ||
double | resolution | ||
) |
Composes the global map.
Pointclouds with zero transformation will be skipped.
clouds | input clouds |
transforms | estimated transformations between input clouds |
resolution | resolution of the output pointcloud |
std::vector<Eigen::Matrix4f> map_merge_3d::estimateMapsTransforms | ( | const std::vector< PointCloudConstPtr > & | clouds, |
const MapMergingParams & | params | ||
) |
Estimate transformations between n pointclouds.
Estimation is based on overlapping space. One of the pointclouds will be selected as the reference frame for all the transformations.
clouds | input pointclouds |
params | parameters for estimation |
std::ostream& map_merge_3d::operator<< | ( | std::ostream & | stream, |
const MapMergingParams & | params | ||
) |