Go to the documentation of this file.
53 #ifndef TEXTURED_MESH_VISUAL_H
54 #define TEXTURED_MESH_VISUAL_H
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>
122 bool setGeometry(
const mesh_msgs::MeshGeometryStamped::ConstPtr& meshMsg);
129 bool setVertexColors(
const mesh_msgs::MeshVertexColorsStamped::ConstPtr& vertexColorsMsg);
136 bool setVertexCosts(
const mesh_msgs::MeshVertexCostsStamped::ConstPtr& vertexCostsMsg,
int costColorType);
138 bool setVertexCosts(
const mesh_msgs::MeshVertexCostsStamped::ConstPtr& vertexCostsMsg,
int costColorType,
139 float minCost,
float maxCost);
146 bool setMaterials(
const mesh_msgs::MeshMaterialsStamped::ConstPtr& materialMsg);
153 bool addTexture(
const mesh_msgs::MeshTexture::ConstPtr& textureMsg);
187 Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors,
bool showVertexCosts,
189 float normalsAlpha,
float normalsScallingFactor);
205 void showWireframe(Ogre::Pass* pass, Ogre::ColourValue wireframeColor,
float wireframeAlpha);
210 void showFaces(Ogre::Pass* pass, Ogre::ColourValue facesColor,
float facesAlpha,
bool useVertexColors);
212 void showNormals(Ogre::Pass* pass, Ogre::ColourValue normalsColor,
float normalsAlpha);
218 const mesh_msgs::MeshVertexColors& vertexColors);
220 const mesh_msgs::MeshVertexCosts& vertexCosts,
int costColorType);
222 const mesh_msgs::MeshVertexCosts& vertexCosts,
int costColorType,
223 float minCost,
float maxCost);
void enteringTriangleMeshWithVertexCosts(const mesh_msgs::MeshGeometry &mesh, const mesh_msgs::MeshVertexCosts &vertexCosts, int costColorType)
void reset()
Clears whole stored data.
Ogre::MaterialPtr m_noTexCluMaterial
The materials of the not textured clusters.
std::string m_meshUuid
Uuid of the currently shown vertex colors.
virtual ~TexturedMeshVisual()
Destructor.
bool m_vertex_costs_enabled
Ogre::SceneNode * m_sceneNode
Ogre Scenenode.
Class to display mesh data in the main panel of rviz.
Ogre::ManualObject * m_normals
The manual object to display normals.
std::string m_materialsUuid
Uuid of the currently shown materials.
void updateNormals(float scallingFactor)
Updates the size of the normals dynamically.
Ogre::PixelFormat getOgrePixelFormatFromRosString(std::string encoding)
void setFrameOrientation(const Ogre::Quaternion &orientation)
Sets the orientation of the coordinate frame the message refers to.
size_t m_random
Random ID of the created mesh.
size_t m_postfix
Second ID of the created mesh.
void enteringNormals(const mesh_msgs::MeshGeometry &mesh)
mesh_msgs::MeshGeometry m_meshMsg
Triangle Mesh contained in the given message.
Ogre::MaterialPtr m_meshTexturedTrianglesMaterial
The material for the textured triangle mesh.
std::vector< Ogre::Image > m_images
rviz::DisplayContext * m_displayContext
The context that contains the display information.
Ogre::ManualObject * m_vertexCostsMesh
The manual object to display the mesh with vertex costs.
void showWireframe(Ogre::Pass *pass, Ogre::ColourValue wireframeColor, float wireframeAlpha)
Enables the wireframe.
void loadImageIntoTextureMaterial(size_t textureIndex)
bool m_texture_coords_enabled
bool m_vertex_normals_enabled
Ogre::MaterialPtr m_meshGeneralMaterial
The material for the general mesh.
Ogre::MaterialPtr m_texturedMeshMaterial
void showNormals(Ogre::Pass *pass, Ogre::ColourValue normalsColor, float normalsAlpha)
void updateMaterial(bool showWireframe, Ogre::ColourValue wireframeColor, float wireframeAlpha, bool showFaces, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors, bool showVertexCosts, bool showTextures, bool showTexturedFacesOnly, bool showNormals, Ogre::ColourValue normalsColor, float normalsAlpha, float normalsScallingFactor)
Updates the visible parts of the mesh depending on input from the rviz display.
std::string m_vertexColorsUuid
Uuid of the currently shown vertex colors.
bool setMaterials(const mesh_msgs::MeshMaterialsStamped::ConstPtr &materialMsg)
Extracts data from the ros-messages and creates a textured mesh.
Ogre::MaterialPtr m_vertexCostMaterial
The material of the mesh with vertex costs.
float m_normalsScalingFactor
Factor the normal-size is multiplied with.
bool addTexture(const mesh_msgs::MeshTexture::ConstPtr &textureMsg)
Extracts data from the ros-messages and adds textures to the textured mesh.
Ogre::MaterialPtr m_normalMaterial
The material of the normals.
bool m_vertex_colors_enabled
void enteringGeneralTriangleMesh(const mesh_msgs::MeshGeometry &mesh)
void enteringColoredTriangleMesh(const mesh_msgs::MeshGeometry &mesh, const mesh_msgs::MeshVertexColors &vertexColors)
void showTextures(Ogre::Pass *pass)
bool setVertexCosts(const mesh_msgs::MeshVertexCostsStamped::ConstPtr &vertexCostsMsg, int costColorType)
Extracts data from the ros-messages and creates a colored mesh with colors calculated from vertex cos...
std::string m_vertexCostsUuid
Uuid of the currently shown vertex costs.
void showFaces(Ogre::Pass *pass, Ogre::ColourValue facesColor, float facesAlpha, bool useVertexColors)
void setFramePosition(const Ogre::Vector3 &position)
Sets the pose of the coordinate frame the message refers to.
Ogre::ManualObject * m_mesh
The mesh-object to display.
TexturedMeshVisual(rviz::DisplayContext *context, size_t displayID, size_t meshID, size_t randomID)
Constructor.
Ogre::ColourValue calculateColorFromCost(float cost, int costColorType)
Calculates a color for a given cost value using a spectrum from red to green.
std::vector< Ogre::MaterialPtr > m_textureMaterials
The materials of the textures.
void enteringTexturedTriangleMesh(const mesh_msgs::MeshGeometry &mesh, const mesh_msgs::MeshMaterials &meshMaterials)
bool setGeometry(const mesh_msgs::MeshGeometryStamped::ConstPtr &meshMsg)
Extracts data from the ros-messages and creates meshes.
Ogre::ManualObject * m_texturedMesh
The manual object to display the textured mesh.
Ogre::ManualObject * m_noTexCluMesh
The manual object to display the not textured parts of the textured mesh.
bool setVertexColors(const mesh_msgs::MeshVertexColorsStamped::ConstPtr &vertexColorsMsg)
Extracts data from the ros-messages and creates a colored mesh.
size_t m_prefix
First ID of the created mesh.
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