39 #include <geometric_shapes/check_isometry.h>
40 #include <geometric_shapes/mesh_operations.h>
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>
68 scene_shapes_.clear();
69 octree_voxel_grids_.clear();
74 const Ogre::ColourValue& color,
float alpha)
76 rviz_rendering::Shape* ogre_shape =
nullptr;
78 Ogre::Vector3 position(translation.x(), translation.y(), translation.z());
80 Eigen::Quaterniond q(
p.linear());
81 Ogre::Quaternion orientation(q.w(), q.x(), q.y(), q.z());
84 if (s->type == shapes::CONE)
86 std::unique_ptr<shapes::Mesh> m(shapes::createMeshFromShape(
static_cast<const shapes::Cone&
>(*s)));
88 renderShape(node, m.get(),
p, octree_voxel_rendering, octree_color_mode, color, alpha);
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));
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]));
108 case shapes::CYLINDER:
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));
119 const shapes::Mesh* mesh =
static_cast<const shapes::Mesh*
>(s);
120 if (mesh->triangle_count > 0)
125 Ogre::Vector3 normal(0.0, 0.0, 0.0);
126 for (
unsigned int i = 0; i < mesh->triangle_count; ++i)
128 unsigned int i3 = i * 3;
129 if (mesh->triangle_normals && !mesh->vertex_normals)
131 normal.x = mesh->triangle_normals[i3];
132 normal.y = mesh->triangle_normals[i3 + 1];
133 normal.z = mesh->triangle_normals[i3 + 2];
136 for (
int k = 0; k < 3; ++k)
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)
142 Ogre::Vector3 n(mesh->vertex_normals[vi], mesh->vertex_normals[vi + 1], mesh->vertex_normals[vi + 2]);
145 else if (mesh->triangle_normals)
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);
175 ogre_shape->setColor(color);
177 if (s->type == shapes::CYLINDER)
181 static Ogre::Quaternion fix(Ogre::Radian(M_PI / 2.0), Ogre::Vector3(1.0, 0.0, 0.0));
182 orientation = orientation * fix;
185 ogre_shape->setPosition(position);
186 ogre_shape->setOrientation(orientation);
187 scene_shapes_.emplace_back(ogre_shape);
193 for (
const std::unique_ptr<rviz_rendering::Shape>& shape : scene_shapes_)
194 shape->setColor(
r, g, b,
a);
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.
void addVertex(const Ogre::Vector3 &position)
Add a vertex to the mesh (no normal defined). If using this function only (not using addTriangle()) i...
void endTriangles()
Notify that the set of triangles to add is complete. No more triangles can be added,...
Vec3fX< details::Vec3Data< double > > Vector3d