render_shapes.cpp
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 
40 
41 #include <OgreSceneNode.h>
42 #include <OgreSceneManager.h>
43 #include <OgreManualObject.h>
44 #include <OgreMaterialManager.h>
45 
48 
49 #include <rviz/display_context.h>
50 #include <rviz/robot/robot.h>
51 
52 #include <boost/lexical_cast.hpp>
53 #include <boost/math/constants/constants.hpp>
54 
55 #include <memory>
56 
57 namespace moveit_rviz_plugin
58 {
59 RenderShapes::RenderShapes(rviz::DisplayContext* context) : context_(context)
60 {
61 }
62 
64 {
65  clear();
66 }
67 
69 {
70  scene_shapes_.clear();
71  octree_voxel_grids_.clear();
72 }
73 
74 void RenderShapes::renderShape(Ogre::SceneNode* node, const shapes::Shape* s, const Eigen::Affine3d& p,
75  OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode,
76  const rviz::Color& color, float alpha)
77 {
78  rviz::Shape* ogre_shape = NULL;
79  Eigen::Vector3d translation = p.translation();
80  Ogre::Vector3 position(translation.x(), translation.y(), translation.z());
81  Eigen::Quaterniond q(p.linear());
82  Ogre::Quaternion orientation(q.w(), q.x(), q.y(), q.z());
83 
84  // we don't know how to render cones directly, but we can convert them to a mesh
85  if (s->type == shapes::CONE)
86  {
87  std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(static_cast<const shapes::Cone&>(*s)));
88  if (m)
89  renderShape(node, m.get(), p, octree_voxel_rendering, octree_color_mode, color, alpha);
90  return;
91  }
92 
93  switch (s->type)
94  {
95  case shapes::SPHERE:
96  {
97  ogre_shape = new rviz::Shape(rviz::Shape::Sphere, context_->getSceneManager(), node);
98  double d = 2.0 * static_cast<const shapes::Sphere*>(s)->radius;
99  ogre_shape->setScale(Ogre::Vector3(d, d, d));
100  }
101  break;
102  case shapes::BOX:
103  {
104  ogre_shape = new rviz::Shape(rviz::Shape::Cube, context_->getSceneManager(), node);
105  const double* sz = static_cast<const shapes::Box*>(s)->size;
106  ogre_shape->setScale(Ogre::Vector3(sz[0], sz[1], sz[2]));
107  }
108  break;
109  case shapes::CYLINDER:
110  {
111  ogre_shape = new rviz::Shape(rviz::Shape::Cylinder, context_->getSceneManager(), node);
112  double d = 2.0 * static_cast<const shapes::Cylinder*>(s)->radius;
113  double z = static_cast<const shapes::Cylinder*>(s)->length;
114  ogre_shape->setScale(Ogre::Vector3(d, z, d)); // the shape has z as major axis, but the rendered cylinder has y
115  // as major axis (assuming z is upright);
116  }
117  break;
118  case shapes::MESH:
119  {
120  const shapes::Mesh* mesh = static_cast<const shapes::Mesh*>(s);
121  if (mesh->triangle_count > 0)
122  {
124  ogre_shape = m;
125 
126  Ogre::Vector3 normal(0.0, 0.0, 0.0);
127  for (unsigned int i = 0; i < mesh->triangle_count; ++i)
128  {
129  unsigned int i3 = i * 3;
130  if (mesh->triangle_normals && !mesh->vertex_normals)
131  {
132  normal.x = mesh->triangle_normals[i3];
133  normal.y = mesh->triangle_normals[i3 + 1];
134  normal.z = mesh->triangle_normals[i3 + 2];
135  }
136 
137  for (int k = 0; k < 3; ++k)
138  {
139  unsigned int vi = 3 * mesh->triangles[i3 + k];
140  Ogre::Vector3 v(mesh->vertices[vi], mesh->vertices[vi + 1], mesh->vertices[vi + 2]);
141  if (mesh->vertex_normals)
142  {
143  Ogre::Vector3 n(mesh->vertex_normals[vi], mesh->vertex_normals[vi + 1], mesh->vertex_normals[vi + 2]);
144  m->addVertex(v, n);
145  }
146  else if (mesh->triangle_normals)
147  m->addVertex(v, normal);
148  else
149  m->addVertex(v);
150  }
151  }
152  m->endTriangles();
153  }
154  }
155  break;
156 
157  case shapes::OCTREE:
158  {
159  OcTreeRenderPtr octree(new OcTreeRender(static_cast<const shapes::OcTree*>(s)->octree, octree_voxel_rendering,
160  octree_color_mode, 0u, context_->getSceneManager(), node));
161  octree->setPosition(position);
162  octree->setOrientation(orientation);
163  octree_voxel_grids_.push_back(octree);
164  }
165  break;
166 
167  default:
168  break;
169  }
170 
171  if (ogre_shape)
172  {
173  ogre_shape->setColor(color.r_, color.g_, color.b_, alpha);
174 
175  if (s->type == shapes::CYLINDER)
176  {
177  // in geometric shapes, the z axis of the cylinder is its height;
178  // for the rviz shape, the y axis is the height; we add a transform to fix this
179  static Ogre::Quaternion fix(Ogre::Radian(boost::math::constants::pi<double>() / 2.0),
180  Ogre::Vector3(1.0, 0.0, 0.0));
181  orientation = orientation * fix;
182  }
183 
184  ogre_shape->setPosition(position);
185  ogre_shape->setOrientation(orientation);
186  scene_shapes_.emplace_back(ogre_shape);
187  }
188 }
189 }
d
Definition: setup.py:4
virtual void setOrientation(const Ogre::Quaternion &orientation)
#define NULL
q
ShapeType type
std::size_t size(custom_string const &s)
void addVertex(const Ogre::Vector3 &position)
std::vector< OcTreeRenderPtr > octree_voxel_grids_
Definition: render_shapes.h:79
v
unsigned int * triangles
rviz::DisplayContext * context_
Definition: render_shapes.h:76
virtual void setColor(float r, float g, float b, float a)
double * vertex_normals
virtual void setPosition(const Ogre::Vector3 &position)
unsigned int triangle_count
void renderShape(Ogre::SceneNode *node, const shapes::Shape *s, const Eigen::Affine3d &p, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, const rviz::Color &color, float alpha)
double z
double * vertices
double * triangle_normals
virtual Ogre::SceneManager * getSceneManager() const =0
Mesh * createMeshFromShape(const Shape *shape)
RenderShapes(rviz::DisplayContext *context)
virtual void setScale(const Ogre::Vector3 &scale)
std::vector< std::unique_ptr< rviz::Shape > > scene_shapes_
Definition: render_shapes.h:78


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:19:09