render_shapes.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
42 #include <rviz/helpers/color.h>
43 #include <Eigen/Geometry>
44 #include <memory>
45 
46 namespace Ogre
47 {
48 class SceneNode;
49 }
50 
51 namespace rviz
52 {
53 class DisplayContext;
54 class Shape;
55 } // namespace rviz
56 
57 namespace moveit_rviz_plugin
58 {
59 MOVEIT_CLASS_FORWARD(OcTreeRender); // Defines OcTreeRenderPtr, ConstPtr, WeakPtr... etc
60 MOVEIT_CLASS_FORWARD(RenderShapes); // Defines RenderShapesPtr, ConstPtr, WeakPtr... etc
61 
63 {
64 public:
66  ~RenderShapes();
67 
68  void renderShape(Ogre::SceneNode* node, const shapes::Shape* s, const Eigen::Isometry3d& p,
69  OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode,
70  const rviz::Color& color, float alpha);
71  void updateShapeColors(float r, float g, float b, float a);
72  void clear();
73 
74 private:
76 
77  std::vector<std::unique_ptr<rviz::Shape> > scene_shapes_;
78  std::vector<OcTreeRenderPtr> octree_voxel_grids_;
79 };
80 } // namespace moveit_rviz_plugin
octomap_render.h
Ogre
s
XmlRpcServer s
r
r
moveit_rviz_plugin::RenderShapes::renderShape
void renderShape(Ogre::SceneNode *node, const shapes::Shape *s, const Eigen::Isometry3d &p, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, const rviz::Color &color, float alpha)
Definition: render_shapes.cpp:107
moveit_rviz_plugin::RenderShapes::RenderShapes
RenderShapes(rviz::DisplayContext *context)
Definition: render_shapes.cpp:92
moveit_rviz_plugin::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(RobotStateVisualization)
moveit_rviz_plugin::RenderShapes::scene_shapes_
std::vector< std::unique_ptr< rviz::Shape > > scene_shapes_
Definition: render_shapes.h:77
shapes::Shape
color.h
a
list a
moveit_rviz_plugin::OctreeVoxelRenderMode
OctreeVoxelRenderMode
Definition: octomap_render.h:52
moveit_rviz_plugin::RenderShapes::context_
rviz::DisplayContext * context_
Definition: render_shapes.h:75
rviz
moveit_rviz_plugin::RenderShapes::octree_voxel_grids_
std::vector< OcTreeRenderPtr > octree_voxel_grids_
Definition: render_shapes.h:78
shapes.h
rviz::DisplayContext
moveit_rviz_plugin::RenderShapes
Definition: render_shapes.h:62
moveit_rviz_plugin
Definition: motion_planning_display.h:80
moveit_rviz_plugin::RenderShapes::clear
void clear()
Definition: render_shapes.cpp:101
class_forward.h
moveit_rviz_plugin::RenderShapes::~RenderShapes
~RenderShapes()
Definition: render_shapes.cpp:96
moveit_rviz_plugin::RenderShapes::updateShapeColors
void updateShapeColors(float r, float g, float b, float a)
Definition: render_shapes.cpp:238
moveit_rviz_plugin::OctreeVoxelColorMode
OctreeVoxelColorMode
Definition: octomap_render.h:58
rviz::Color


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:26