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


octomap_rviz_plugins
Author(s): Julius Kammerl
autogenerated on Thu Jun 6 2019 18:26:16