40 #include <octomap/octomap.h> 
   41 #include <OgrePrerequisites.h> 
   42 #include <rviz_common/properties/color_property.hpp> 
   43 #include <rviz_default_plugins/displays/pointcloud/point_cloud_helpers.hpp> 
   70                OctreeVoxelColorMode octree_color_mode, std::size_t max_octree_depth, Ogre::SceneNode* parent_node);
 
   77   void setColor(
double z_pos, 
double min_z, 
double max_z, 
double color_factor, rviz_rendering::PointCloud::Point* point);
 
   78   void setProbColor(
double prob, rviz_rendering::PointCloud::Point* point);
 
   80   void octreeDecoding(
const std::shared_ptr<const octomap::OcTree>& octree,
 
   84   std::vector<rviz_rendering::PointCloud*> cloud_;
 
   85   std::shared_ptr<const octomap::OcTree> octree_;
 
   87   Ogre::SceneNode* scene_node_;
 
   90   std::size_t octree_depth_;
 
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)
 
@ OCTOMAP_PROBABLILTY_COLOR
 
@ OCTOMAP_OCCUPIED_VOXELS