1 #ifndef MESH_MSGS_HDF5_H_
2 #define MESH_MSGS_HDF5_H_
9 #include <mesh_msgs/MeshFaceClusterStamped.h>
10 #include <mesh_msgs/GetGeometry.h>
11 #include <mesh_msgs/GetMaterials.h>
12 #include <mesh_msgs/GetTexture.h>
13 #include <mesh_msgs/GetUUIDs.h>
14 #include <mesh_msgs/GetVertexColors.h>
15 #include <mesh_msgs/GetVertexCosts.h>
16 #include <mesh_msgs/GetVertexCostLayers.h>
17 #include <mesh_msgs/GetLabeledClusters.h>
18 #include <label_manager/GetLabelGroups.h>
19 #include <label_manager/GetLabeledClusterGroup.h>
20 #include <label_manager/DeleteLabel.h>
21 #include <sensor_msgs/Image.h>
24 #include <boost/algorithm/string.hpp>
40 bool getVertices(std::vector<float>& vertices, mesh_msgs::MeshGeometryStamped& geometryMsg);
41 bool getFaces(std::vector<uint32_t>& faceIds, mesh_msgs::MeshGeometryStamped& geometryMsg);
42 bool getVertexNormals(std::vector<float>& vertexNormals, mesh_msgs::MeshGeometryStamped& geometryMsg);
44 bool getVertexColors(std::vector<uint8_t>& vertexColors, mesh_msgs::MeshVertexColorsStamped& vertexColorsMsg);
45 bool getVertexCosts(std::vector<float>& vertexCosts, std::string layer, mesh_msgs::MeshVertexCostsStamped& vertexCostsMsg);
49 mesh_msgs::GetUUIDs::Request &req,
50 mesh_msgs::GetUUIDs::Response &res);
52 mesh_msgs::GetGeometry::Request &req,
53 mesh_msgs::GetGeometry::Response &res);
55 mesh_msgs::GetGeometry::Request &req,
56 mesh_msgs::GetGeometry::Response &res);
58 mesh_msgs::GetGeometry::Request &req,
59 mesh_msgs::GetGeometry::Response &res);
61 mesh_msgs::GetGeometry::Request &req,
62 mesh_msgs::GetGeometry::Response &res);
65 mesh_msgs::GetMaterials::Request &req,
66 mesh_msgs::GetMaterials::Response &res);
68 mesh_msgs::GetTexture::Request &req,
69 mesh_msgs::GetTexture::Response &res);
71 mesh_msgs::GetVertexColors::Request &req,
72 mesh_msgs::GetVertexColors::Response &res);
74 mesh_msgs::GetVertexCosts::Request &req,
75 mesh_msgs::GetVertexCosts::Response &res);
77 mesh_msgs::GetVertexCostLayers::Request &req,
78 mesh_msgs::GetVertexCostLayers::Response &res);
82 mesh_msgs::GetLabeledClusters::Request &req,
83 mesh_msgs::GetLabeledClusters::Response &res);