Go to the documentation of this file.
51 #ifndef TRIANGLEMESH_VISUAL_H
52 #define TRIANGLEMESH_VISUAL_H
54 #include <mesh_msgs/TriangleMeshStamped.h>
59 #include <OGRE/OgreSceneNode.h>
60 #include <OGRE/OgreSceneManager.h>
61 #include <OGRE/OgreManualObject.h>
62 #include <OGRE/OgreEntity.h>
63 #include <OGRE/OgreMaterialManager.h>
64 #include <OGRE/OgreColourValue.h>
109 void setMessage(
const mesh_msgs::TriangleMeshStamped::ConstPtr& meshMsg);
143 Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors,
bool useTriangleColors,
145 float normalsScallingFactor);
155 void showWireframe(Ogre::Pass* pass, Ogre::ColourValue wireframeColor,
float wireframeAlpha);
157 void showFaces(Ogre::Pass* pass, Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors);
159 void showNormals(Ogre::Pass* pass, Ogre::ColourValue normalsColor,
float normalsAlpha);
Ogre::MaterialPtr m_normalMaterial
The material of the normals.
bool m_triangle_colors_enabled
Ogre::ManualObject * m_mesh
The mesh-object to display.
bool m_texture_coords_enabled
TriangleMeshVisual(rviz::DisplayContext *context, size_t displayID, size_t meshID, size_t randomID)
Constructor.
void showWireframe(Ogre::Pass *pass, Ogre::ColourValue wireframeColor, float wireframeAlpha)
bool m_hasTextures
Is the mesh textured?
size_t m_prefix
First ID of the created mesh.
rviz::DisplayContext * m_displayContext
The context that contains the display information.
Ogre::MaterialPtr m_meshGeneralMaterial
The material for the general mesh.
void showTextures(Ogre::Pass *pass)
void enteringNormals(const mesh_msgs::TriangleMesh &mesh)
bool m_vertex_colors_enabled
void setFrameOrientation(const Ogre::Quaternion &orientation)
Sets the orientation of the coordinate frame the message refers to.
void reset()
Clears whole stored data.
Ogre::MaterialPtr m_meshColoredTrianglesMaterial
The material for the colored triangle mesh.
size_t m_textureCounter
Counter for textures.
size_t m_postfix
Second ID of the created mesh.
void enteringGeneralTriangleMesh(const mesh_msgs::TriangleMesh &mesh)
float m_normalsScalingFactor
Factor the normal-size is multiplied with.
Ogre::SceneNode * m_sceneNode
Ogre Scenenode.
void setFramePosition(const Ogre::Vector3 &position)
Sets the pose of the coordinate frame the message refers to.
bool m_vertex_normals_enabled
void showNormals(Ogre::Pass *pass, Ogre::ColourValue normalsColor, float normalsAlpha)
Class to display mesh data in the main panel of rviz.
void setMessage(const mesh_msgs::TriangleMeshStamped::ConstPtr &meshMsg)
Extracts data from the ros-messages and creates meshes.
std::map< size_t, Ogre::ColourValue > m_fakeTextures
Map of fake textures (size = 1x1 = only a color)
void enteringColoredTriangleMesh(const mesh_msgs::TriangleMesh &mesh)
void updateMaterial(bool showWireframe, Ogre::ColourValue wireframeColor, float wireframeAlpha, bool showFaces, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors, bool useTriangleColors, bool showTextures, bool showNormals, Ogre::ColourValue normalsColor, float normalsAlpha, float normalsScallingFactor)
Updates the visible parts of the mesh depending on input from the rviz display.
size_t m_random
Random ID of the created mesh.
void updateNormals(float scallingFactor)
Updates the size of the normals dynamically.
void showFaces(Ogre::Pass *pass, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors)
virtual ~TriangleMeshVisual()
Destructor.
rviz_mesh_plugin
Author(s): Sebastian Pütz
, Henning Deeken , Marcel Mrozinski , Kristin Schmidt , Jan Philipp Vogtherr
autogenerated on Fri Feb 12 2021 04:03:57