commit f19a23d33880fb60b51277ee5e02fef3ade7fbd1
Author: Armin Hornung <hornunga@informatik.uni-freiburg.de>
Date:   Fri Apr 5 15:18:12 2013 +0200

    Doxygen updates / additions

diff --git a/octomap/doxygen.h b/octomap/doxygen.h
index e5b515d..cd7ab4c 100644
--- a/octomap/doxygen.h
+++ b/octomap/doxygen.h
@@ -84,7 +84,7 @@ https://github.com/OctoMap/octomap.</p>
   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::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 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>
 
   \image html uml_overview.png
diff --git a/octomap/include/octomap/OcTreeBaseImpl.h b/octomap/include/octomap/OcTreeBaseImpl.h
index dc2f248..17693c0 100644
--- a/octomap/include/octomap/OcTreeBaseImpl.h
+++ b/octomap/include/octomap/OcTreeBaseImpl.h
@@ -82,8 +82,11 @@ namespace octomap {
     OcTreeBaseImpl(double resolution);
     virtual ~OcTreeBaseImpl();
 
+    /// Deep copy constructor
     OcTreeBaseImpl(const OcTreeBaseImpl<NODE,INTERFACE>& rhs);
 
+    /// Comparison between two octrees, all meta data, all
+    /// nodes, and the structure must be identical
     bool operator== (const OcTreeBaseImpl<NODE,INTERFACE>& rhs) const;
 
     std::string getTreeType() const {return "OcTreeBaseImpl";}
@@ -105,19 +108,22 @@ namespace octomap {
     inline NODE* getRoot() const { return root; }
 
     /** 
-     *  Search node at specified depth given a 3d point (depth=0: search full tree depth)
+     *  Search node at specified depth given a 3d point (depth=0: search full tree depth).
+     *  You need to check if the returned node is NULL, since it can be in unknown space.
      *  @return pointer to node if found, NULL otherwise
      */
     NODE* search(double x, double y, double z, unsigned int depth = 0) const;
 
     /**
      *  Search node at specified depth given a 3d point (depth=0: search full tree depth)
+     *  You need to check if the returned node is NULL, since it can be in unknown space.
      *  @return pointer to node if found, NULL otherwise
      */
     NODE* search(const point3d& value, unsigned int depth = 0) const;
 
     /**
      *  Search a node at specified depth given an addressing key (depth=0: search full tree depth)
+     *  You need to check if the returned node is NULL, since it can be in unknown space.
      *  @return pointer to node if found, NULL otherwise
      */
     NODE* search(const OcTreeKey& key, unsigned int depth = 0) const;
@@ -146,11 +152,12 @@ namespace octomap {
     /// Deletes the complete tree structure
     void clear();
 
-    OcTreeBaseImpl deepCopy() const;
-
-
-    /// Lossless compression of OcTree: merge children to parent when there are
-    /// eight children with identical values
+    /**
+     * Lossless compression of the octree: A node will replace all of its eight
+     * children if they have identical values. You usually don't have to call
+     * prune() after a regular occupancy update, updateNode() incrementally
+     * prunes all affected nodes.
+     */
     virtual void prune();
 
     /// Expands all pruned nodes (reverse of prune())
@@ -165,7 +172,7 @@ namespace octomap {
     /// \return Memory usage of the complete octree in bytes (may vary between architectures)
     virtual size_t memoryUsage() const;
 
-    /// \return Memory usage of the a single octree node
+    /// \return Memory usage of a single octree node
     virtual inline size_t memoryUsageNode() const {return sizeof(NODE); };
 
     /// \return Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)
diff --git a/octomap/include/octomap/OccupancyOcTreeBase.h b/octomap/include/octomap/OccupancyOcTreeBase.h
index 238daff..2abdd40 100644
--- a/octomap/include/octomap/OccupancyOcTreeBase.h
+++ b/octomap/include/octomap/OccupancyOcTreeBase.h
@@ -82,6 +82,8 @@ namespace octomap {
     * This avoids holes in the floor from mutual deletion and is more efficient than the plain
     * ray insertion in insertPointCloudRays().
     *
+    * @note replaces insertScan()
+    *
     * @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)
@@ -98,6 +100,8 @@ namespace octomap {
     * This avoids holes in the floor from mutual deletion and is more efficient than the plain
     * ray insertion in insertPointCloudRays().
     *
+    * @note replaces insertScan()
+    *
     * @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
@@ -111,6 +115,8 @@ namespace octomap {
     /**
     * Insert a 3d scan (given as a ScanNode) into the tree, parallelized with OpenMP.
     *
+    * @note replaces insertScan
+    *
     * @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).
