39 #include <octomap_msgs/msg/octomap.hpp> 
   40 #include <octomap/octomap.h> 
   42 #include <OgreSceneNode.h> 
   43 #include <OgreSceneManager.h> 
   47 typedef std::vector<rviz_rendering::PointCloud::Point> 
VPoint;
 
   52                            std::size_t max_octree_depth, Ogre::SceneNode* parent_node)
 
   53   : octree_(octree), colorFactor_(0.8)
 
   55   if (!max_octree_depth)
 
   57     octree_depth_ = octree->getTreeDepth();
 
   61     octree_depth_ = std::min(max_octree_depth, (std::size_t)octree->getTreeDepth());
 
   64   scene_node_ = parent_node->createChildSceneNode();
 
   66   cloud_.resize(octree_depth_);
 
   68   for (std::size_t i = 0; i < octree_depth_; ++i)
 
   70     std::stringstream sname;
 
   71     sname << 
"PointCloud Nr." << i;
 
   72     cloud_[i] = 
new rviz_rendering::PointCloud();
 
   73     cloud_[i]->setName(sname.str());
 
   74     cloud_[i]->setRenderMode(rviz_rendering::PointCloud::RM_BOXES);
 
   75     scene_node_->attachObject(cloud_[i]);
 
   78   octreeDecoding(octree, octree_voxel_rendering, octree_color_mode);
 
   83   scene_node_->detachAllObjects();
 
   85   for (std::size_t i = 0; i < octree_depth_; ++i)
 
   93   scene_node_->setPosition(position);
 
   98   scene_node_->setOrientation(orientation);
 
  102 void OcTreeRender::setColor(
double z_pos, 
double min_z, 
double max_z, 
double color_factor,
 
  103                             rviz_rendering::PointCloud::Point* point)
 
  111   double h = (1.0 - std::min(std::max((z_pos - min_z) / (max_z - min_z), 0.0), 1.0)) * color_factor;
 
  126       point->setColor(v, n, m);
 
  129       point->setColor(n, v, m);
 
  132       point->setColor(m, v, n);
 
  135       point->setColor(m, n, v);
 
  138       point->setColor(n, m, v);
 
  141       point->setColor(v, m, n);
 
  144       point->setColor(1, 0.5, 0.5);
 
  149 void OcTreeRender::octreeDecoding(
const std::shared_ptr<const octomap::OcTree>& octree,
 
  153   point_buf.resize(octree_depth_);
 
  156   double min_x, min_y, min_z, max_x, max_y, max_z;
 
  157   octree->getMetricMin(min_x, min_y, min_z);
 
  158   octree->getMetricMax(max_x, max_y, max_z);
 
  160   unsigned int render_mode_mask = 
static_cast<unsigned int>(octree_voxel_rendering);
 
  162   size_t point_count = 0;
 
  164     int step_size = 1 << (octree->getTreeDepth() - octree_depth_);  
 
  167     for (octomap::OcTree::iterator it = octree->begin(octree_depth_), end = octree->end(); it != end; ++it)
 
  169       bool display_voxel = 
false;
 
  172       if ((
static_cast<int>(octree->isNodeOccupied(*it)) + 1) & render_mode_mask)
 
  175         bool all_neighbors_found = 
true;
 
  177         octomap::OcTreeKey key;
 
  178         octomap::OcTreeKey n_key = it.getIndexKey();  
 
  182         int diff_base = 1 << (octree->getTreeDepth() - it.getDepth());
 
  183         int diff[2] = { -1, diff_base };
 
  186         for (
unsigned int idx_case = 0; idx_case < 3; ++idx_case)
 
  188           int idx_0 = idx_case % 3;
 
  189           int idx_1 = (idx_case + 1) % 3;
 
  190           int idx_2 = (idx_case + 2) % 3;
 
  192           for (
int i = 0; all_neighbors_found && i < 2; ++i)
 
  194             key[idx_0] = n_key[idx_0] + diff[i];
 
  197             for (key[idx_1] = n_key[idx_1] + diff[0] + 1; all_neighbors_found && key[idx_1] < n_key[idx_1] + diff[1];
 
  198                  key[idx_1] += step_size)
 
  200               for (key[idx_2] = n_key[idx_2] + diff[0] + 1; all_neighbors_found && key[idx_2] < n_key[idx_2] + diff[1];
 
  201                    key[idx_2] += step_size)
 
  203                 octomap::OcTreeNode* node = octree->search(key, octree_depth_);
 
  206                 if (!(node && (((
static_cast<int>(octree->isNodeOccupied(node))) + 1) & render_mode_mask)))
 
  209                   all_neighbors_found = 
false;
 
  216         display_voxel |= !all_neighbors_found;
 
  221         rviz_rendering::PointCloud::Point new_point;
 
  223         new_point.position.x = it.getX();
 
  224         new_point.position.y = it.getY();
 
  225         new_point.position.z = it.getZ();
 
  227         float cell_probability;
 
  229         switch (octree_color_mode)
 
  232             setColor(new_point.position.z, min_z, max_z, colorFactor_, &new_point);
 
  235             cell_probability = it->getOccupancy();
 
  236             new_point.setColor((1.0f - cell_probability), cell_probability, 0.0);
 
  243         unsigned int depth = it.getDepth();
 
  244         point_buf[depth - 1].push_back(new_point);
 
  251   for (
size_t i = 0; i < octree_depth_; ++i)
 
  253     double size = octree->getNodeSize(i + 1);
 
  256     cloud_[i]->setDimensions(size, size, size);
 
  258     cloud_[i]->addPoints(point_buf[i].begin(), point_buf[i].end());
 
  259     point_buf[i].clear();
 
void setOrientation(const Ogre::Quaternion &orientation)
 
OcTreeRender(const std::shared_ptr< const octomap::OcTree > &octree, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, std::size_t max_octree_depth, Ogre::SceneNode *parent_node)
 
void setPosition(const Ogre::Vector3 &position)
 
std::vector< rviz_rendering::PointCloud::Point > VPoint
 
std::vector< VPoint > VVPoint
 
@ OCTOMAP_PROBABLILTY_COLOR