$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 25/1/2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include <srs_env_model/but_server/octonode.h> 00029 00030 using namespace octomap; 00031 00035 srs_env_model::EModelTreeNode::EModelTreeNode() : 00036 octomap::OcTreeNodeStamped(), m_r(0), m_g(0), m_b(0), m_a(0) { 00037 00038 } 00039 00043 srs_env_model::EModelTreeNode::~EModelTreeNode() { 00044 00045 } 00046 00050 bool srs_env_model::EModelTreeNode::createChild(unsigned int i) { 00051 if (itsChildren == NULL) { 00052 allocChildren(); 00053 } 00054 itsChildren[i] = new EModelTreeNode(); 00055 return true; 00056 } 00057 00058 void srs_env_model::EModelTreeNode::updateColorChildren() { 00059 setAverageChildColor(); 00060 } 00061 00062 bool srs_env_model::EModelTreeNode::pruneNode() { 00063 // checks for equal occupancy only, color ignored 00064 if (!this->collapsible()) 00065 return false; 00066 // set occupancy value 00067 setLogOdds(getChild(0)->getLogOdds()); 00068 // set color to average color 00069 if (isColorSet()) { 00070 setAverageChildColor(); 00071 } 00072 // delete children 00073 for (unsigned int i = 0; i < 8; i++) { 00074 delete itsChildren[i]; 00075 } 00076 delete[] itsChildren; 00077 itsChildren = NULL; 00078 return true; 00079 } 00080 00081 void srs_env_model::EModelTreeNode::expandNode() { 00082 assert(!hasChildren()); 00083 00084 // expand node, set children color same as node color 00085 for (unsigned int k = 0; k < 8; k++) { 00086 createChild(k); 00087 itsChildren[k]->setValue(value); 00088 getChild(k)->setColor(r(), g(), b(), a()); 00089 } 00090 } 00091 00092 void srs_env_model::EModelTreeNode::setAverageChildColor() { 00093 int mr(0), mg(0), mb(0), ma(0); 00094 int c(0); 00095 for (int i = 0; i < 8; i++) { 00096 if (childExists(i) && getChild(i)->isColorSet()) { 00097 mr += getChild(i)->r(); 00098 mg += getChild(i)->g(); 00099 mb += getChild(i)->b(); 00100 ma += getChild(i)->a(); 00101 ++c; 00102 } 00103 } 00104 if (c) { 00105 mr /= c; 00106 mg /= c; 00107 mb /= c; 00108 ma /= c; 00109 00110 m_r = mr; 00111 m_g = mg; 00112 m_b = mb; 00113 m_a = ma; 00114 setColor((unsigned char) mr, (unsigned char) mg, (unsigned char) mb, 00115 (unsigned char) ma); 00116 } else { // no child had a color other than white 00117 setColor((unsigned char) 255, (unsigned char) 255, (unsigned char) 255, 00118 (unsigned char) 255); 00119 } 00120 } 00121 00129 std::istream& srs_env_model::EModelTreeNode::readValue(std::istream &s) 00130 { 00131 // Read common data 00132 octomap::OcTreeNodeStamped::readValue( s ); 00133 00134 char children_char; 00135 00136 // read data: 00137 s.read((char*) &m_r, sizeof(m_r)); 00138 s.read((char*) &m_g, sizeof(m_g)); 00139 s.read((char*) &m_b, sizeof(m_b)); 00140 s.read((char*) &m_a, sizeof(m_a)); 00141 00142 s.read((char*)&children_char, sizeof(char)); 00143 std::bitset<8> children ((unsigned long long) children_char); 00144 00145 //std::cerr << "Read color: " << int(m_r) << ", " << int(m_g) << ", " << int(m_b) << ", " << int(m_a) << std::endl; 00146 00147 // std::cout << "read: " << value << " " 00148 // << children.to_string<char,std::char_traits<char>,std::allocator<char> >() 00149 // << std::endl; 00150 00151 for (unsigned int i=0; i<8; i++) { 00152 if (children[i] == 1){ 00153 createChild(i); 00154 getChild(i)->readValue(s); 00155 } 00156 } 00157 return s; 00158 } 00159 00168 std::ostream& srs_env_model::EModelTreeNode::writeValue(std::ostream &s) const 00169 { 00170 // 1 bit for each children; 0: empty, 1: allocated 00171 std::bitset<8> children; 00172 00173 for (unsigned int i=0; i<8; i++) { 00174 if (childExists(i)) 00175 children[i] = 1; 00176 else 00177 children[i] = 0; 00178 } 00179 00180 octomap::OcTreeNodeStamped::writeValue(s); 00181 00182 char children_char = (char) children.to_ulong(); 00183 00184 // Write node data 00185 s.write((const char*) &m_r, sizeof(m_r)); 00186 s.write((const char*) &m_g, sizeof(m_g)); 00187 s.write((const char*) &m_b, sizeof(m_b)); 00188 s.write((const char*) &m_a, sizeof(m_a)); 00189 00190 // std::cerr << "Writing node" << std::endl; 00191 00192 s.write((char*)&children_char, sizeof(char)); 00193 00194 // std::cout << "wrote: " << value << " " 00195 // << children.to_string<char,std::char_traits<char>,std::allocator<char> >() 00196 // << std::endl; 00197 00198 // write children's children 00199 for (unsigned int i=0; i<8; i++) { 00200 if (children[i] == 1) { 00201 this->getChild(i)->writeValue(s); 00202 } 00203 } 00204 return s; 00205 } 00206 00207 00212 srs_env_model::EMOcTree::EMOcTree(double _resolution) : 00213 octomap::OccupancyOcTreeBase<srs_env_model::EModelTreeNode> (_resolution) { 00214 itsRoot = new EModelTreeNode(); 00215 tree_size++; 00216 } 00217 00223 srs_env_model::EMOcTree::EMOcTree(std::string _filename) : 00224 OccupancyOcTreeBase<srs_env_model::EModelTreeNode> (0.1) { // resolution will be set according to tree file 00225 itsRoot = new EModelTreeNode(); 00226 tree_size++; 00227 00228 readBinary(_filename); 00229 } 00230 00231 srs_env_model::EModelTreeNode* srs_env_model::EMOcTree::setNodeColor(const octomap::OcTreeKey& key, 00232 const unsigned char& r, const unsigned char& g, const unsigned char& b, 00233 const unsigned char& a) { 00234 EModelTreeNode* n = search(key); 00235 if (n != 0) { 00236 n->setColor(r, g, b, a); 00237 } 00238 return n; 00239 } 00240 00241 srs_env_model::EModelTreeNode* srs_env_model::EMOcTree::averageNodeColor( 00242 const octomap::OcTreeKey& key, const unsigned char& r, const unsigned char& g, 00243 const unsigned char& b, const unsigned char& a) { 00244 EModelTreeNode* n = search(key); 00245 if (n != 0) { 00246 if (n->isColorSet()) { 00247 // get previous color 00248 unsigned char prev_color_r = n->r(); 00249 unsigned char prev_color_g = n->g(); 00250 unsigned char prev_color_b = n->b(); 00251 unsigned char prev_color_a = n->a(); 00252 00253 // average it with new color and set 00254 n->setColor((prev_color_r + r) / 2, (prev_color_g + g) / 2, 00255 (prev_color_b + b) / 2, (prev_color_a + a) / 2); 00256 } else { 00257 // nothing to average with 00258 n->setColor(r, g, b, a); 00259 } 00260 } 00261 return n; 00262 } 00263 00264 srs_env_model::EModelTreeNode* srs_env_model::EMOcTree::integrateNodeColor( 00265 const octomap::OcTreeKey& key, const unsigned char& r, const unsigned char& g, 00266 const unsigned char& b, const unsigned char& a) { 00267 EModelTreeNode* n = search(key); 00268 if (n != 0) { 00269 if (n->isColorSet()) { 00270 // get previous color 00271 unsigned char prev_color_r = n->r(); 00272 unsigned char prev_color_g = n->g(); 00273 unsigned char prev_color_b = n->b(); 00274 unsigned char prev_color_a = n->a(); 00275 00276 // average it with new color taking account of node probability 00277 double node_prob = n->getOccupancy(); 00278 unsigned char new_r = (unsigned char) ((double) prev_color_r 00279 * node_prob + (double) r * (0.99 - node_prob)); 00280 unsigned char new_g = (unsigned char) ((double) prev_color_g 00281 * node_prob + (double) g * (0.99 - node_prob)); 00282 unsigned char new_b = (unsigned char) ((double) prev_color_b 00283 * node_prob + (double) b * (0.99 - node_prob)); 00284 unsigned char new_a = (unsigned char) ((double) prev_color_a 00285 * node_prob + (double) a * (0.99 - node_prob)); 00286 n->setColor(new_r, new_g, new_b, new_a); 00287 } else { 00288 n->setColor(r, g, b, a); 00289 } 00290 } 00291 return n; 00292 } 00293 00294 void srs_env_model::EMOcTree::updateInnerOccupancy() { 00295 this->updateInnerOccupancyRecurs(this->itsRoot, 0); 00296 } 00297 00298 void srs_env_model::EMOcTree::updateInnerOccupancyRecurs(EModelTreeNode* node, 00299 unsigned int depth) { 00300 // only recurse and update for inner nodes: 00301 if (node->hasChildren()) { 00302 // return early for last level: 00303 if (depth < this->tree_depth) { 00304 for (unsigned int i = 0; i < 8; i++) { 00305 if (node->childExists(i)) { 00306 updateInnerOccupancyRecurs(node->getChild(i), depth + 1); 00307 } 00308 } 00309 } 00310 node->updateOccupancyChildren(); 00311 node->updateColorChildren(); 00312 } 00313 } 00314 00315 unsigned int srs_env_model::EMOcTree::getLastUpdateTime() { 00316 // this value is updated whenever inner nodes are 00317 // updated using updateOccupancyChildren() 00318 return itsRoot->getTimestamp(); 00319 } 00320 00321 void srs_env_model::EMOcTree::degradeOutdatedNodes(unsigned int time_thres) { 00322 unsigned int query_time = (unsigned int) time(NULL); 00323 00324 for (leaf_iterator it = this->begin_leafs(), end = this->end_leafs(); it 00325 != end; ++it) { 00326 if (this->isNodeOccupied(*it) && ((query_time - it->getTimestamp()) 00327 > time_thres)) { 00328 integrateMissNoTime(&*it); 00329 } 00330 } 00331 } 00332 00333 void srs_env_model::EMOcTree::updateNodeLogOdds(EModelTreeNode* node, 00334 const float& update) const { 00335 OccupancyOcTreeBase<EModelTreeNode>::updateNodeLogOdds(node, update); 00336 node->updateTimestamp(); 00337 } 00338 00339 void srs_env_model::EMOcTree::integrateMissNoTime(EModelTreeNode* node) const { 00340 OccupancyOcTreeBase<EModelTreeNode>::updateNodeLogOdds(node, probMissLog); 00341 } 00342 00343 void srs_env_model::EMOcTree::insertColoredScan(const typePointCloud& coloredScan, 00344 const octomap::point3d& sensor_origin, double maxrange, bool pruning, 00345 bool lazy_eval) { 00346 00347 // convert colored scan to octomap pcl 00348 octomap::Pointcloud scan; 00349 octomap::pointcloudPCLToOctomap(coloredScan, scan); 00350 00351 // insert octomap pcl to count new probabilities 00352 octomap::KeySet free_cells, occupied_cells; 00353 computeUpdate(scan, sensor_origin, free_cells, occupied_cells, maxrange); 00354 00355 // insert data into tree ----------------------- 00356 for (octomap::KeySet::iterator it = free_cells.begin(); it != free_cells.end(); ++it) { 00357 updateNode(*it, false, lazy_eval); 00358 } 00359 for (octomap::KeySet::iterator it = occupied_cells.begin(); it 00360 != occupied_cells.end(); ++it) { 00361 updateNode(*it, true, lazy_eval); 00362 } 00363 00364 // TODO: does pruning make sense if we used "lazy_eval"? 00365 if (pruning) 00366 this->prune(); 00367 00368 // update node colors 00369 BOOST_FOREACH (const pcl::PointXYZRGB& pt, coloredScan.points) 00370 { 00371 // averageNodeColor or integrateNodeColor can be used to count final color 00372 averageNodeColor(pt.x, pt.y, pt.z, (unsigned char)pt.r, (unsigned char)pt.g, (unsigned char)pt.b, (unsigned char)255); 00373 } 00374 00375 } 00376 00378 srs_env_model::EMOcTree::StaticMemberInitializer srs_env_model::EMOcTree::ocEMOcTreeMemberInit; 00379