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 #include "rviz/properties/float_property.h"
00048 
00049 #include <octomap/octomap.h>
00050 #include <octomap/ColorOcTree.h>
00051 #include <octomap_msgs/Octomap.h>
00052 #include <octomap_msgs/conversions.h>
00053 
00054 
00055 #include <sstream>
00056 
00057 
00058 using namespace rviz;
00059 
00060 namespace octomap_rviz_plugin
00061 {
00062 
00063 static const std::size_t max_octree_depth_ = sizeof(unsigned short) * 8;
00064 
00065 enum OctreeVoxelRenderMode
00066 {
00067   OCTOMAP_FREE_VOXELS = 1,
00068   OCTOMAP_OCCUPIED_VOXELS = 2
00069 };
00070 
00071 enum OctreeVoxelColorMode
00072 {
00073   OCTOMAP_CELL_COLOR,
00074   OCTOMAP_Z_AXIS_COLOR,
00075   OCTOMAP_PROBABLILTY_COLOR,
00076 };
00077 
00078 OccupancyGridDisplay::OccupancyGridDisplay() :
00079     rviz::Display(),
00080     new_points_received_(false),
00081     messages_received_(0),
00082     queue_size_(5),
00083     color_factor_(0.8)
00084 {
00085 
00086   octomap_topic_property_ = new RosTopicProperty( "Octomap Topic",
00087                                                   "",
00088                                                   QString::fromStdString(ros::message_traits::datatype<octomap_msgs::Octomap>()),
00089                                                   "octomap_msgs::Octomap topic to subscribe to (binary or full probability map)",
00090                                                   this,
00091                                                   SLOT( updateTopic() ));
00092 
00093   queue_size_property_ = new IntProperty( "Queue Size",
00094                                           queue_size_,
00095                                           "Advanced: set the size of the incoming message queue.  Increasing this "
00096                                           "is useful if your incoming TF data is delayed significantly from your"
00097                                           " image data, but it can greatly increase memory usage if the messages are big.",
00098                                           this,
00099                                           SLOT( updateQueueSize() ));
00100   queue_size_property_->setMin(1);
00101 
00102   octree_render_property_ = new rviz::EnumProperty( "Voxel Rendering", "Occupied Voxels",
00103                                                     "Select voxel type.",
00104                                                      this,
00105                                                      SLOT( updateOctreeRenderMode() ) );
00106 
00107   octree_render_property_->addOption( "Occupied Voxels",  OCTOMAP_OCCUPIED_VOXELS );
00108   octree_render_property_->addOption( "Free Voxels",  OCTOMAP_FREE_VOXELS );
00109   octree_render_property_->addOption( "All Voxels",  OCTOMAP_FREE_VOXELS | OCTOMAP_OCCUPIED_VOXELS);
00110 
00111   octree_coloring_property_ = new rviz::EnumProperty( "Voxel Coloring", "Z-Axis",
00112                                                 "Select voxel coloring mode",
00113                                                 this,
00114                                                 SLOT( updateOctreeColorMode() ) );
00115 
00116   octree_coloring_property_->addOption( "Cell Color",  OCTOMAP_CELL_COLOR );
00117   octree_coloring_property_->addOption( "Z-Axis",  OCTOMAP_Z_AXIS_COLOR );
00118   octree_coloring_property_->addOption( "Cell Probability",  OCTOMAP_PROBABLILTY_COLOR );
00119   alpha_property_ = new rviz::FloatProperty( "Voxel Alpha", 1.0, "Set voxel transparency alpha",
00120                                              this, 
00121                                              SLOT( updateAlpha() ) );
00122   alpha_property_->setMin(0.0);
00123   alpha_property_->setMax(1.0);
00124 
00125   tree_depth_property_ = new IntProperty("Max. Octree Depth",
00126                                          max_octree_depth_,
00127                                          "Defines the maximum tree depth",
00128                                          this,
00129                                          SLOT (updateTreeDepth() ));
00130   tree_depth_property_->setMin(0);
00131 
00132   max_height_property_ = new FloatProperty("Max. Height Display",
00133                                            std::numeric_limits<double>::infinity(),
00134                                            "Defines the maximum height to display",
00135                                            this,
00136                                            SLOT (updateMaxHeight() ));
00137 
00138   min_height_property_ = new FloatProperty("Min. Height Display",
00139                                            -std::numeric_limits<double>::infinity(),
00140                                            "Defines the minimum height to display",
00141                                            this,
00142                                            SLOT (updateMinHeight() ));
00143 }
00144 
00145 void OccupancyGridDisplay::onInitialize()
00146 {
00147   boost::mutex::scoped_lock lock(mutex_);
00148 
00149   box_size_.resize(max_octree_depth_);
00150   cloud_.resize(max_octree_depth_);
00151   point_buf_.resize(max_octree_depth_);
00152   new_points_.resize(max_octree_depth_);
00153 
00154   for (std::size_t i = 0; i < max_octree_depth_; ++i)
00155   {
00156     std::stringstream sname;
00157     sname << "PointCloud Nr." << i;
00158     cloud_[i] = new rviz::PointCloud();
00159     cloud_[i]->setName(sname.str());
00160     cloud_[i]->setRenderMode(rviz::PointCloud::RM_BOXES);
00161     scene_node_->attachObject(cloud_[i]);
00162   }
00163 }
00164 
00165 OccupancyGridDisplay::~OccupancyGridDisplay()
00166 {
00167   std::size_t i;
00168 
00169   unsubscribe();
00170 
00171   for (std::vector<rviz::PointCloud*>::iterator it = cloud_.begin(); it != cloud_.end(); ++it) {
00172     delete *(it);
00173   }
00174 
00175   if (scene_node_)
00176     scene_node_->detachAllObjects();
00177 }
00178 
00179 void OccupancyGridDisplay::updateQueueSize()
00180 {
00181   queue_size_ = queue_size_property_->getInt();
00182 
00183   subscribe();
00184 }
00185 
00186 void OccupancyGridDisplay::onEnable()
00187 {
00188   scene_node_->setVisible(true);
00189   subscribe();
00190 }
00191 
00192 void OccupancyGridDisplay::onDisable()
00193 {
00194   scene_node_->setVisible(false);
00195   unsubscribe();
00196 
00197   clear();
00198 }
00199 
00200 void OccupancyGridDisplay::subscribe()
00201 {
00202   if (!isEnabled())
00203   {
00204     return;
00205   }
00206 
00207   try
00208   {
00209     unsubscribe();
00210 
00211     const std::string& topicStr = octomap_topic_property_->getStdString();
00212 
00213     if (!topicStr.empty())
00214     {
00215 
00216       sub_.reset(new message_filters::Subscriber<octomap_msgs::Octomap>());
00217 
00218       sub_->subscribe(threaded_nh_, topicStr, queue_size_);
00219       sub_->registerCallback(boost::bind(&OccupancyGridDisplay::incomingMessageCallback, this, _1));
00220 
00221     }
00222   }
00223   catch (ros::Exception& e)
00224   {
00225     setStatus(StatusProperty::Error, "Topic", (std::string("Error subscribing: ") + e.what()).c_str());
00226   }
00227 
00228 }
00229 
00230 void OccupancyGridDisplay::unsubscribe()
00231 {
00232   clear();
00233 
00234   try
00235   {
00236     // reset filters
00237     sub_.reset();
00238   }
00239   catch (ros::Exception& e)
00240   {
00241     setStatus(StatusProperty::Error, "Topic", (std::string("Error unsubscribing: ") + e.what()).c_str());
00242   }
00243 
00244 }
00245 
00246 // method taken from octomap_server package
00247 void OccupancyGridDisplay::setColor(double z_pos, double min_z, double max_z, double color_factor,
00248                                     rviz::PointCloud::Point& point)
00249 {
00250   int i;
00251   double m, n, f;
00252 
00253   double s = 1.0;
00254   double v = 1.0;
00255 
00256   double h = (1.0 - std::min(std::max((z_pos - min_z) / (max_z - min_z), 0.0), 1.0)) * color_factor;
00257 
00258   h -= floor(h);
00259   h *= 6;
00260   i = floor(h);
00261   f = h - i;
00262   if (!(i & 1))
00263     f = 1 - f; // if i is even
00264   m = v * (1 - s);
00265   n = v * (1 - s * f);
00266 
00267   switch (i)
00268   {
00269     case 6:
00270     case 0:
00271       point.setColor(v, n, m);
00272       break;
00273     case 1:
00274       point.setColor(n, v, m);
00275       break;
00276     case 2:
00277       point.setColor(m, v, n);
00278       break;
00279     case 3:
00280       point.setColor(m, n, v);
00281       break;
00282     case 4:
00283       point.setColor(n, m, v);
00284       break;
00285     case 5:
00286       point.setColor(v, m, n);
00287       break;
00288     default:
00289       point.setColor(1, 0.5, 0.5);
00290       break;
00291   }
00292 }
00293 
00294 void OccupancyGridDisplay::updateTreeDepth()
00295 {
00296 }
00297 
00298 void OccupancyGridDisplay::updateOctreeRenderMode()
00299 {
00300 }
00301 
00302 void OccupancyGridDisplay::updateOctreeColorMode()
00303 {
00304 }
00305 
00306 void OccupancyGridDisplay::updateAlpha()
00307 {
00308 }
00309 
00310 void OccupancyGridDisplay::updateMaxHeight()
00311 {
00312 }
00313 
00314 void OccupancyGridDisplay::updateMinHeight()
00315 {
00316 }
00317 
00318 void OccupancyGridDisplay::clear()
00319 {
00320 
00321   boost::mutex::scoped_lock lock(mutex_);
00322 
00323   // reset rviz pointcloud boxes
00324   for (size_t i = 0; i < cloud_.size(); ++i)
00325   {
00326     cloud_[i]->clear();
00327   }
00328 }
00329 
00330 void OccupancyGridDisplay::update(float wall_dt, float ros_dt)
00331 {
00332   if (new_points_received_)
00333   {
00334     boost::mutex::scoped_lock lock(mutex_);
00335 
00336     for (size_t i = 0; i < max_octree_depth_; ++i)
00337     {
00338       double size = box_size_[i];
00339 
00340       cloud_[i]->clear();
00341       cloud_[i]->setDimensions(size, size, size);
00342 
00343       cloud_[i]->addPoints(&new_points_[i].front(), new_points_[i].size());
00344       new_points_[i].clear();
00345       cloud_[i]->setAlpha(alpha_property_->getFloat());
00346     }
00347     new_points_received_ = false;
00348   }
00349 }
00350 
00351 void OccupancyGridDisplay::reset()
00352 {
00353   clear();
00354   messages_received_ = 0;
00355   setStatus(StatusProperty::Ok, "Messages", QString("0 binary octomap messages received"));
00356 }
00357 
00358 void OccupancyGridDisplay::updateTopic()
00359 {
00360   unsubscribe();
00361   reset();
00362   subscribe();
00363   context_->queueRender();
00364 }
00365 
00366 template <typename OcTreeType>
00367 bool TemplatedOccupancyGridDisplay<OcTreeType>::checkType(std::string type_id)
00368 {
00369   //General case: Need to be specialized for every used case
00370   setStatus(StatusProperty::Warn, "Messages", QString("Cannot verify octomap type"));
00371   return true; //Try deserialization, might crash though
00372 }
00373   
00374 template <>
00375 bool TemplatedOccupancyGridDisplay<octomap::OcTreeStamped>::checkType(std::string type_id)
00376 {
00377   if(type_id == "OcTreeStamped") return true;
00378   else return false;
00379 }
00380 template <>
00381 bool TemplatedOccupancyGridDisplay<octomap::OcTree>::checkType(std::string type_id)
00382 {
00383   if(type_id == "OcTree") return true;
00384   else return false;
00385 }
00386 
00387 template <>
00388 bool TemplatedOccupancyGridDisplay<octomap::ColorOcTree>::checkType(std::string type_id)
00389 {
00390   if(type_id == "ColorOcTree") return true;
00391   else return false;
00392 }
00393 
00394 template <typename OcTreeType>
00395 void TemplatedOccupancyGridDisplay<OcTreeType>::setVoxelColor(PointCloud::Point& newPoint, 
00396                                                               typename OcTreeType::NodeType& node,
00397                                                               double minZ, double maxZ)
00398 {
00399   OctreeVoxelColorMode octree_color_mode = static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt());
00400   float cell_probability;
00401   switch (octree_color_mode)
00402   {
00403     case OCTOMAP_CELL_COLOR:
00404       setStatus(StatusProperty::Error, "Messages", QString("Cannot extract color"));
00405       //Intentional fall-through for else-case
00406     case OCTOMAP_Z_AXIS_COLOR:
00407       setColor(newPoint.position.z, minZ, maxZ, color_factor_, newPoint);
00408       break;
00409     case OCTOMAP_PROBABLILTY_COLOR:
00410       cell_probability = node.getOccupancy();
00411       newPoint.setColor((1.0f-cell_probability), cell_probability, 0.0);
00412       break;
00413     default:
00414       break;
00415   }
00416 }
00417 
00418 //Specialization for ColorOcTreeNode, which can set the voxel color from the node itself
00419 template <>
00420 void TemplatedOccupancyGridDisplay<octomap::ColorOcTree>::setVoxelColor(PointCloud::Point& newPoint, 
00421                                                                       octomap::ColorOcTree::NodeType& node,
00422                                                                       double minZ, double maxZ)
00423 {
00424   float cell_probability;
00425   OctreeVoxelColorMode octree_color_mode = static_cast<OctreeVoxelColorMode>(octree_coloring_property_->getOptionInt());
00426   switch (octree_color_mode)
00427   {
00428     case OCTOMAP_CELL_COLOR:
00429     {
00430       const float b2f = 1./256.; 
00431       octomap::ColorOcTreeNode::Color& color = node.getColor();
00432       newPoint.setColor(b2f*color.r, b2f*color.g, b2f*color.b, node.getOccupancy());
00433       break;
00434     }
00435     case OCTOMAP_Z_AXIS_COLOR:
00436       setColor(newPoint.position.z, minZ, maxZ, color_factor_, newPoint);
00437       break;
00438     case OCTOMAP_PROBABLILTY_COLOR:
00439       cell_probability = node.getOccupancy();
00440       newPoint.setColor((1.0f-cell_probability), cell_probability, 0.0);
00441       break;
00442     default:
00443       break;
00444   }
00445 }
00446 
00447 
00448 template <typename OcTreeType>
00449 void TemplatedOccupancyGridDisplay<OcTreeType>::incomingMessageCallback(const octomap_msgs::OctomapConstPtr& msg)
00450 {
00451   ++messages_received_;
00452   setStatus(StatusProperty::Ok, "Messages", QString::number(messages_received_) + " octomap messages received");
00453   setStatusStd(StatusProperty::Ok, "Type", msg->id.c_str());
00454   if(!checkType(msg->id)){
00455     setStatusStd(StatusProperty::Error, "Message", "Wrong octomap type. Use a different display type.");
00456     return;
00457   }
00458 
00459   ROS_DEBUG("Received OctomapBinary message (size: %d bytes)", (int)msg->data.size());
00460 
00461   // get tf transform
00462   Ogre::Vector3 pos;
00463   Ogre::Quaternion orient;
00464   if (!context_->getFrameManager()->getTransform(msg->header, pos, orient))
00465   {
00466     std::stringstream ss;
00467     ss << "Failed to transform from frame [" << msg->header.frame_id << "] to frame ["
00468         << context_->getFrameManager()->getFixedFrame() << "]";
00469     setStatusStd(StatusProperty::Error, "Message", ss.str());
00470     return;
00471   }
00472 
00473   scene_node_->setOrientation(orient);
00474   scene_node_->setPosition(pos);
00475 
00476   // creating octree
00477   OcTreeType* octomap = NULL;
00478   octomap::AbstractOcTree* tree = octomap_msgs::msgToMap(*msg);
00479   if (tree){
00480     octomap = dynamic_cast<OcTreeType*>(tree);
00481     if(!octomap){
00482       setStatusStd(StatusProperty::Error, "Message", "Wrong octomap type. Use a different display type.");
00483     }
00484   }
00485   else
00486   {
00487     setStatusStd(StatusProperty::Error, "Message", "Failed to deserialize octree message.");
00488     return;
00489   }
00490 
00491 
00492   std::size_t octree_depth = octomap->getTreeDepth();
00493   tree_depth_property_->setMax(octomap->getTreeDepth());
00494 
00495 
00496   // get dimensions of octree
00497   double minX, minY, minZ, maxX, maxY, maxZ;
00498   octomap->getMetricMin(minX, minY, minZ);
00499   octomap->getMetricMax(maxX, maxY, maxZ);
00500 
00501   // reset rviz pointcloud classes
00502   for (std::size_t i = 0; i < max_octree_depth_; ++i)
00503   {
00504     point_buf_[i].clear();
00505     box_size_[i] = octomap->getNodeSize(i + 1);
00506   }
00507 
00508   size_t pointCount = 0;
00509   {
00510     // traverse all leafs in the tree:
00511     unsigned int treeDepth = std::min<unsigned int>(tree_depth_property_->getInt(), octomap->getTreeDepth());
00512     double maxHeight = std::min<double>(max_height_property_->getFloat(), maxZ);
00513     double minHeight = std::max<double>(min_height_property_->getFloat(), minZ);
00514     for (typename OcTreeType::iterator it = octomap->begin(treeDepth), end = octomap->end(); it != end; ++it)
00515     {
00516 
00517       if (octomap->isNodeOccupied(*it))
00518       {
00519         if(it.getZ() <= maxHeight && it.getZ() >= minHeight)
00520         {
00521           int render_mode_mask = octree_render_property_->getOptionInt();
00522 
00523           bool display_voxel = false;
00524 
00525           // the left part evaluates to 1 for free voxels and 2 for occupied voxels
00526           if (((int)octomap->isNodeOccupied(*it) + 1) & render_mode_mask)
00527           {
00528             // check if current voxel has neighbors on all sides -> no need to be displayed
00529             bool allNeighborsFound = true;
00530 
00531             octomap::OcTreeKey key;
00532             octomap::OcTreeKey nKey = it.getKey();
00533 
00534             for (key[2] = nKey[2] - 1; allNeighborsFound && key[2] <= nKey[2] + 1; ++key[2])
00535             {
00536               for (key[1] = nKey[1] - 1; allNeighborsFound && key[1] <= nKey[1] + 1; ++key[1])
00537               {
00538                 for (key[0] = nKey[0] - 1; allNeighborsFound && key[0] <= nKey[0] + 1; ++key[0])
00539                 {
00540                   if (key != nKey)
00541                   {
00542                     typename OcTreeType::NodeType* node = octomap->search(key);
00543 
00544                     // the left part evaluates to 1 for free voxels and 2 for occupied voxels
00545                     if (!(node && ((((int)octomap->isNodeOccupied(node)) + 1) & render_mode_mask)))
00546                     {
00547                       // we do not have a neighbor => break!
00548                       allNeighborsFound = false;
00549                     }
00550                   }
00551                 }
00552               }
00553             }
00554 
00555             display_voxel |= !allNeighborsFound;
00556           }
00557 
00558 
00559           if (display_voxel)
00560           {
00561             PointCloud::Point newPoint;
00562 
00563             newPoint.position.x = it.getX();
00564             newPoint.position.y = it.getY();
00565             newPoint.position.z = it.getZ();
00566 
00567 
00568 
00569             setVoxelColor(newPoint, *it, minZ, maxZ);
00570             // push to point vectors
00571             unsigned int depth = it.getDepth();
00572             point_buf_[depth - 1].push_back(newPoint);
00573 
00574             ++pointCount;
00575           }
00576         }
00577       }
00578     }
00579   }
00580 
00581   if (pointCount)
00582   {
00583     boost::mutex::scoped_lock lock(mutex_);
00584 
00585     new_points_received_ = true;
00586 
00587     for (size_t i = 0; i < max_octree_depth_; ++i)
00588       new_points_[i].swap(point_buf_[i]);
00589 
00590   }
00591   delete octomap;
00592 }
00593 
00594 } // namespace octomap_rviz_plugin
00595 
00596 #include <pluginlib/class_list_macros.h>
00597 
00598 typedef octomap_rviz_plugin::TemplatedOccupancyGridDisplay<octomap::OcTree> OcTreeGridDisplay;
00599 typedef octomap_rviz_plugin::TemplatedOccupancyGridDisplay<octomap::ColorOcTree> ColorOcTreeGridDisplay;
00600 typedef octomap_rviz_plugin::TemplatedOccupancyGridDisplay<octomap::OcTreeStamped> OcTreeStampedGridDisplay;
00601 
00602 PLUGINLIB_EXPORT_CLASS( OcTreeGridDisplay, rviz::Display)
00603 PLUGINLIB_EXPORT_CLASS( ColorOcTreeGridDisplay, rviz::Display)
00604 PLUGINLIB_EXPORT_CLASS( OcTreeStampedGridDisplay, rviz::Display)
00605 


octomap_rviz_plugins
Author(s): Julius Kammerl
autogenerated on Mon Jul 11 2016 08:58:18