Go to the documentation of this file.
53 #ifndef TEXTURED_MESH_DISPLAY_H
54 #define TEXTURED_MESH_DISPLAY_H
58 #include <mesh_msgs/MeshGeometryStamped.h>
59 #include <mesh_msgs/MeshGeometry.h>
60 #include <mesh_msgs/MeshVertexColorsStamped.h>
61 #include <mesh_msgs/MeshVertexColors.h>
62 #include <mesh_msgs/MeshVertexCostsStamped.h>
63 #include <mesh_msgs/MeshVertexCosts.h>
64 #include <mesh_msgs/MeshMaterialsStamped.h>
65 #include <mesh_msgs/MeshMaterials.h>
66 #include <mesh_msgs/MeshMaterial.h>
67 #include <mesh_msgs/MeshTexture.h>
69 #include <sensor_msgs/Image.h>
80 #include <boost/circular_buffer.hpp>
91 class RosTopicProperty;
100 class TexturedMeshVisual;
161 void incomingGeometry(
const mesh_msgs::MeshGeometryStamped::ConstPtr& meshMsg);
234 void cacheVertexCosts(
const mesh_msgs::MeshVertexCostsStamped::ConstPtr costsStamped);
240 void processMessage(
const mesh_msgs::MeshGeometryStamped::ConstPtr& meshMsg);
292 boost::circular_buffer<boost::shared_ptr<TexturedMeshVisual> >
m_meshVisuals;
394 std::map<std::string, const mesh_msgs::MeshVertexCostsStamped::ConstPtr>
m_costCache;
message_filters::Subscriber< mesh_msgs::MeshVertexColorsStamped > m_vertexColorsSubscriber
Subscriber for vertex colors.
rviz::EnumProperty * m_selectVertexCostMap
Property to select different types of vertex cost maps to be shown.
rviz::BoolProperty * m_costUseCustomLimits
Property for using custom limits for cost display.
std::string m_lastUuid
Uuid of the last received message.
void updateMeshBufferSize()
Sets capacity of trianglemesh_visual.
rviz::BoolProperty * m_showWireframe
Property to select the wireframe.
boost::shared_ptr< TexturedMeshVisual > getNewVisual()
Creates a new visual and returns shared pointer.
size_t m_meshCounter
Counter for the meshes.
ros::ServiceClient m_uuidClient
Client to request the UUID.
void onDisable()
Calls unsubscribe() and reset() if display is disabled.
Class to show options in rviz window.
rviz::RosTopicProperty * m_vertexColorsTopic
Property to handle topic for vertex colors.
void updateMaterialAndTextureServices()
Updates the material and texture services.
void fixedFrameChanged()
Sets the fixed frame.
message_filters::Subscriber< mesh_msgs::MeshGeometryStamped > m_meshSubscriber
Subscriber for meshMsg.
boost::shared_ptr< TexturedMeshVisual > getCurrentVisual()
Creates a new visual and returns shared pointer.
tf2_ros::MessageFilter< mesh_msgs::MeshVertexCostsStamped > * m_tfVertexCostsFilter
Messagefilter for vertex costs.
boost::circular_buffer< boost::shared_ptr< TexturedMeshVisual > > m_meshVisuals
Shared pointer to store the created objects of trianglemesh_visual.
rviz::ColorProperty * m_normalsColor
Property to set the color of the normals.
rviz::EnumProperty * m_displayType
Property to select the display type.
void subscribe()
Set the topics to subscribe.
static size_t displayCounter
rviz::FloatProperty * m_facesAlpha
Property to set faces transparency.
rviz::RosTopicProperty * m_vertexCostsTopic
Property to handle topic for vertex cost maps.
rviz::ColorProperty * m_wireframeColor
Property to set wireframe color.
void updateSynchronizer()
Updates the topic synchronizer.
void updateTopic()
Updates the subscribed topic.
message_filters::Cache< mesh_msgs::MeshVertexColorsStamped > * m_colorsSynchronizer
Synchronizer for vertex colors.
void reset()
Clears whole stored data.
void requestMaterials(boost::shared_ptr< TexturedMeshVisual > visual, std::string uuid)
Requests materials from the specified service.
rviz::StringProperty * m_textureServiceName
Property to handle service name for textures.
void incomingVertexColors(const mesh_msgs::MeshVertexColorsStamped::ConstPtr &colorsStamped)
Handler for incoming vertex color messages. Validate data and update mesh.
rviz::BoolProperty * m_facesTriangleColors
Property to use the triangle colors.
void initialServiceCall()
initial service call for UUID & geometry
void unsubscribe()
Unsubscribes all topics.
void onEnable()
Calls subscribe() if display is enabled.
ros::ServiceClient m_vertexColorClient
Client to request the vertex colors.
ros::ServiceClient m_geometryClient
Client to request the geometry.
void updateVertexColorService()
Updates the vertex color service.
rviz::EnumProperty * m_costColorType
Property for selecting the color type for cost display.
rviz::BoolProperty * m_showTexturedFacesOnly
Property to only show textured faces when texturizing is enabled.
void cacheVertexCosts(const mesh_msgs::MeshVertexCostsStamped::ConstPtr costsStamped)
Cache function for vertex cost messages.
rviz::RosTopicProperty * m_meshTopic
Property to handle topic for meshMsg.
rviz::ColorProperty * m_facesColor
Property to set faces color.
tf2_ros::MessageFilter< mesh_msgs::MeshGeometryStamped > * m_tfMeshFilter
Messagefilter for meshMsg.
message_filters::Cache< mesh_msgs::MeshGeometryStamped > * m_meshSynchronizer
Synchronizer for meshMsgs.
void incomingVertexCosts(const mesh_msgs::MeshVertexCostsStamped::ConstPtr &costsStamped)
Handler for incoming vertex cost messages. Validate data and update mesh.
tf2_ros::MessageFilter< mesh_msgs::MeshVertexColorsStamped > * m_tfVertexColorsFilter
Messagefilter for vertex colors.
rviz::StringProperty * m_materialServiceName
Property to handle service name for materials.
void updateMesh()
Updates material for each mesh displayed by trianglemesh_visual.
rviz::IntProperty * m_meshBufferSize
Property to set meshBufferSize.
rviz::FloatProperty * m_costLowerLimit
Property for setting the lower limit of cost display.
size_t m_displayID
DisplayID.
rviz::BoolProperty * m_facesVertexColors
Property to use the vertex colors.
void updateVertexCosts()
Update the vertex costs.
rviz::StringProperty * m_vertexColorServiceName
Property to handle service name for vertexColors.
void incomingGeometry(const mesh_msgs::MeshGeometryStamped::ConstPtr &meshMsg)
Handler for incoming geometry messages. Validate data and update mesh.
TexturedMeshDisplay()
Constructor.
void requestVertexColors(boost::shared_ptr< TexturedMeshVisual > visual, std::string uuid)
Requests vertex colors from the specified service.
rviz::FloatProperty * m_wireframeAlpha
Property to set wireframe transparency.
ros::ServiceClient m_textureClient
Client to request the textures.
rviz::FloatProperty * m_scalingFactor
Property to set the size of the normals.
message_filters::Subscriber< mesh_msgs::MeshVertexCostsStamped > m_vertexCostsSubscriber
Subscriber for vertex costs.
rviz::FloatProperty * m_costUpperLimit
Property for setting the upper limit of cost display.
std::map< std::string, const mesh_msgs::MeshVertexCostsStamped::ConstPtr > m_costCache
Cache for received vertex cost messages.
rviz::BoolProperty * m_showNormals
Property to select the normals.
void initServices()
Initializes the used services.
void processMessage(const mesh_msgs::MeshGeometryStamped::ConstPtr &meshMsg)
Sets data for trianglemesh_visual and updates the mesh.
message_filters::Cache< mesh_msgs::MeshVertexCostsStamped > * m_costsSynchronizer
Synchronizer for vertex costs.
uint32_t m_messagesReceived
Counter for the received messages.
rviz::FloatProperty * m_normalsAlpha
Property to set the transparency of the normals.
void onInitialize()
Initialises all nessessary things to get started.
~TexturedMeshDisplay()
Destructor.
ros::ServiceClient m_materialsClient
Client to request the materials.
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