41 #include <OgreSceneNode.h> 42 #include <OgreSceneManager.h> 43 #include <OgreManualObject.h> 44 #include <OgreMaterialManager.h> 52 #include <boost/lexical_cast.hpp> 53 #include <boost/math/constants/constants.hpp> 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());
89 renderShape(node, m.get(), p, octree_voxel_rendering, octree_color_mode, color, alpha);
99 ogre_shape->
setScale(Ogre::Vector3(d, d, d));
106 ogre_shape->
setScale(Ogre::Vector3(sz[0], sz[1], sz[2]));
114 ogre_shape->
setScale(Ogre::Vector3(d, z, d));
126 Ogre::Vector3 normal(0.0, 0.0, 0.0);
129 unsigned int i3 = i * 3;
137 for (
int k = 0; k < 3; ++k)
139 unsigned int vi = 3 * mesh->
triangles[i3 + k];
159 OcTreeRenderPtr octree(
new OcTreeRender(static_cast<const shapes::OcTree*>(s)->octree, octree_voxel_rendering,
161 octree->setPosition(position);
162 octree->setOrientation(orientation);
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;
virtual void setOrientation(const Ogre::Quaternion &orientation)
std::size_t size(custom_string const &s)
void addVertex(const Ogre::Vector3 &position)
std::vector< OcTreeRenderPtr > octree_voxel_grids_
rviz::DisplayContext * context_
virtual void setColor(float r, float g, float b, float a)
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 * 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_