Go to the documentation of this file.
53 #ifndef MESH_VISUAL_HPP
54 #define MESH_VISUAL_HPP
56 #include <mesh_msgs/MeshGeometryStamped.h>
57 #include <mesh_msgs/MeshGeometry.h>
58 #include <mesh_msgs/MeshVertexColorsStamped.h>
59 #include <mesh_msgs/MeshVertexColors.h>
60 #include <mesh_msgs/MeshVertexCostsStamped.h>
61 #include <mesh_msgs/MeshVertexCosts.h>
62 #include <mesh_msgs/MeshMaterialsStamped.h>
63 #include <mesh_msgs/MeshMaterials.h>
64 #include <mesh_msgs/MeshMaterial.h>
65 #include <mesh_msgs/MeshTexture.h>
67 #include <sensor_msgs/Image.h>
72 #include <OGRE/OgreSceneNode.h>
73 #include <OGRE/OgreSceneManager.h>
74 #include <OGRE/OgreManualObject.h>
75 #include <OGRE/OgreEntity.h>
76 #include <OGRE/OgreMaterialManager.h>
77 #include <OGRE/OgreColourValue.h>
132 bool setNormals(
const std::vector<Normal>& normals);
154 bool setVertexCosts(
const std::vector<float>& vertexCosts,
int costColorType);
164 bool setVertexCosts(
const std::vector<float>& vertexCosts,
int costColorType,
float minCost,
float maxCost);
172 bool setMaterials(
const vector<Material>& materials,
const vector<TexCoords>& texCoords);
208 bool showVertexCosts,
bool showTextures,
bool showTexturedFacesOnly);
229 Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors,
bool showVertexCosts,
231 float normalsAlpha,
float normalsScallingFactor);
275 void showWireframe(Ogre::Pass* pass, Ogre::ColourValue wireframeColor,
float wireframeAlpha);
280 void showFaces(Ogre::Pass* pass, Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors);
282 void showNormals(Ogre::Pass* pass, Ogre::ColourValue normalsColor,
float normalsAlpha);
292 float minCost,
float maxCost);
295 const vector<TexCoords>& texCoords);
void enteringNormals(const Geometry &mesh, const vector< Normal > &normals)
void updateNormals(float scallingFactor)
Updates the size of the normals dynamically.
Ogre::ManualObject * m_normals
The manual object to display normals.
void updateMaterial(bool showFaces, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors, bool showVertexCosts, bool showTextures, bool showTexturedFacesOnly)
Updates the visible parts of the mesh depending on input from the rviz display.
void reset()
Clears whole stored data.
bool setVertexColors(const std::vector< Color > &vertexColors)
Extracts data from the ros-messages and creates a colored mesh.
Geometry m_geometry
raw Triangle Mesh
Ogre::PixelFormat getOgrePixelFormatFromRosString(std::string encoding)
bool setGeometry(const Geometry &geometry)
Extracts data from the ros-messages and creates meshes.
Ogre::MaterialPtr m_noTexCluMaterial
The materials of the not textured clusters.
Class to display mesh data in the main panel of rviz.
Ogre::MaterialPtr m_meshTexturedTrianglesMaterial
The material for the textured triangle mesh.
bool addTexture(Texture &texture, uint32_t textureIndex)
Extracts data from the ros-messages and adds textures to the textured mesh.
Ogre::MaterialPtr m_texturedMeshMaterial
Ogre::MaterialPtr m_meshGeneralMaterial
The material for the general mesh.
size_t m_random
Random ID of the created mesh.
bool m_vertex_costs_enabled
Ogre::MaterialPtr m_normalMaterial
The material of the normals.
std::vector< Normal > m_geometryNormals
raw normals
Ogre::ManualObject * m_noTexCluMesh
The manual object to display the not textured parts of the textured mesh.
void setFrameOrientation(const Ogre::Quaternion &orientation)
Sets the orientation of the coordinate frame the message refers to.
size_t m_prefix
First ID of the created mesh.
MeshVisual(rviz::DisplayContext *context, size_t displayID, size_t meshID, size_t randomID)
Constructor.
Ogre::ManualObject * m_texturedMesh
The manual object to display the textured mesh.
bool setVertexCosts(const std::vector< float > &vertexCosts)
Extracts data from the ros-messages and creates a colored mesh with colors calculated from vertex cos...
bool m_vertex_normals_enabled
void updateWireframe(bool showWireframe, Ogre::ColourValue wireframeColor, float wireframeAlpha)
Updates the wireframe dynamically.
std::vector< Ogre::MaterialPtr > m_textureMaterials
The materials of the textures.
bool setMaterials(const vector< Material > &materials, const vector< TexCoords > &texCoords)
Extracts data from the ros-messages and creates a textured mesh.
void enteringTexturedTriangleMesh(const Geometry &mesh, const vector< Material > &meshMaterials, const vector< TexCoords > &texCoords)
Ogre::SceneNode * m_sceneNode
Ogre Scenenode.
void showWireframe(Ogre::Pass *pass, Ogre::ColourValue wireframeColor, float wireframeAlpha)
Enables the wireframe.
float m_normalsScalingFactor
Factor the normal-size is multiplied with.
virtual ~MeshVisual()
Destructor.
bool m_vertex_colors_enabled
void setFramePosition(const Ogre::Vector3 &position)
Sets the pose of the coordinate frame the message refers to.
void enteringTriangleMeshWithVertexCosts(const Geometry &mesh, const vector< float > &vertexCosts, int costColorType)
Ogre::MaterialPtr m_vertexCostMaterial
The material of the mesh with vertex costs.
bool setNormals(const std::vector< Normal > &normals)
Passes the normal data to the mesh visual.
void enteringGeneralTriangleMesh(const Geometry &mesh)
void showTextures(Ogre::Pass *pass)
size_t m_postfix
Second ID of the created mesh.
void showNormals(Ogre::Pass *pass, Ogre::ColourValue normalsColor, float normalsAlpha)
bool m_texture_coords_enabled
std::vector< Ogre::Image > m_images
void showFaces(Ogre::Pass *pass, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors)
void enteringColoredTriangleMesh(const Geometry &mesh, const vector< Color > &vertexColors)
Ogre::ManualObject * m_vertexCostsMesh
The manual object to display the mesh with vertex costs.
Ogre::ColourValue calculateColorFromCost(float cost, int costColorType)
Calculates a color for a given cost value using a spectrum from red to green.
Ogre::ManualObject * m_mesh
The mesh-object to display.
void loadImageIntoTextureMaterial(size_t textureIndex)
rviz::DisplayContext * m_displayContext
The context that contains the display information.
rviz_map_plugin
Author(s): Sebastian Pütz
, Kristin Schmidt , Jan Philipp Vogtherr , Malte kleine Piening
autogenerated on Sun Jan 21 2024 04:06:25