Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_OCTOMAP_RENDER_
00038 #define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_OCTOMAP_RENDER_
00039
00040 #include <vector>
00041 #include <rviz/ogre_helpers/point_cloud.h>
00042
00043 #include <moveit/rviz_plugin_render_tools/octomap_render.h>
00044
00045 namespace octomap
00046 {
00047 class OcTree;
00048 }
00049
00050 namespace Ogre
00051 {
00052 class SceneManager;
00053 class SceneNode;
00054 class AxisAlignedBox;
00055 }
00056
00057 namespace moveit_rviz_plugin
00058 {
00059 enum OctreeVoxelRenderMode
00060 {
00061 OCTOMAP_FREE_VOXELS = 1,
00062 OCTOMAP_OCCUPIED_VOXELS = 2
00063 };
00064
00065 enum OctreeVoxelColorMode
00066 {
00067 OCTOMAP_Z_AXIS_COLOR,
00068 OCTOMAP_PROBABLILTY_COLOR,
00069 };
00070
00071 class OcTreeRender
00072 {
00073 public:
00074 OcTreeRender(const boost::shared_ptr<const octomap::OcTree>& octree, OctreeVoxelRenderMode octree_voxel_rendering,
00075 OctreeVoxelColorMode octree_color_mode, std::size_t max_octree_depth, Ogre::SceneManager* scene_manager,
00076 Ogre::SceneNode* parent_node);
00077 virtual ~OcTreeRender();
00078
00079 private:
00080 void setColor(double z_pos, double min_z, double max_z, double color_factor, rviz::PointCloud::Point* point);
00081 void setProbColor(double prob, rviz::PointCloud::Point* point);
00082
00083 void octreeDecoding(const boost::shared_ptr<const octomap::OcTree>& octree,
00084 OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode);
00085
00086
00087 std::vector<rviz::PointCloud*> cloud_;
00088 boost::shared_ptr<const octomap::OcTree> octree_;
00089
00090 Ogre::SceneNode* scene_node_;
00091 Ogre::SceneManager* scene_manager_;
00092
00093 double colorFactor_;
00094 std::size_t octree_depth_;
00095 };
00096 }
00097 #endif