OctoMap.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <rtabmap/core/OctoMap.h>
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UStl.h>
00031 #include <rtabmap/core/util3d_transforms.h>
00032 #include <rtabmap/core/util3d_filtering.h>
00033 #include <rtabmap/core/util3d_mapping.h>
00034 
00035 namespace rtabmap {
00036 
00037 OctoMap::OctoMap(float voxelSize) :
00038                 octree_(new octomap::ColorOcTree(voxelSize))
00039 {
00040         UASSERT(voxelSize>0.0f);
00041 }
00042 
00043 OctoMap::~OctoMap()
00044 {
00045         this->clear();
00046         delete octree_;
00047 }
00048 
00049 void OctoMap::clear()
00050 {
00051         octree_->clear();
00052         occupiedCells_.clear();
00053         cache_.clear();
00054         addedNodes_.clear();
00055         keyRay_ = octomap::KeyRay();
00056 }
00057 
00058 void OctoMap::addToCache(int nodeId,
00059                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & ground,
00060                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr & obstacles)
00061 {
00062         UDEBUG("nodeId=%d", nodeId);
00063         cache_.insert(std::make_pair(nodeId, std::make_pair(ground, obstacles)));
00064 }
00065 
00066 void OctoMap::update(const std::map<int, Transform> & poses)
00067 {
00068         UDEBUG("Update (poses=%d addedNodes_=%d)", (int)poses.size(), (int)addedNodes_.size());
00069 
00070         // First, check of the graph has changed. If so, re-create the octree by moving all occupied nodes.
00071         bool graphChanged = false;
00072         std::map<int, Transform> transforms;
00073         std::map<int, Transform> updatedAddedNodes;
00074         for(std::map<int, Transform>::iterator iter=addedNodes_.begin(); iter!=addedNodes_.end(); ++iter)
00075         {
00076                 std::map<int, Transform>::const_iterator jter = poses.find(iter->first);
00077                 if(jter != poses.end())
00078                 {
00079                         UASSERT(!iter->second.isNull() && !jter->second.isNull());
00080                         Transform t = Transform::getIdentity();
00081                         if(iter->second.getDistanceSquared(jter->second) > 0.0001)
00082                         {
00083                                 t = jter->second * iter->second.inverse();
00084                                 graphChanged = true;
00085                         }
00086                         transforms.insert(std::make_pair(jter->first, t));
00087                         updatedAddedNodes.insert(std::make_pair(jter->first, jter->second));
00088                 }
00089                 else
00090                 {
00091                         UWARN("Updated pose for node %d is not found, some points may not be copied.", jter->first);
00092                 }
00093         }
00094         if(graphChanged)
00095         {
00096                 UINFO("Graph changed!");
00097                 octomap::ColorOcTree * newOcTree = new octomap::ColorOcTree(octree_->getResolution());
00098                 std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo > newOccupiedCells;
00099                 int copied=0;
00100                 for(std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo >::iterator iter = occupiedCells_.begin();
00101                                 iter!=occupiedCells_.end();
00102                                 ++iter)
00103                 {
00104                         std::map<int, Transform>::iterator jter = transforms.find(iter->second.nodeRefId_);
00105                         if(jter != transforms.end())
00106                         {
00107                                 octomap::point3d pt = octree_->keyToCoord(iter->second.key_);
00108                                 std::map<int, Transform>::iterator pter = addedNodes_.find(iter->second.nodeRefId_);
00109                                 UASSERT(pter != addedNodes_.end());
00110 
00111                                 cv::Point3f cvPt(pt.x(), pt.y(), pt.z());
00112                                 cvPt = util3d::transformPoint(cvPt, jter->second);
00113 
00114                                 octomap::OcTreeKey key;
00115                                 if(newOcTree->coordToKeyChecked(cvPt.x, cvPt.y, cvPt.z, key))
00116                                 {
00117                                         octomap::ColorOcTreeNode * n = newOcTree->updateNode(key, iter->second.isObstacle_);
00118                                         if(n)
00119                                         {
00120                                                 ++copied;
00121                                                 uInsert(newOccupiedCells, std::make_pair(n, OcTreeNodeInfo(jter->first, key, iter->second.isObstacle_)));
00122                                                 newOcTree->setNodeColor(key, iter->first->getColor().r, iter->first->getColor().g, iter->first->getColor().b);
00123                                         }
00124                                         else
00125                                         {
00126                                                 UERROR("Could not update node at (%f,%f,%f)", cvPt.x, cvPt.y, cvPt.z);
00127                                         }
00128                                 }
00129                                 else
00130                                 {
00131                                         UERROR("Could not find key for (%f,%f,%f)", cvPt.x, cvPt.y, cvPt.z);
00132                                 }
00133                         }
00134                         else if(jter == transforms.end() && iter->second.nodeRefId_ > 0)
00135                         {
00136                                 UWARN("Could not find a transform for point linked to node %d (transforms=%d)", iter->second.nodeRefId_, (int)transforms.size());
00137                         }
00138                 }
00139                 UDEBUG("%d/%d", copied, (int)occupiedCells_.size());
00140                 delete octree_;
00141                 octree_ = newOcTree;
00142                 occupiedCells_ = newOccupiedCells;
00143 
00144                 //update added poses
00145                 addedNodes_ = updatedAddedNodes;
00146         }
00147 
00148         // Original version from A. Hornung:
00149         // https://github.com/OctoMap/octomap_mapping/blob/jade-devel/octomap_server/src/OctomapServer.cpp#L356
00150         //
00151         int lastId = addedNodes_.size()?addedNodes_.rbegin()->first:0;
00152         UDEBUG("Last id = %d", lastId);
00153         if(lastId >= 0)
00154         {
00155                 std::list<std::pair<int, Transform> > orderedPoses;
00156                 for(std::map<int, Transform>::const_iterator iter=poses.upper_bound(lastId); iter!=poses.end(); ++iter)
00157                 {
00158                         orderedPoses.push_back(*iter);
00159                 }
00160                 // insert negative after
00161                 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
00162                 {
00163                         if(iter->first < 0)
00164                         {
00165                                 orderedPoses.push_back(*iter);
00166                         }
00167                         else
00168                         {
00169                                 break;
00170                         }
00171                 }
00172 
00173                 UDEBUG("orderedPoses = %d", (int)orderedPoses.size());
00174                 for(std::list<std::pair<int, Transform> >::const_iterator iter=orderedPoses.begin(); iter!=orderedPoses.end(); ++iter)
00175                 {
00176                         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::PointCloud<pcl::PointXYZRGB>::Ptr> >::iterator cloudIter;
00177                         cloudIter = cache_.find(iter->first);
00178                         if(cloudIter != cache_.end())
00179                         {
00180                                 UDEBUG("Adding %d to octomap (resolution=%f)", iter->first, octree_->getResolution());
00181 
00182                                 octomap::point3d sensorOrigin(iter->second.x(), iter->second.y(), iter->second.z());
00183                                 octomap::OcTreeKey tmpKey;
00184                                 if (!octree_->coordToKeyChecked(sensorOrigin, tmpKey)
00185                                                 || !octree_->coordToKeyChecked(sensorOrigin, tmpKey))
00186                                 {
00187                                         UERROR("Could not generate Key for origin ", sensorOrigin.x(), sensorOrigin.y(), sensorOrigin.z());
00188                                 }
00189 
00190                                 // instead of direct scan insertion, compute update to filter ground:
00191                                 octomap::KeySet free_cells, occupied_cells, ground_cells;
00192                                 // insert ground points only as free:
00193                                 UDEBUG("%d: compute free cells (from %d ground points)", iter->first, (int)cloudIter->second.first->size());
00194                                 for (unsigned int i=0; i<cloudIter->second.first->size(); ++i)
00195                                 {
00196                                         pcl::PointXYZRGB pt = util3d::transformPoint(cloudIter->second.first->at(i), iter->second);
00197 
00198                                         octomap::point3d point(pt.x, pt.y, pt.z);
00199 
00200                                         // only clear space (ground points)
00201                                         if (octree_->computeRayKeys(sensorOrigin, point, keyRay_))
00202                                         {
00203                                                 free_cells.insert(keyRay_.begin(), keyRay_.end());
00204                                         }
00205                                         // occupied endpoint
00206                                         octomap::OcTreeKey key;
00207                                         if (octree_->coordToKeyChecked(point, key))
00208                                         {
00209                                                 ground_cells.insert(key);
00210 
00211                                                 octomap::ColorOcTreeNode * n = octree_->updateNode(key, false);
00212                                                 if(n)
00213                                                 {
00214                                                         octree_->averageNodeColor(key, pt.r, pt.g, pt.b);
00215                                                         if(iter->first > 0)
00216                                                         {
00217                                                                 uInsert(occupiedCells_, std::make_pair(n, OcTreeNodeInfo(iter->first, key, false)));
00218                                                         }
00219                                                         else
00220                                                         {
00221                                                                 occupiedCells_.insert(std::make_pair(n, OcTreeNodeInfo(iter->first, key, false)));
00222                                                         }
00223                                                 }
00224                                         }
00225                                 }
00226                                 UDEBUG("%d: free cells = %d", iter->first, (int)free_cells.size());
00227 
00228                                 // all other points: free on ray, occupied on endpoint:
00229                                 UDEBUG("%d: compute occupied cells (from %d obstacle points)", iter->first, (int) cloudIter->second.second->size());
00230                                 for (unsigned int i=0; i<cloudIter->second.second->size(); ++i)
00231                                 {
00232                                         pcl::PointXYZRGB pt = util3d::transformPoint(cloudIter->second.second->at(i), iter->second);
00233 
00234                                         octomap::point3d point(pt.x, pt.y, pt.z);
00235 
00236                                         // free cells
00237                                         if (octree_->computeRayKeys(sensorOrigin, point, keyRay_))
00238                                         {
00239                                                 free_cells.insert(keyRay_.begin(), keyRay_.end());
00240                                         }
00241                                         // occupied endpoint
00242                                         octomap::OcTreeKey key;
00243                                         if (octree_->coordToKeyChecked(point, key))
00244                                         {
00245                                                 occupied_cells.insert(key);
00246 
00247                                                 octomap::ColorOcTreeNode * n = octree_->updateNode(key, true);
00248                                                 if(n)
00249                                                 {
00250                                                         octree_->averageNodeColor(key, pt.r, pt.g, pt.b);
00251                                                         if(iter->first > 0)
00252                                                         {
00253                                                                 uInsert(occupiedCells_, std::make_pair(n, OcTreeNodeInfo(iter->first, key, true)));
00254                                                         }
00255                                                         else
00256                                                         {
00257                                                                 occupiedCells_.insert(std::make_pair(n, OcTreeNodeInfo(iter->first, key, true)));
00258                                                         }
00259                                                 }
00260                                         }
00261                                 }
00262                                 UDEBUG("%d: occupied cells=%d free cells=%d", iter->first, (int)occupied_cells.size(), (int)free_cells.size());
00263 
00264 
00265                                 // mark free cells only if not seen occupied in this cloud
00266                                 for(octomap::KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it)
00267                                 {
00268                                         if (occupied_cells.find(*it) == occupied_cells.end() &&
00269                                                 ground_cells.find(*it) == ground_cells.end())
00270                                         {
00271                                                 octomap::ColorOcTreeNode * n = octree_->updateNode(*it, false);
00272                                                 if(n)
00273                                                 {
00274                                                         std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo>::iterator gter;
00275                                                         gter = occupiedCells_.find(n);
00276                                                         if(gter != occupiedCells_.end() && gter->second.isObstacle_)
00277                                                         {
00278                                                                 occupiedCells_.erase(gter);
00279                                                         }
00280                                                 }
00281                                         }
00282                                 }
00283 
00284                                 // compress map
00285                                 //octree_->prune();
00286 
00287                                 // ignore negative ids as they are temporary clouds
00288                                 if(iter->first > 0)
00289                                 {
00290                                         addedNodes_.insert(*iter);
00291                                 }
00292                                 UDEBUG("%d: end", iter->first);
00293                         }
00294                         else
00295                         {
00296                                 UDEBUG("Did not find %d in cache", iter->first);
00297                         }
00298                 }
00299         }
00300         cache_.clear();
00301 }
00302 
00303 void HSVtoRGB( float *r, float *g, float *b, float h, float s, float v )
00304 {
00305         int i;
00306         float f, p, q, t;
00307         if( s == 0 ) {
00308                 // achromatic (grey)
00309                 *r = *g = *b = v;
00310                 return;
00311         }
00312         h /= 60;                        // sector 0 to 5
00313         i = floor( h );
00314         f = h - i;                      // factorial part of h
00315         p = v * ( 1 - s );
00316         q = v * ( 1 - s * f );
00317         t = v * ( 1 - s * ( 1 - f ) );
00318         switch( i ) {
00319                 case 0:
00320                         *r = v;
00321                         *g = t;
00322                         *b = p;
00323                         break;
00324                 case 1:
00325                         *r = q;
00326                         *g = v;
00327                         *b = p;
00328                         break;
00329                 case 2:
00330                         *r = p;
00331                         *g = v;
00332                         *b = t;
00333                         break;
00334                 case 3:
00335                         *r = p;
00336                         *g = q;
00337                         *b = v;
00338                         break;
00339                 case 4:
00340                         *r = t;
00341                         *g = p;
00342                         *b = v;
00343                         break;
00344                 default:                // case 5:
00345                         *r = v;
00346                         *g = p;
00347                         *b = q;
00348                         break;
00349         }
00350 }
00351 
00352 pcl::PointCloud<pcl::PointXYZRGB>::Ptr OctoMap::createCloud(
00353                 unsigned int treeDepth,
00354                 std::vector<int> * obstacleIndices,
00355                 std::vector<int> * emptyIndices) const
00356 {
00357         UASSERT(treeDepth <= octree_->getTreeDepth());
00358         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00359         UDEBUG("depth=%d (maxDepth=%d) octree = %d",
00360                         (int)treeDepth, (int)octree_->getTreeDepth(), (int)octree_->size());
00361         cloud->resize(octree_->size());
00362         if(obstacleIndices)
00363         {
00364                 obstacleIndices->resize(octree_->size());
00365         }
00366         if(emptyIndices)
00367         {
00368                 emptyIndices->resize(octree_->size());
00369         }
00370 
00371         if(treeDepth == 0)
00372         {
00373                 treeDepth = octree_->getTreeDepth();
00374         }
00375 
00376         double minX, minY, minZ, maxX, maxY, maxZ;
00377         octree_->getMetricMin(minX, minY, minZ);
00378         octree_->getMetricMax(maxX, maxY, maxZ);
00379 
00380         int oi=0;
00381         int si=0;
00382         int gi=0;
00383         for (octomap::ColorOcTree::iterator it = octree_->begin(treeDepth); it != octree_->end(); ++it)
00384         {
00385                 if(octree_->isNodeOccupied(*it))
00386                 {
00387                         octomap::point3d pt = octree_->keyToCoord(it.getKey());
00388                         if(octree_->getTreeDepth() == it.getDepth())
00389                         {
00390                                 (*cloud)[oi]  = pcl::PointXYZRGB(it->getColor().r, it->getColor().g, it->getColor().b);
00391                         }
00392                         else
00393                         {
00394                                 // Gradiant color on z axis
00395                                 float H = (maxZ - pt.z())*299.0f/(maxZ-minZ);
00396                                 float r,g,b;
00397                                 HSVtoRGB(&r, &g, &b, H, 1, 1);
00398                                 (*cloud)[oi].r = r*255.0f;
00399                                 (*cloud)[oi].g = g*255.0f;
00400                                 (*cloud)[oi].b = b*255.0f;
00401                         }
00402                         (*cloud)[oi].x = pt.x();
00403                         (*cloud)[oi].y = pt.y();
00404                         (*cloud)[oi].z = pt.z();
00405                         if(obstacleIndices)
00406                         {
00407                                 obstacleIndices->at(si++) = oi;
00408                         }
00409                         ++oi;
00410                 }
00411                 else
00412                 {
00413                         octomap::point3d pt = octree_->keyToCoord(it.getKey());
00414                         (*cloud)[oi]  = pcl::PointXYZRGB(it->getColor().r, it->getColor().g, it->getColor().b);
00415                         (*cloud)[oi].x = pt.x();
00416                         (*cloud)[oi].y = pt.y();
00417                         (*cloud)[oi].z = pt.z();
00418                         if(emptyIndices)
00419                         {
00420                                 emptyIndices->at(gi++) = oi;
00421                         }
00422                         ++oi;
00423                 }
00424         }
00425 
00426         cloud->resize(oi);
00427         if(obstacleIndices)
00428         {
00429                 obstacleIndices->resize(si);
00430         }
00431         if(emptyIndices)
00432         {
00433                 emptyIndices->resize(gi);
00434         }
00435 
00436         UDEBUG("");
00437         return cloud;
00438 }
00439 
00440 cv::Mat OctoMap::createProjectionMap(float & xMin, float & yMin, float & gridCellSize, float minGridSize)
00441 {
00442         gridCellSize = octree_->getResolution();
00443 
00444         pcl::PointCloud<pcl::PointXYZ>::Ptr ground(new pcl::PointCloud<pcl::PointXYZ>);
00445         pcl::PointCloud<pcl::PointXYZ>::Ptr obstacles(new pcl::PointCloud<pcl::PointXYZ>);
00446 
00447         ground->resize(occupiedCells_.size());
00448         obstacles->resize(occupiedCells_.size());
00449         int gi=0;
00450         int oi=0;
00451         for(std::map<octomap::ColorOcTreeNode*, OcTreeNodeInfo>::const_iterator iter = occupiedCells_.begin();
00452                 iter!=occupiedCells_.end();
00453                 ++iter)
00454         {
00455                 if(iter->second.isObstacle_ && octree_->isNodeOccupied(iter->first))
00456                 {
00457                         octomap::point3d pt = octree_->keyToCoord(iter->second.key_);
00458                         (*obstacles)[oi++]  = pcl::PointXYZ(pt.x(), pt.y(), 0); // projected on ground
00459                 }
00460                 else if(!iter->second.isObstacle_)
00461                 {
00462                         octomap::point3d pt = octree_->keyToCoord(iter->second.key_);
00463                         (*ground)[gi++]  = pcl::PointXYZ(pt.x(), pt.y(), 0); // projected on ground
00464                 }
00465         }
00466         obstacles->resize(oi);
00467         ground->resize(gi);
00468 
00469         if(obstacles->size())
00470         {
00471                 obstacles = util3d::voxelize(obstacles, gridCellSize);
00472         }
00473         if(ground->size())
00474         {
00475                 ground = util3d::voxelize(ground, gridCellSize);
00476         }
00477 
00478         cv::Mat obstaclesMat = cv::Mat((int)obstacles->size(), 1, CV_32FC2);
00479         for(unsigned int i=0;i<obstacles->size(); ++i)
00480         {
00481                 obstaclesMat.at<cv::Vec2f>(i)[0] = obstacles->at(i).x;
00482                 obstaclesMat.at<cv::Vec2f>(i)[1] = obstacles->at(i).y;
00483         }
00484 
00485         cv::Mat groundMat = cv::Mat((int)ground->size(), 1, CV_32FC2);
00486         for(unsigned int i=0;i<ground->size(); ++i)
00487         {
00488                 groundMat.at<cv::Vec2f>(i)[0] = ground->at(i).x;
00489                 groundMat.at<cv::Vec2f>(i)[1] = ground->at(i).y;
00490         }
00491 
00492         std::map<int, Transform> poses;
00493         poses.insert(std::make_pair(1, Transform::getIdentity()));
00494         std::map<int, std::pair<cv::Mat, cv::Mat> > maps;
00495         maps.insert(std::make_pair(1, std::make_pair(groundMat, obstaclesMat)));
00496 
00497         return util3d::create2DMapFromOccupancyLocalMaps(
00498                         poses,
00499                         maps,
00500                         gridCellSize,
00501                         xMin, yMin,
00502                         minGridSize,
00503                         false);
00504 }
00505 
00506 bool OctoMap::writeBinary(const std::string & path)
00507 {
00508         return octree_->writeBinary(path);
00509 }
00510 
00511 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17