occupancy_grid_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
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  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  * Author: Julius Kammerl (jkammerl@willowgarage.com)
00030  *
00031  */
00032 #include <QObject>
00033 
00034 #include "octomap_rviz_plugins/occupancy_grid_display.h"
00035 
00036 #include <boost/bind.hpp>
00037 #include <boost/shared_ptr.hpp>
00038 
00039 #include <OGRE/OgreSceneNode.h>
00040 #include <OGRE/OgreSceneManager.h>
00041 
00042 #include "rviz/visualization_manager.h"
00043 #include "rviz/frame_manager.h"
00044 #include "rviz/properties/int_property.h"
00045 #include "rviz/properties/ros_topic_property.h"
00046 #include "rviz/properties/enum_property.h"
00047 
00048 #include <octomap/octomap.h>
00049 #include <octomap_msgs/Octomap.h>
00050 #include <octomap_msgs/conversions.h>
00051 
00052 #include <sstream>
00053 
00054 using namespace rviz;
00055 
00056 namespace octomap_rviz_plugin
00057 {
00058 
00059 static const std::size_t max_octree_depth_ = sizeof(unsigned short) * 8;
00060 
00061 enum OctreeVoxelRenderMode
00062 {
00063   OCTOMAP_FREE_VOXELS = 1,
00064   OCTOMAP_OCCUPIED_VOXELS = 2
00065 };
00066 
00067 enum OctreeVoxelColorMode
00068 {
00069   OCTOMAP_Z_AXIS_COLOR,
00070   OCTOMAP_PROBABLILTY_COLOR,
00071 };
00072 
00073 OccupancyGridDisplay::OccupancyGridDisplay() :
00074     rviz::Display(),
00075     new_points_received_(false),
00076     messages_received_(0),
00077     queue_size_(5),
00078     color_factor_(0.8),
00079     octree_depth_(0)
00080 {
00081 
00082   octomap_topic_property_ = new RosTopicProperty( "Octomap Binary Topic",
00083                                                   "",
00084                                                   QString::fromStdString(ros::message_traits::datatype<octomap_msgs::Octomap>()),
00085                                                   "octomap_msgs::OctomapBinary topic to subscribe to.",
00086                                                   this,
00087                                                   SLOT( updateTopic() ));
00088 
00089   queue_size_property_ = new IntProperty( "Queue Size",
00090                                           queue_size_,
00091                                           "Advanced: set the size of the incoming message queue.  Increasing this "
00092                                           "is useful if your incoming TF data is delayed significantly from your"
00093                                           " image data, but it can greatly increase memory usage if the messages are big.",
00094                                           this,
00095                                           SLOT( updateQueueSize() ));
00096   queue_size_property_->setMin(1);
00097 
00098   octree_render_property_ = new rviz::EnumProperty( "Voxel Rendering", "Occupied Voxels",
00099                                                     "Select voxel type.",
00100                                                      this,
00101                                                      SLOT( updateOctreeRenderMode() ) );
00102 
00103   octree_render_property_->addOption( "Occupied Voxels",  OCTOMAP_OCCUPIED_VOXELS );
00104   octree_render_property_->addOption( "Free Voxels",  OCTOMAP_FREE_VOXELS );
00105   octree_render_property_->addOption( "All Voxels",  OCTOMAP_FREE_VOXELS | OCTOMAP_OCCUPIED_VOXELS);
00106 
00107   octree_coloring_property_ = new rviz::EnumProperty( "Voxel Coloring", "Z-Axis",
00108                                                 "Select voxel coloring mode",
00109                                                 this,
00110                                                 SLOT( updateOctreeColorMode() ) );
00111 
00112   octree_coloring_property_->addOption( "Z-Axis",  OCTOMAP_Z_AXIS_COLOR );
00113   octree_coloring_property_->addOption( "Cell Probability",  OCTOMAP_PROBABLILTY_COLOR );
00114 
00115   tree_depth_property_ = new IntProperty("Max. Octree Depth",
00116                                          max_octree_depth_,
00117                                          "Defines the maximum tree depth",
00118                                          this,
00119                                          SLOT (updateTreeDepth() ));
00120 }
00121 
00122 void OccupancyGridDisplay::onInitialize()
00123 {
00124   boost::mutex::scoped_lock lock(mutex_);
00125 
00126   box_size_.resize(max_octree_depth_);
00127   cloud_.resize(max_octree_depth_);
00128   point_buf_.resize(max_octree_depth_);
00129   new_points_.resize(max_octree_depth_);
00130 
00131   for (std::size_t i = 0; i < max_octree_depth_; ++i)
00132   {
00133     std::stringstream sname;
00134     sname << "PointCloud Nr." << i;
00135     cloud_[i] = new rviz::PointCloud();
00136     cloud_[i]->setName(sname.str());
00137     cloud_[i]->setRenderMode(rviz::PointCloud::RM_BOXES);
00138     scene_node_->attachObject(cloud_[i]);
00139   }
00140 }
00141 
00142 OccupancyGridDisplay::~OccupancyGridDisplay()
00143 {
00144   std::size_t i;
00145 
00146   unsubscribe();
00147 
00148   for (i = 0; i < max_octree_depth_; ++i)
00149     delete cloud_[i];
00150 
00151   scene_node_->detachAllObjects();
00152 }
00153 
00154 void OccupancyGridDisplay::updateQueueSize()
00155 {
00156   queue_size_ = queue_size_property_->getInt();
00157 
00158   subscribe();
00159 }
00160 
00161 void OccupancyGridDisplay::onEnable()
00162 {
00163   scene_node_->setVisible(true);
00164   subscribe();
00165 }
00166 
00167 void OccupancyGridDisplay::onDisable()
00168 {
00169   scene_node_->setVisible(false);
00170   unsubscribe();
00171 
00172   clear();
00173 }
00174 
00175 void OccupancyGridDisplay::subscribe()
00176 {
00177   if (!isEnabled())
00178   {
00179     return;
00180   }
00181 
00182   try
00183   {
00184     unsubscribe();
00185 
00186     const std::string& topicStr = octomap_topic_property_->getStdString();
00187 
00188     if (!topicStr.empty())
00189     {
00190 
00191       sub_.reset(new message_filters::Subscriber<octomap_msgs::Octomap>());
00192 
00193       sub_->subscribe(threaded_nh_, topicStr, queue_size_);
00194       sub_->registerCallback(boost::bind(&OccupancyGridDisplay::incomingMessageCallback, this, _1));
00195 
00196     }
00197   }
00198   catch (ros::Exception& e)
00199   {
00200     setStatus(StatusProperty::Error, "Topic", (std::string("Error subscribing: ") + e.what()).c_str());
00201   }
00202 
00203 }
00204 
00205 void OccupancyGridDisplay::unsubscribe()
00206 {
00207   clear();
00208 
00209   try
00210   {
00211     // reset filters
00212     sub_.reset();
00213   }
00214   catch (ros::Exception& e)
00215   {
00216     setStatus(StatusProperty::Error, "Topic", (std::string("Error unsubscribing: ") + e.what()).c_str());
00217   }
00218 
00219 }
00220 
00221 // method taken from octomap_server package
00222 void OccupancyGridDisplay::setColor(double z_pos, double min_z, double max_z, double color_factor,
00223                                     rviz::PointCloud::Point& point)
00224 {
00225   int i;
00226   double m, n, f;
00227 
00228   double s = 1.0;
00229   double v = 1.0;
00230 
00231   double h = (1.0 - std::min(std::max((z_pos - min_z) / (max_z - min_z), 0.0), 1.0)) * color_factor;
00232 
00233   h -= floor(h);
00234   h *= 6;
00235   i = floor(h);
00236   f = h - i;
00237   if (!(i & 1))
00238     f = 1 - f; // if i is even
00239   m = v * (1 - s);
00240   n = v * (1 - s * f);
00241 
00242   switch (i)
00243   {
00244     case 6:
00245     case 0:
00246       point.setColor(v, n, m);
00247       break;
00248     case 1:
00249       point.setColor(n, v, m);
00250       break;
00251     case 2:
00252       point.setColor(m, v, n);
00253       break;
00254     case 3:
00255       point.setColor(m, n, v);
00256       break;
00257     case 4:
00258       point.setColor(n, m, v);
00259       break;
00260     case 5:
00261       point.setColor(v, m, n);
00262       break;
00263     default:
00264       point.setColor(1, 0.5, 0.5);
00265       break;
00266   }
00267 }
00268 
00269 void OccupancyGridDisplay::incomingMessageCallback(const octomap_msgs::OctomapConstPtr& msg)
00270 {
00271   ++messages_received_;
00272   setStatus(StatusProperty::Ok, "Messages", QString::number(messages_received_) + " binary octomap messages received");
00273 
00274   ROS_DEBUG("Received OctomapBinary message (size: %d bytes)", (int)msg->data.size());
00275 
00276   // get tf transform
00277   Ogre::Vector3 pos;
00278   Ogre::Quaternion orient;
00279   if (!context_->getFrameManager()->getTransform(msg->header, pos, orient))
00280   {
00281     std::stringstream ss;
00282     ss << "Failed to transform from frame [" << msg->header.frame_id << "] to frame ["
00283         << context_->getFrameManager()->getFixedFrame() << "]";
00284     this->setStatusStd(StatusProperty::Error, "Message", ss.str());
00285     return;
00286   }
00287 
00288   scene_node_->setOrientation(orient);
00289   scene_node_->setPosition(pos);
00290 
00291   // creating octree
00292   octomap::OcTree* octomap = NULL;
00293   octomap::AbstractOcTree* tree = octomap_msgs::msgToMap(*msg);
00294   if (tree){
00295     octomap = dynamic_cast<octomap::OcTree*>(tree);
00296   }
00297 
00298   if (!octomap)
00299   {
00300     this->setStatusStd(StatusProperty::Error, "Message", "Failed to create octree structure");
00301     return;
00302   }
00303 
00304   std::size_t octree_depth = octomap->getTreeDepth();
00305 
00306   // get dimensions of octree
00307   double minX, minY, minZ, maxX, maxY, maxZ;
00308   octomap->getMetricMin(minX, minY, minZ);
00309   octomap->getMetricMax(maxX, maxY, maxZ);
00310 
00311   // reset rviz pointcloud classes
00312   for (std::size_t i = 0; i < max_octree_depth_; ++i)
00313   {
00314     point_buf_[i].clear();
00315     box_size_[i] = octomap->getNodeSize(i + 1);
00316   }
00317 
00318   size_t pointCount = 0;
00319   {
00320     // traverse all leafs in the tree:
00321     unsigned int treeDepth = std::min<unsigned int>(tree_depth_property_->getInt(), octomap->getTreeDepth());
00322     for (octomap::OcTree::iterator it = octomap->begin(treeDepth), end = octomap->end(); it != end; ++it)
00323     {
00324 
00325       if (octomap->isNodeOccupied(*it))
00326       {
00327 
00328         int render_mode_mask = octree_render_property_->getOptionInt();
00329 
00330         bool display_voxel = false;
00331 
00332         // the left part evaluates to 1 for free voxels and 2 for occupied voxels
00333         if (((int)octomap->isNodeOccupied(*it) + 1) & render_mode_mask)
00334         {
00335           // check if current voxel has neighbors on all sides -> no need to be displayed
00336           bool allNeighborsFound = true;
00337 
00338           octomap::OcTreeKey key;
00339           octomap::OcTreeKey nKey = it.getKey();
00340 
00341           for (key[2] = nKey[2] - 1; allNeighborsFound && key[2] <= nKey[2] + 1; ++key[2])
00342           {
00343             for (key[1] = nKey[1] - 1; allNeighborsFound && key[1] <= nKey[1] + 1; ++key[1])
00344             {
00345               for (key[0] = nKey[0] - 1; allNeighborsFound && key[0] <= nKey[0] + 1; ++key[0])
00346               {
00347                 if (key != nKey)
00348                 {
00349                   octomap::OcTreeNode* node = octomap->search(key);
00350 
00351                   // the left part evaluates to 1 for free voxels and 2 for occupied voxels
00352                   if (!(node && (((int)octomap->isNodeOccupied(node)) + 1) & render_mode_mask))
00353                   {
00354                     // we do not have a neighbor => break!
00355                     allNeighborsFound = false;
00356                   }
00357                 }
00358               }
00359             }
00360           }
00361 
00362           display_voxel |= !allNeighborsFound;
00363         }
00364 
00365 
00366         if (display_voxel)
00367         {
00368           PointCloud::Point newPoint;
00369 
00370           newPoint.position.x = it.getX();
00371           newPoint.position.y = it.getY();
00372           newPoint.position.z = it.getZ();
00373 
00374           float cell_probability;
00375 
00376           OctreeVoxelColorMode octree_color_mode = static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt());
00377 
00378           switch (octree_color_mode)
00379           {
00380             case OCTOMAP_Z_AXIS_COLOR:
00381               setColor(newPoint.position.z, minZ, maxZ, color_factor_, newPoint);
00382               break;
00383             case OCTOMAP_PROBABLILTY_COLOR:
00384               cell_probability = it->getOccupancy();
00385               newPoint.setColor((1.0f-cell_probability), cell_probability, 0.0);
00386               break;
00387             default:
00388               break;
00389           }
00390 
00391           // push to point vectors
00392           unsigned int depth = it.getDepth();
00393           point_buf_[depth - 1].push_back(newPoint);
00394 
00395           ++pointCount;
00396         }
00397       }
00398     }
00399   }
00400 
00401   if (pointCount)
00402   {
00403     boost::mutex::scoped_lock lock(mutex_);
00404 
00405     new_points_received_ = true;
00406 
00407     for (size_t i = 0; i < max_octree_depth_; ++i)
00408       new_points_[i].swap(point_buf_[i]);
00409 
00410   }
00411   delete octomap;
00412 }
00413 
00414 void OccupancyGridDisplay::updateTreeDepth()
00415 {
00416 }
00417 
00418 void OccupancyGridDisplay::updateOctreeRenderMode()
00419 {
00420 }
00421 
00422 void OccupancyGridDisplay::updateOctreeColorMode()
00423 {
00424 }
00425 
00426 void OccupancyGridDisplay::clear()
00427 {
00428 
00429   boost::mutex::scoped_lock lock(mutex_);
00430 
00431   // reset rviz pointcloud boxes
00432   for (size_t i = 0; i < cloud_.size(); ++i)
00433   {
00434     cloud_[i]->clear();
00435   }
00436 }
00437 
00438 void OccupancyGridDisplay::update(float wall_dt, float ros_dt)
00439 {
00440   if (new_points_received_)
00441   {
00442     boost::mutex::scoped_lock lock(mutex_);
00443 
00444     for (size_t i = 0; i < max_octree_depth_; ++i)
00445     {
00446       double size = box_size_[i];
00447 
00448       cloud_[i]->clear();
00449       cloud_[i]->setDimensions(size, size, size);
00450 
00451       cloud_[i]->addPoints(&new_points_[i].front(), new_points_[i].size());
00452       new_points_[i].clear();
00453 
00454     }
00455     new_points_received_ = false;
00456   }
00457 }
00458 
00459 void OccupancyGridDisplay::reset()
00460 {
00461   clear();
00462   messages_received_ = 0;
00463   setStatus(StatusProperty::Ok, "Messages", QString("0 binary octomap messages received"));
00464 }
00465 
00466 void OccupancyGridDisplay::updateTopic()
00467 {
00468   unsubscribe();
00469   reset();
00470   subscribe();
00471   context_->queueRender();
00472 }
00473 
00474 
00475 } // namespace octomap_rviz_plugin
00476 
00477 #include <pluginlib/class_list_macros.h>
00478 
00479 PLUGINLIB_EXPORT_CLASS( octomap_rviz_plugin::OccupancyGridDisplay, rviz::Display)
00480 


octomap_rviz_plugins
Author(s): Julius Kammerl
autogenerated on Mon Oct 6 2014 03:00:57