mesh_msgs_hdf5.h
Go to the documentation of this file.
1 #ifndef MESH_MSGS_HDF5_H_
2 #define MESH_MSGS_HDF5_H_
3 
4 #include <ros/ros.h>
6 
8 
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>
22 #include <sensor_msgs/fill_image.h>
23 
24 #include <boost/algorithm/string.hpp>
25 #include <string>
26 #include <vector>
27 
28 namespace mesh_msgs_hdf5
29 {
30 
32 {
33 
34  public:
35  hdf5_to_msg();
36 
37  protected:
39 
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);
43 
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);
46 
47  // Mesh services
48  bool service_getUUIDs(
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);
63 
65  mesh_msgs::GetMaterials::Request &req,
66  mesh_msgs::GetMaterials::Response &res);
67  bool service_getTexture(
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);
79 
80  // Label manager services
82  mesh_msgs::GetLabeledClusters::Request &req,
83  mesh_msgs::GetLabeledClusters::Response &res);
84 
85  void callback_clusterLabel(const mesh_msgs::MeshFaceClusterStamped::ConstPtr &msg);
86 
87  private:
88 
89  // Mesh message service servers
100 
101  // Mesh message publishers
105 
106  // Label manager services and subs/pubs
109 
110  // ROS
112 
113  // ROS parameter
114  std::string inputFile;
115 
116  std::string mesh_uuid = "mesh";
117 
118 };
119 
120 } // end namespace
121 
122 #endif /* MESH_MSGS_HDF5_H_ */
hdf5_map_io.h
mesh_msgs_hdf5::hdf5_to_msg::getVertexCosts
bool getVertexCosts(std::vector< float > &vertexCosts, std::string layer, mesh_msgs::MeshVertexCostsStamped &vertexCostsMsg)
Definition: mesh_msgs_hdf5.cpp:179
fill_image.h
ros::Publisher
mesh_msgs_hdf5::hdf5_to_msg::node_handle
ros::NodeHandle node_handle
Definition: mesh_msgs_hdf5.h:111
mesh_msgs_hdf5::hdf5_to_msg::service_getVertexCosts
bool service_getVertexCosts(mesh_msgs::GetVertexCosts::Request &req, mesh_msgs::GetVertexCosts::Response &res)
Definition: mesh_msgs_hdf5.cpp:388
mesh_msgs_hdf5::hdf5_to_msg::sub_cluster_label_
ros::Subscriber sub_cluster_label_
Definition: mesh_msgs_hdf5.h:108
mesh_msgs_hdf5::hdf5_to_msg::srv_get_geometry_
ros::ServiceServer srv_get_geometry_
Definition: mesh_msgs_hdf5.h:91
mesh_msgs_hdf5::hdf5_to_msg::pub_vertex_colors_
ros::Publisher pub_vertex_colors_
Definition: mesh_msgs_hdf5.h:103
mesh_msgs_hdf5::hdf5_to_msg::service_getMaterials
bool service_getMaterials(mesh_msgs::GetMaterials::Request &req, mesh_msgs::GetMaterials::Response &res)
Definition: mesh_msgs_hdf5.cpp:257
mesh_msgs_hdf5::hdf5_to_msg::srv_get_vertex_colors_
ros::ServiceServer srv_get_vertex_colors_
Definition: mesh_msgs_hdf5.h:97
ros.h
mesh_msgs_hdf5::hdf5_to_msg::service_getUUIDs
bool service_getUUIDs(mesh_msgs::GetUUIDs::Request &req, mesh_msgs::GetUUIDs::Response &res)
Definition: mesh_msgs_hdf5.cpp:195
mesh_msgs_hdf5::hdf5_to_msg::getVertexNormals
bool getVertexNormals(std::vector< float > &vertexNormals, mesh_msgs::MeshGeometryStamped &geometryMsg)
Definition: mesh_msgs_hdf5.cpp:134
mesh_msgs_hdf5::hdf5_to_msg::hdf5_to_msg
hdf5_to_msg()
Definition: mesh_msgs_hdf5.cpp:6
mesh_msgs_hdf5::hdf5_to_msg::service_getVertexCostLayers
bool service_getVertexCostLayers(mesh_msgs::GetVertexCostLayers::Request &req, mesh_msgs::GetVertexCostLayers::Response &res)
Definition: mesh_msgs_hdf5.cpp:398
simple_action_server.h
mesh_msgs_hdf5::hdf5_to_msg::loadAndPublishGeometry
void loadAndPublishGeometry()
Definition: mesh_msgs_hdf5.cpp:51
mesh_msgs_hdf5::hdf5_to_msg
Definition: mesh_msgs_hdf5.h:31
mesh_msgs_hdf5::hdf5_to_msg::srv_get_geometry_vertex_normals_
ros::ServiceServer srv_get_geometry_vertex_normals_
Definition: mesh_msgs_hdf5.h:94
ros::ServiceServer
mesh_msgs_hdf5::hdf5_to_msg::srv_get_labeled_clusters_
ros::ServiceServer srv_get_labeled_clusters_
Definition: mesh_msgs_hdf5.h:107
mesh_msgs_hdf5::hdf5_to_msg::getVertices
bool getVertices(std::vector< float > &vertices, mesh_msgs::MeshGeometryStamped &geometryMsg)
Definition: mesh_msgs_hdf5.cpp:94
mesh_msgs_hdf5::hdf5_to_msg::srv_get_uuids_
ros::ServiceServer srv_get_uuids_
Definition: mesh_msgs_hdf5.h:90
mesh_msgs_hdf5::hdf5_to_msg::srv_get_vertex_costs_
ros::ServiceServer srv_get_vertex_costs_
Definition: mesh_msgs_hdf5.h:98
mesh_msgs_hdf5::hdf5_to_msg::pub_vertex_costs_
ros::Publisher pub_vertex_costs_
Definition: mesh_msgs_hdf5.h:104
mesh_msgs_hdf5::hdf5_to_msg::srv_get_vertex_cost_layers_
ros::ServiceServer srv_get_vertex_cost_layers_
Definition: mesh_msgs_hdf5.h:99
mesh_msgs_hdf5::hdf5_to_msg::service_getLabeledClusters
bool service_getLabeledClusters(mesh_msgs::GetLabeledClusters::Request &req, mesh_msgs::GetLabeledClusters::Response &res)
Definition: mesh_msgs_hdf5.cpp:408
mesh_msgs_hdf5::hdf5_to_msg::srv_get_materials_
ros::ServiceServer srv_get_materials_
Definition: mesh_msgs_hdf5.h:95
mesh_msgs_hdf5::hdf5_to_msg::srv_get_geometry_vertices_
ros::ServiceServer srv_get_geometry_vertices_
Definition: mesh_msgs_hdf5.h:92
mesh_msgs_hdf5::hdf5_to_msg::service_getVertexColors
bool service_getVertexColors(mesh_msgs::GetVertexColors::Request &req, mesh_msgs::GetVertexColors::Response &res)
Definition: mesh_msgs_hdf5.cpp:377
mesh_msgs_hdf5::hdf5_to_msg::getFaces
bool getFaces(std::vector< uint32_t > &faceIds, mesh_msgs::MeshGeometryStamped &geometryMsg)
Definition: mesh_msgs_hdf5.cpp:114
mesh_msgs_hdf5::hdf5_to_msg::inputFile
std::string inputFile
Definition: mesh_msgs_hdf5.h:114
mesh_msgs_hdf5::hdf5_to_msg::service_getTexture
bool service_getTexture(mesh_msgs::GetTexture::Request &req, mesh_msgs::GetTexture::Response &res)
Definition: mesh_msgs_hdf5.cpp:346
mesh_msgs_hdf5::hdf5_to_msg::getVertexColors
bool getVertexColors(std::vector< uint8_t > &vertexColors, mesh_msgs::MeshVertexColorsStamped &vertexColorsMsg)
Definition: mesh_msgs_hdf5.cpp:154
mesh_msgs_hdf5::hdf5_to_msg::service_getGeometryVertexNormals
bool service_getGeometryVertexNormals(mesh_msgs::GetGeometry::Request &req, mesh_msgs::GetGeometry::Response &res)
Definition: mesh_msgs_hdf5.cpp:246
mesh_msgs_hdf5::hdf5_to_msg::srv_get_texture_
ros::ServiceServer srv_get_texture_
Definition: mesh_msgs_hdf5.h:96
mesh_msgs_hdf5::hdf5_to_msg::service_getGeometryVertices
bool service_getGeometryVertices(mesh_msgs::GetGeometry::Request &req, mesh_msgs::GetGeometry::Response &res)
Definition: mesh_msgs_hdf5.cpp:224
mesh_msgs_hdf5::hdf5_to_msg::srv_get_geometry_faces_
ros::ServiceServer srv_get_geometry_faces_
Definition: mesh_msgs_hdf5.h:93
mesh_msgs_hdf5::hdf5_to_msg::service_getGeometryFaces
bool service_getGeometryFaces(mesh_msgs::GetGeometry::Request &req, mesh_msgs::GetGeometry::Response &res)
Definition: mesh_msgs_hdf5.cpp:235
mesh_msgs_hdf5::hdf5_to_msg::callback_clusterLabel
void callback_clusterLabel(const mesh_msgs::MeshFaceClusterStamped::ConstPtr &msg)
Definition: mesh_msgs_hdf5.cpp:440
mesh_msgs_hdf5::hdf5_to_msg::service_getGeometry
bool service_getGeometry(mesh_msgs::GetGeometry::Request &req, mesh_msgs::GetGeometry::Response &res)
Definition: mesh_msgs_hdf5.cpp:203
mesh_msgs_hdf5::hdf5_to_msg::mesh_uuid
std::string mesh_uuid
Definition: mesh_msgs_hdf5.h:116
mesh_msgs_hdf5
Definition: mesh_msgs_hdf5.h:28
mesh_msgs_hdf5::hdf5_to_msg::pub_geometry_
ros::Publisher pub_geometry_
Definition: mesh_msgs_hdf5.h:102
ros::NodeHandle
ros::Subscriber


mesh_msgs_hdf5
Author(s): Sebastian Pütz
autogenerated on Sun Jan 21 2024 04:06:20