moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
39 #include <geometric_shapes/check_isometry.h>
40 #include <geometric_shapes/mesh_operations.h>
41 
42 #include <OgreSceneNode.h>
43 #include <OgreSceneManager.h>
44 #include <OgreManualObject.h>
45 #include <OgreMaterialManager.h>
46 #include <rviz_rendering/objects/shape.hpp>
48 #include <rviz_common/display_context.hpp>
49 #include <rviz_default_plugins/robot/robot.hpp>
50 
51 #include <math.h>
52 #include <memory>
53 #include <string>
54 
55 namespace moveit_rviz_plugin
56 {
57 RenderShapes::RenderShapes(rviz_common::DisplayContext* context) : context_(context)
58 {
59 }
60 
62 {
63  clear();
64 }
65 
67 {
68  scene_shapes_.clear();
69  octree_voxel_grids_.clear();
70 }
71 
72 void RenderShapes::renderShape(Ogre::SceneNode* node, const shapes::Shape* s, const Eigen::Isometry3d& p,
73  OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode,
74  const Ogre::ColourValue& color, float alpha)
75 {
76  rviz_rendering::Shape* ogre_shape = nullptr;
77  Eigen::Vector3d translation = p.translation();
78  Ogre::Vector3 position(translation.x(), translation.y(), translation.z());
79  ASSERT_ISOMETRY(p) // unsanitized input, could contain a non-isometry
80  Eigen::Quaterniond q(p.linear());
81  Ogre::Quaternion orientation(q.w(), q.x(), q.y(), q.z());
82 
83  // we don't know how to render cones directly, but we can convert them to a mesh
84  if (s->type == shapes::CONE)
85  {
86  std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(static_cast<const shapes::Cone&>(*s)));
87  if (m)
88  renderShape(node, m.get(), p, octree_voxel_rendering, octree_color_mode, color, alpha);
89  return;
90  }
91 
92  switch (s->type)
93  {
94  case shapes::SPHERE:
95  {
96  ogre_shape = new rviz_rendering::Shape(rviz_rendering::Shape::Sphere, context_->getSceneManager(), node);
97  double d = 2.0 * static_cast<const shapes::Sphere*>(s)->radius;
98  ogre_shape->setScale(Ogre::Vector3(d, d, d));
99  }
100  break;
101  case shapes::BOX:
102  {
103  ogre_shape = new rviz_rendering::Shape(rviz_rendering::Shape::Cube, context_->getSceneManager(), node);
104  const double* sz = static_cast<const shapes::Box*>(s)->size;
105  ogre_shape->setScale(Ogre::Vector3(sz[0], sz[1], sz[2]));
106  }
107  break;
108  case shapes::CYLINDER:
109  {
110  ogre_shape = new rviz_rendering::Shape(rviz_rendering::Shape::Cylinder, context_->getSceneManager(), node);
111  double d = 2.0 * static_cast<const shapes::Cylinder*>(s)->radius;
112  double z = static_cast<const shapes::Cylinder*>(s)->length;
113  ogre_shape->setScale(Ogre::Vector3(d, z, d)); // the shape has z as major axis, but the rendered cylinder has y
114  // as major axis (assuming z is upright);
115  }
116  break;
117  case shapes::MESH:
118  {
119  const shapes::Mesh* mesh = static_cast<const shapes::Mesh*>(s);
120  if (mesh->triangle_count > 0)
121  {
122  rviz_rendering::MeshShape* m = new rviz_rendering::MeshShape(context_->getSceneManager(), node);
123  ogre_shape = m;
124 
125  Ogre::Vector3 normal(0.0, 0.0, 0.0);
126  for (unsigned int i = 0; i < mesh->triangle_count; ++i)
127  {
128  unsigned int i3 = i * 3;
129  if (mesh->triangle_normals && !mesh->vertex_normals)
130  {
131  normal.x = mesh->triangle_normals[i3];
132  normal.y = mesh->triangle_normals[i3 + 1];
133  normal.z = mesh->triangle_normals[i3 + 2];
134  }
135 
136  for (int k = 0; k < 3; ++k)
137  {
138  unsigned int vi = 3 * mesh->triangles[i3 + k];
139  Ogre::Vector3 v(mesh->vertices[vi], mesh->vertices[vi + 1], mesh->vertices[vi + 2]);
140  if (mesh->vertex_normals)
141  {
142  Ogre::Vector3 n(mesh->vertex_normals[vi], mesh->vertex_normals[vi + 1], mesh->vertex_normals[vi + 2]);
143  m->addVertex(v, n);
144  }
145  else if (mesh->triangle_normals)
146  m->addVertex(v, normal);
147  else
148  m->addVertex(v);
149  }
150  }
151  m->endTriangles();
152  }
153  }
154  break;
155 
156  case shapes::OCTREE:
157  {
158  if (octree_voxel_rendering != OCTOMAP_DISABLED)
159  {
160  auto octree = std::make_shared<moveit_rviz_plugin::OcTreeRender>(
161  static_cast<const shapes::OcTree*>(s)->octree, octree_voxel_rendering, octree_color_mode, 0u, node);
162  octree->setPosition(position);
163  octree->setOrientation(orientation);
164  octree_voxel_grids_.push_back(octree);
165  }
166  }
167  break;
168 
169  default:
170  break;
171  }
172 
173  if (ogre_shape)
174  {
175  ogre_shape->setColor(color);
176 
177  if (s->type == shapes::CYLINDER)
178  {
179  // in geometric shapes, the z axis of the cylinder is its height;
180  // for the rviz shape, the y axis is the height; we add a transform to fix this
181  static Ogre::Quaternion fix(Ogre::Radian(M_PI / 2.0), Ogre::Vector3(1.0, 0.0, 0.0));
182  orientation = orientation * fix;
183  }
184 
185  ogre_shape->setPosition(position);
186  ogre_shape->setOrientation(orientation);
187  scene_shapes_.emplace_back(ogre_shape);
188  }
189 }
190 
191 void RenderShapes::updateShapeColors(float r, float g, float b, float a)
192 {
193  for (const std::unique_ptr<rviz_rendering::Shape>& shape : scene_shapes_)
194  shape->setColor(r, g, b, a);
195 }
196 
197 } // namespace moveit_rviz_plugin
void renderShape(Ogre::SceneNode *node, const shapes::Shape *s, const Eigen::Isometry3d &p, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, const Ogre::ColourValue &color, float alpha)
RenderShapes(rviz_common::DisplayContext *context)
void updateShapeColors(float r, float g, float b, float a)
This class allows constructing Ogre shapes manually, from triangle lists.
Definition: mesh_shape.hpp:69
void addVertex(const Ogre::Vector3 &position)
Add a vertex to the mesh (no normal defined). If using this function only (not using addTriangle()) i...
Definition: mesh_shape.cpp:80
void endTriangles()
Notify that the set of triangles to add is complete. No more triangles can be added,...
Definition: mesh_shape.cpp:116
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
p
Definition: pick.py:62
z
Definition: pick.py:66
a
Definition: plan.py:54
r
Definition: plan.py:56
d
Definition: setup.py:4