octomap 1.5.0
|
00001 // $Id: MapCollection.hxx 402 2012-08-06 13:39:42Z ahornung $ 00002 00011 /* 00012 * Copyright (c) 2009, K. M. Wurm, A. Hornung, University of Freiburg 00013 * All rights reserved. 00014 * 00015 * Redistribution and use in source and binary forms, with or without 00016 * modification, are permitted provided that the following conditions are met: 00017 * 00018 * * Redistributions of source code must retain the above copyright 00019 * notice, this list of conditions and the following disclaimer. 00020 * * Redistributions in binary form must reproduce the above copyright 00021 * notice, this list of conditions and the following disclaimer in the 00022 * documentation and/or other materials provided with the distribution. 00023 * * Neither the name of the University of Freiburg nor the names of its 00024 * contributors may be used to endorse or promote products derived from 00025 * this software without specific prior written permission. 00026 * 00027 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00028 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00029 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00030 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00031 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00032 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00033 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00034 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00035 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00036 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00037 * POSSIBILITY OF SUCH DAMAGE. 00038 */ 00039 00040 #include <stdio.h> 00041 #include <sstream> 00042 #include <fstream> 00043 00044 namespace octomap { 00045 00046 template <class MAPNODE> 00047 MapCollection<MAPNODE>::MapCollection() { 00048 } 00049 00050 template <class MAPNODE> 00051 MapCollection<MAPNODE>::MapCollection(std::string filename) { 00052 this->read(filename); 00053 } 00054 00055 template <class MAPNODE> 00056 MapCollection<MAPNODE>::~MapCollection() { 00057 this->clear(); 00058 } 00059 00060 template <class MAPNODE> 00061 void MapCollection<MAPNODE>::clear() { 00062 // FIXME: memory leak, else we run into double frees in, e.g., the viewer... 00063 00064 // for(typename std::vector<MAPNODE*>::iterator it= nodes.begin(); it != nodes.end(); ++it) 00065 // delete *it; 00066 nodes.clear(); 00067 } 00068 00069 template <class MAPNODE> 00070 bool MapCollection<MAPNODE>::read(std::string filenamefullpath) { 00071 00072 std::string path; 00073 std::string filename; 00074 splitPathAndFilename(filenamefullpath, &path, &filename); 00075 00076 std::ifstream infile; 00077 infile.open(filenamefullpath.c_str(), std::ifstream::in); 00078 if(!infile.is_open()){ 00079 OCTOMAP_ERROR_STR("Could not open "<< filenamefullpath << ". MapCollection not loaded."); 00080 return false; 00081 } 00082 00083 bool ok = true; 00084 while(ok){ 00085 std::string nodeID; 00086 ok = readTagValue("MAPNODEID", infile, &nodeID); 00087 if(!ok){ 00088 //do not throw error, you could be at the end of the file 00089 break; 00090 } 00091 00092 std::string mapNodeFilename; 00093 ok = readTagValue("MAPNODEFILENAME", infile, &mapNodeFilename); 00094 if(!ok){ 00095 OCTOMAP_ERROR_STR("Could not read MAPNODEFILENAME."); 00096 break; 00097 } 00098 00099 std::string poseStr; 00100 ok = readTagValue("MAPNODEPOSE", infile, &poseStr); 00101 std::istringstream poseStream(poseStr); 00102 float x,y,z; 00103 poseStream >> x >> y >> z; 00104 double roll,pitch,yaw; 00105 poseStream >> roll >> pitch >> yaw; 00106 ok = ok && !poseStream.fail(); 00107 if(!ok){ 00108 OCTOMAP_ERROR_STR("Could not read MAPNODEPOSE."); 00109 break; 00110 } 00111 octomap::pose6d origin(x, y, z, roll, pitch, yaw); 00112 00113 MAPNODE* node = new MAPNODE(combinePathAndFilename(path,mapNodeFilename), origin); 00114 node->setId(nodeID); 00115 00116 if(!ok){ 00117 for(unsigned int i=0; i<nodes.size(); i++){ 00118 delete nodes[i]; 00119 } 00120 infile.close(); 00121 return false; 00122 } else { 00123 nodes.push_back(node); 00124 } 00125 } 00126 infile.close(); 00127 return true; 00128 } 00129 00130 template <class MAPNODE> 00131 void MapCollection<MAPNODE>::addNode( MAPNODE* node){ 00132 nodes.push_back(node); 00133 } 00134 00135 template <class MAPNODE> 00136 MAPNODE* MapCollection<MAPNODE>::addNode(const Pointcloud& cloud, point3d sensor_origin) { 00137 // TODO... 00138 return 0; 00139 } 00140 00141 template <class MAPNODE> 00142 bool MapCollection<MAPNODE>::removeNode(const MAPNODE* n) { 00143 // TODO... 00144 return false; 00145 } 00146 00147 template <class MAPNODE> 00148 MAPNODE* MapCollection<MAPNODE>::queryNode(const point3d& p) { 00149 for (const_iterator it = this->begin(); it != this->end(); ++it) { 00150 point3d ptrans = (*it)->getOrigin().inv().transform(p); 00151 typename MAPNODE::TreeType::NodeType* n = (*it)->getMap()->search(ptrans); 00152 if (!n) continue; 00153 if ((*it)->getMap()->isNodeOccupied(n)) return (*it); 00154 } 00155 return 0; 00156 } 00157 00158 template <class MAPNODE> 00159 bool MapCollection<MAPNODE>::isOccupied(const point3d& p) const { 00160 for (const_iterator it = this->begin(); it != this->end(); ++it) { 00161 point3d ptrans = (*it)->getOrigin().inv().transform(p); 00162 typename MAPNODE::TreeType::NodeType* n = (*it)->getMap()->search(ptrans); 00163 if (!n) continue; 00164 if ((*it)->getMap()->isNodeOccupied(n)) return true; 00165 } 00166 return false; 00167 } 00168 00169 template <class MAPNODE> 00170 bool MapCollection<MAPNODE>::isOccupied(float x, float y, float z) const { 00171 point3d q(x,y,z); 00172 return this->isOccupied(q); 00173 } 00174 00175 00176 template <class MAPNODE> 00177 float MapCollection<MAPNODE>::getOccupancy(const point3d& p) { 00178 float max_occ_val = 0; 00179 bool is_unknown = true; 00180 for (const_iterator it = this->begin(); it != this->end(); ++it) { 00181 point3d ptrans = (*it)->getOrigin().inv().transform(p); 00182 typename MAPNODE::TreeType::NodeType* n = (*it)->getMap()->search(ptrans); 00183 if (n) { 00184 float occ = n->getOccupancy(); 00185 if (occ > max_occ_val) max_occ_val = occ; 00186 is_unknown = false; 00187 } 00188 } 00189 if (is_unknown) return 0.5; 00190 return max_occ_val; 00191 } 00192 00193 00194 template <class MAPNODE> 00195 bool MapCollection<MAPNODE>::castRay(const point3d& origin, const point3d& direction, point3d& end, 00196 bool ignoreUnknownCells, double maxRange) const { 00197 bool hit_obstacle = false; 00198 double min_dist = 1e6; 00199 // SPEEDUP: use openMP to do raycasting in parallel 00200 // SPEEDUP: use bounding boxes to determine submaps 00201 for (const_iterator it = this->begin(); it != this->end(); ++it) { 00202 point3d origin_trans = (*it)->getOrigin().inv().transform(origin); 00203 point3d direction_trans = (*it)->getOrigin().inv().rot().rotate(direction); 00204 printf("ray from %.2f,%.2f,%.2f in dir %.2f,%.2f,%.2f in node %s\n", 00205 origin_trans.x(), origin_trans.y(), origin_trans.z(), 00206 direction_trans.x(), direction_trans.y(), direction_trans.z(), 00207 (*it)->getId().c_str()); 00208 point3d temp_endpoint; 00209 if ((*it)->getMap()->castRay(origin_trans, direction_trans, temp_endpoint, ignoreUnknownCells, maxRange)) { 00210 printf("hit obstacle in node %s\n", (*it)->getId().c_str()); 00211 double current_dist = origin_trans.distance(temp_endpoint); 00212 if (current_dist < min_dist) { 00213 min_dist = current_dist; 00214 end = (*it)->getOrigin().transform(temp_endpoint); 00215 } 00216 hit_obstacle = true; 00217 } // end if hit obst 00218 } // end for 00219 return hit_obstacle; 00220 } 00221 00222 00223 template <class MAPNODE> 00224 bool MapCollection<MAPNODE>::writePointcloud(std::string filename) { 00225 Pointcloud pc; 00226 for(typename std::vector<MAPNODE* >::iterator it = nodes.begin(); it != nodes.end(); ++it){ 00227 Pointcloud tmp = (*it)->generatePointcloud(); 00228 pc.push_back(tmp); 00229 } 00230 pc.writeVrml(filename); 00231 return true; 00232 } 00233 00234 00235 template <class MAPNODE> 00236 bool MapCollection<MAPNODE>::write(std::string filename) { 00237 bool ok = true; 00238 00239 std::ofstream outfile(filename.c_str()); 00240 outfile << "#This file was generated by the write-method of MapCollection\n"; 00241 00242 for(typename std::vector<MAPNODE* >::iterator it = nodes.begin(); it != nodes.end(); ++it){ 00243 std::string id = (*it)->getId(); 00244 pose6d origin = (*it)->getOrigin(); 00245 std::string nodemapFilename = "nodemap_"; 00246 nodemapFilename.append(id); 00247 nodemapFilename.append(".bt"); 00248 00249 outfile << "MAPNODEID " << id << "\n"; 00250 outfile << "MAPNODEFILENAME "<< nodemapFilename << "\n"; 00251 outfile << "MAPNODEPOSE " << origin.x() << " " << origin.y() << " " << origin.z() << " " 00252 << origin.roll() << " " << origin.pitch() << " " << origin.yaw() << std::endl; 00253 ok = ok && (*it)->writeMap(nodemapFilename); 00254 } 00255 outfile.close(); 00256 return ok; 00257 } 00258 00259 // TODO 00260 template <class MAPNODE> 00261 void MapCollection<MAPNODE>::insertScan(const Pointcloud& scan, const octomap::point3d& sensor_origin, 00262 double maxrange, bool pruning, bool lazy_eval) { 00263 fprintf(stderr, "ERROR: MapCollection::insertScan is not implemented yet.\n"); 00264 } 00265 00266 template <class MAPNODE> 00267 MAPNODE* MapCollection<MAPNODE>::queryNode(std::string id) { 00268 for (const_iterator it = this->begin(); it != this->end(); ++it) { 00269 if ((*it)->getId() == id) return *(it); 00270 } 00271 return 0; 00272 } 00273 00274 // TODO 00275 template <class MAPNODE> 00276 std::vector<Pointcloud*> MapCollection<MAPNODE>::segment(const Pointcloud& scan) const { 00277 std::vector<Pointcloud*> result; 00278 fprintf(stderr, "ERROR: MapCollection::segment is not implemented yet.\n"); 00279 return result; 00280 } 00281 00282 // TODO 00283 template <class MAPNODE> 00284 MAPNODE* MapCollection<MAPNODE>::associate(const Pointcloud& scan) { 00285 fprintf(stderr, "ERROR: MapCollection::associate is not implemented yet.\n"); 00286 return 0; 00287 } 00288 00289 template <class MAPNODE> 00290 void MapCollection<MAPNODE>::splitPathAndFilename(std::string &filenamefullpath, 00291 std::string* path, std::string *filename) { 00292 #ifdef WIN32 00293 std::string::size_type lastSlash = filenamefullpath.find_last_of('\\'); 00294 #else 00295 std::string::size_type lastSlash = filenamefullpath.find_last_of('/'); 00296 #endif 00297 if (lastSlash != std::string::npos){ 00298 *filename = filenamefullpath.substr(lastSlash + 1); 00299 *path = filenamefullpath.substr(0, lastSlash); 00300 } else { 00301 *filename = filenamefullpath; 00302 *path = ""; 00303 } 00304 } 00305 00306 template <class MAPNODE> 00307 std::string MapCollection<MAPNODE>::combinePathAndFilename(std::string path, std::string filename) { 00308 std::string result = path; 00309 if(path != ""){ 00310 #ifdef WIN32 00311 result.append("\\"); 00312 #else 00313 result.append("/"); 00314 #endif 00315 } 00316 result.append(filename); 00317 return result; 00318 } 00319 00320 template <class MAPNODE> 00321 bool MapCollection<MAPNODE>::readTagValue(std::string tag, std::ifstream& infile, std::string* value) { 00322 std::string line; 00323 while( getline(infile, line) ){ 00324 if(line.length() != 0 && line[0] != '#') 00325 break; 00326 } 00327 *value = ""; 00328 std::string::size_type firstSpace = line.find(' '); 00329 if(firstSpace != std::string::npos && firstSpace != line.size()-1){ 00330 *value = line.substr(firstSpace + 1); 00331 return true; 00332 } 00333 else return false; 00334 } 00335 00336 } // namespace