Skip to content

Commit

Permalink
new functions insertPointCloud(...) replace insertScan(...),
Browse files Browse the repository at this point in the history
pruning argument no longer necessary (see #16)
  • Loading branch information
Armin Hornung committed Apr 3, 2013
1 parent b3ca41b commit 45551dd
Show file tree
Hide file tree
Showing 9 changed files with 124 additions and 111 deletions.
2 changes: 1 addition & 1 deletion octomap/doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ You can find an overview at http://octomap.github.com/ and the code repository a
Jump right in and have a look at the main class \ref octomap::OcTree OcTree and the examples in src/octomap/simple.cpp.
To integrate single measurements into the 3D map have a look at
\ref octomap::OcTree::insertRay "OcTree::insertRay(...)", to insert full 3D scans (pointclouds) please have a look at
\ref octomap::OcTree::insertScan "OcTree::insertScan(...)". Queries can be performed e.g. with \ref octomap::OcTree::search "OcTree::search(...)" or
\ref octomap::OcTree::insertPointCloud "OcTree::insertPointCloud(...)". Queries can be performed e.g. with \ref octomap::OcTree::search "OcTree::search(...)" or
\ref octomap::OcTree::castRay(...) "OcTree::castRay(...)". The preferred way to batch-access or process nodes in an Octree is with the iterators
\ref leaf_iterator "leaf_iterator", \ref tree_iterator "tree_iterator", or \ref leaf_bbx_iterator "leaf_bbx_iterator".</p>
Expand Down
188 changes: 103 additions & 85 deletions octomap/include/octomap/OccupancyOcTreeBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,107 +75,125 @@ namespace octomap {
/// Copy constructor
OccupancyOcTreeBase(const OccupancyOcTreeBase<NODE>& rhs);

/**
* Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
* Special care is taken that each voxel
* in the map is updated only once, and occupied nodes have a preference over free ones.
* This avoids holes in the floor from mutual deletion and is more efficient than the plain
* ray insertion in insertScanRays().
*
* @param scan Pointcloud (measurement endpoints), in global reference frame
* @param sensor_origin measurement origin in global reference frame
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param pruning whether the tree is (losslessly) pruned after insertion (default: true)
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertScan(const Pointcloud& scan, const octomap::point3d& sensor_origin,
double maxrange=-1., bool pruning=true, bool lazy_eval = false);

/**
* Integrate a 3d scan (transform scan before tree update), parallelized with OpenMP.
* Special care is taken that each voxel
* in the map is updated only once, and occupied nodes have a preference over free ones.
* This avoids holes in the floor from mutual deletion and is more efficient than the plain
* ray insertion in insertScanRays().
*
* @param scan Pointcloud (measurement endpoints) relative to frame origin
* @param sensor_origin origin of sensor relative to frame origin
* @param frame_origin origin of reference frame, determines transform to be applied to cloud and sensor origin
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param pruning whether the tree is (losslessly) pruned after insertion (default: true)
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertScan(const Pointcloud& scan, const point3d& sensor_origin, const pose6d& frame_origin,
double maxrange=-1., bool pruning = true, bool lazy_eval = false);

/**
* Insert a 3d scan (given as a ScanNode) into the tree, parallelized with OpenMP.
*
* @param scan ScanNode contains Pointcloud data and frame/sensor origin
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param pruning whether the tree is (losslessly) pruned after insertion (default: true)
* @param lazy_eval whether the tree is left 'dirty' after the update (default: false).
* This speeds up the insertion by not updating inner nodes, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertScan(const ScanNode& scan, double maxrange=-1., bool pruning = true, bool lazy_eval = false);

/// @note Deprecated, use insertScanRays instead.
OCTOMAP_DEPRECATED( virtual void insertScanNaive(const Pointcloud& scan, const point3d& sensor_origin, double maxrange, bool pruning = true, bool lazy_eval = false));

/**
* Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
* This function simply inserts all rays of the point clouds as batch operation.
* Discretization effects can lead to the deletion of occupied space, it is
* usually recommended to use insertScan() instead.
* Special care is taken that each voxel
* in the map is updated only once, and occupied nodes have a preference over free ones.
* This avoids holes in the floor from mutual deletion and is more efficient than the plain
* ray insertion in insertPointCloudRays().
*
* @param scan Pointcloud (measurement endpoints), in global reference frame
* @param sensor_origin measurement origin in global reference frame
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param pruning whether the tree is (losslessly) pruned after insertion (default: true)
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertScanRays(const Pointcloud& scan, const point3d& sensor_origin, double maxrange = -1., bool pruning = true, bool lazy_eval = false);
virtual void insertPointCloud(const Pointcloud& scan, const octomap::point3d& sensor_origin,
double maxrange=-1., bool lazy_eval = false);

/**
* Manipulate log_odds value of a voxel directly. This only works if key is at the lowest
* octree level
*
* @param key OcTreeKey of the NODE that is to be updated
* @param log_odds_update value to be added (+) to log_odds value of node
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(const OcTreeKey& key, float log_odds_update, bool lazy_eval = false);
* Integrate a 3d scan (transform scan before tree update), parallelized with OpenMP.
* Special care is taken that each voxel
* in the map is updated only once, and occupied nodes have a preference over free ones.
* This avoids holes in the floor from mutual deletion and is more efficient than the plain
* ray insertion in insertPointCloudRays().
*
* @param scan Pointcloud (measurement endpoints) relative to frame origin
* @param sensor_origin origin of sensor relative to frame origin
* @param frame_origin origin of reference frame, determines transform to be applied to cloud and sensor origin
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param pruning whether the tree is (losslessly) pruned after insertion (default: true)
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertPointCloud(const Pointcloud& scan, const point3d& sensor_origin, const pose6d& frame_origin,
double maxrange=-1., bool lazy_eval = false);

/**
* Manipulate log_odds value of voxel directly.
* Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
*
* @param value 3d coordinate of the NODE that is to be updated
* @param log_odds_update value to be added (+) to log_odds value of node
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(const point3d& value, float log_odds_update, bool lazy_eval = false);
* Insert a 3d scan (given as a ScanNode) into the tree, parallelized with OpenMP.
*
* @param scan ScanNode contains Pointcloud data and frame/sensor origin
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param lazy_eval whether the tree is left 'dirty' after the update (default: false).
* This speeds up the insertion by not updating inner nodes, but you need to call updateInnerOccupancy() when done.
*/
virtual void insertPointCloud(const ScanNode& scan, double maxrange=-1., bool lazy_eval = false);

/// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically.
OCTOMAP_DEPRECATED(virtual void insertScan(const Pointcloud& scan, const octomap::point3d& sensor_origin,
double maxrange=-1., bool pruning=true, bool lazy_eval = false))
{
this->insertPointCloud(scan, sensor_origin, maxrange, lazy_eval);
}

/// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically.
OCTOMAP_DEPRECATED(virtual void insertScan(const Pointcloud& scan, const point3d& sensor_origin,
const pose6d& frame_origin, double maxrange=-1., bool pruning = true, bool lazy_eval = false))
{
this->insertPointCloud(scan, sensor_origin, frame_origin, maxrange, lazy_eval);
}

/// @note Deprecated, use insertPointCloud() instead. pruning is now done automatically.
OCTOMAP_DEPRECATED(virtual void insertScan(const ScanNode& scan, double maxrange=-1., bool pruning = true, bool lazy_eval = false)){
this->insertPointCloud(scan, maxrange, lazy_eval);
}

/// @note Deprecated, use insertPointCloudRays instead. pruning is now done automatically.
OCTOMAP_DEPRECATED( virtual void insertScanNaive(const Pointcloud& scan, const point3d& sensor_origin, double maxrange, bool lazy_eval = false)){
this->insertPointCloudRays(scan, sensor_origin, maxrange, lazy_eval);
}

/**
* Manipulate log_odds value of voxel directly.
* Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
* Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
* This function simply inserts all rays of the point clouds as batch operation.
* Discretization effects can lead to the deletion of occupied space, it is
* usually recommended to use insertPointCloud() instead.
*
* @param x
* @param y
* @param z
* @param log_odds_update value to be added (+) to log_odds value of node
* @param scan Pointcloud (measurement endpoints), in global reference frame
* @param sensor_origin measurement origin in global reference frame
* @param maxrange maximum range for how long individual beams are inserted (default -1: complete beam)
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(double x, double y, double z, float log_odds_update, bool lazy_eval = false);
virtual void insertPointCloudRays(const Pointcloud& scan, const point3d& sensor_origin, double maxrange = -1., bool lazy_eval = false);

/**
* Manipulate log_odds value of a voxel directly. This only works if key is at the lowest
* octree level
*
* @param key OcTreeKey of the NODE that is to be updated
* @param log_odds_update value to be added (+) to log_odds value of node
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(const OcTreeKey& key, float log_odds_update, bool lazy_eval = false);

/**
* Manipulate log_odds value of voxel directly.
* Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
*
* @param value 3d coordinate of the NODE that is to be updated
* @param log_odds_update value to be added (+) to log_odds value of node
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(const point3d& value, float log_odds_update, bool lazy_eval = false);

/**
* Manipulate log_odds value of voxel directly.
* Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
*
* @param x
* @param y
* @param z
* @param log_odds_update value to be added (+) to log_odds value of node
* @param lazy_eval whether update of inner nodes is omitted after the update (default: false).
* This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
* @return pointer to the updated NODE
*/
virtual NODE* updateNode(double x, double y, double z, float log_odds_update, bool lazy_eval = false);

/**
* Integrate occupancy measurement.
Expand Down Expand Up @@ -225,8 +243,8 @@ namespace octomap {
/**
* Insert one ray between origin and end into the tree.
* integrateMissOnRay() is called for the ray, the end point is updated as occupied.
* It is usually more efficient to insert complete pointcloudsm with insertScan() or
* insertScanRays().
* It is usually more efficient to insert complete pointcloudsm with insertPointCloud() or
* insertPointCloudRays().
*
* @param origin origin of sensor in global coordinates
* @param end endpoint of measurement in global coordinates
Expand Down Expand Up @@ -294,7 +312,7 @@ namespace octomap {


/**
* Helper for insertScan. Computes all octree nodes affected by the point cloud
* Helper for insertPointCloud(). Computes all octree nodes affected by the point cloud
* integration at once. Here, occupied nodes have a preference over free
* ones.
*
Expand Down
27 changes: 10 additions & 17 deletions octomap/include/octomap/OccupancyOcTreeBase.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -69,19 +69,19 @@ namespace octomap {

}

// performs transformation to data and sensor origin first
template <class NODE>
void OccupancyOcTreeBase<NODE>::insertScan(const ScanNode& scan, double maxrange, bool pruning, bool lazy_eval) {
void OccupancyOcTreeBase<NODE>::insertPointCloud(const ScanNode& scan, double maxrange, bool lazy_eval) {
// performs transformation to data and sensor origin first
Pointcloud& cloud = *(scan.scan);
pose6d frame_origin = scan.pose;
point3d sensor_origin = frame_origin.inv().transform(scan.pose.trans());
insertScan(cloud, sensor_origin, frame_origin, maxrange, pruning, lazy_eval);
insertPointCloud(cloud, sensor_origin, frame_origin, maxrange, lazy_eval);
}


template <class NODE>
void OccupancyOcTreeBase<NODE>::insertScan(const Pointcloud& scan, const octomap::point3d& sensor_origin,
double maxrange, bool pruning, bool lazy_eval) {
void OccupancyOcTreeBase<NODE>::insertPointCloud(const Pointcloud& scan, const octomap::point3d& sensor_origin,
double maxrange, bool lazy_eval) {

KeySet free_cells, occupied_cells;
computeUpdate(scan, sensor_origin, free_cells, occupied_cells, maxrange);
Expand All @@ -95,23 +95,19 @@ namespace octomap {
}
}

// performs transformation to data and sensor origin first
template <class NODE>
void OccupancyOcTreeBase<NODE>::insertScan(const Pointcloud& pc, const point3d& sensor_origin, const pose6d& frame_origin,
double maxrange, bool pruning, bool lazy_eval) {
void OccupancyOcTreeBase<NODE>::insertPointCloud(const Pointcloud& pc, const point3d& sensor_origin, const pose6d& frame_origin,
double maxrange, bool lazy_eval) {
// performs transformation to data and sensor origin first
Pointcloud transformed_scan (pc);
transformed_scan.transform(frame_origin);
point3d transformed_sensor_origin = frame_origin.transform(sensor_origin);
insertScan(transformed_scan, transformed_sensor_origin, maxrange, pruning, lazy_eval);
insertPointCloud(transformed_scan, transformed_sensor_origin, maxrange, lazy_eval);
}

template <class NODE>
void OccupancyOcTreeBase<NODE>::insertScanNaive(const Pointcloud& pc, const point3d& origin, double maxrange, bool pruning, bool lazy_eval) {
this->insertScanRays(pc, origin, maxrange, pruning, lazy_eval);
}

template <class NODE>
void OccupancyOcTreeBase<NODE>::insertScanRays(const Pointcloud& pc, const point3d& origin, double maxrange, bool pruning, bool lazy_eval) {
void OccupancyOcTreeBase<NODE>::insertPointCloudRays(const Pointcloud& pc, const point3d& origin, double maxrange, bool lazy_eval) {
if (pc.size() < 1)
return;

Expand Down Expand Up @@ -140,9 +136,6 @@ namespace octomap {
}

}

if (pruning)
this->prune();
}


Expand Down
4 changes: 3 additions & 1 deletion octomap/src/eval_octree_accuracy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ int main(int argc, char** argv) {
if (currentScan % skip_scan_eval != 0){
if (max_scan_no > 0) cout << "("<<currentScan << "/" << max_scan_no << ") " << flush;
else cout << "("<<currentScan << "/" << numScans << ") " << flush;
tree->insertScan(**scan_it, maxrange, false);
tree->insertPointCloud(**scan_it, maxrange);
} else
cout << "(SKIP) " << flush;

Expand All @@ -118,6 +118,8 @@ int main(int argc, char** argv) {
currentScan++;
}

tree->expand();


cout << "\nEvaluating scans\n===========================\n";
currentScan = 1;
Expand Down
4 changes: 2 additions & 2 deletions octomap/src/graph2tree.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,9 +240,9 @@ int main(int argc, char** argv) {
else cout << "("<<currentScan << "/" << numScans << ") " << flush;

if (simpleUpdate)
tree->insertScanRays((*scan_it)->scan, (*scan_it)->pose.trans(), maxrange, (compression==1));
tree->insertPointCloudRays((*scan_it)->scan, (*scan_it)->pose.trans(), maxrange);
else
tree->insertScan((*scan_it)->scan, (*scan_it)->pose.trans(), maxrange, (compression==1));
tree->insertPointCloud((*scan_it)->scan, (*scan_it)->pose.trans(), maxrange);

if (compression == 2){
tree->toMaxLikelihood();
Expand Down
2 changes: 1 addition & 1 deletion octomap/src/testing/test_changedkeys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ int main(int argc, char** argv) {
}

// insert in global coordinates:
tree.insertScan(cloud, origin, -1, false);
tree.insertPointCloud(cloud, origin, -1);
}

printChanges(tree);
Expand Down
2 changes: 1 addition & 1 deletion octomap/src/testing/test_scans.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main(int argc, char** argv) {
}

// insert in global coordinates:
tree.insertScan(cloud, origin);
tree.insertPointCloud(cloud, origin);

cout << "done." << endl;
cout << "writing to spherical_scan.bt..." << endl;
Expand Down
2 changes: 1 addition & 1 deletion octomap/src/testing/unit_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ int main(int argc, char** argv) {
}

OcTree tree (0.05);
tree.insertScan(*measurement, origin);
tree.insertPointCloud(*measurement, origin);
EXPECT_EQ ((int) tree.size(), 54076);

ScanGraph* graph = new ScanGraph();
Expand Down
Loading

0 comments on commit 45551dd

Please sign in to comment.