30 #ifndef MESH_MSGS_CONVERSIONS_H_
31 #define MESH_MSGS_CONVERSIONS_H_
52 #include <std_msgs/String.h>
53 #include <sensor_msgs/PointCloud2.h>
56 #include <mesh_msgs/MeshFaceCluster.h>
57 #include <mesh_msgs/MeshMaterial.h>
58 #include <mesh_msgs/MeshTriangleIndices.h>
60 #include <mesh_msgs/MeshGeometry.h>
61 #include <mesh_msgs/MeshGeometryStamped.h>
62 #include <mesh_msgs/MeshMaterialsStamped.h>
63 #include <mesh_msgs/MeshVertexColors.h>
64 #include <mesh_msgs/MeshVertexColorsStamped.h>
65 #include <mesh_msgs/MeshVertexCostsStamped.h>
66 #include <mesh_msgs/MeshVertexTexCoords.h>
67 #include <mesh_msgs/MeshMaterial.h>
68 #include <mesh_msgs/MeshTexture.h>
89 typedef std::vector <boost::shared_ptr<MaterialGroup>>
GroupVector;
93 template<
typename CoordType>
98 mesh_msgs::MeshGeometry mesh_msg;
99 mesh_msg.vertices.reserve(hem.numVertices());
100 mesh_msg.faces.reserve(hem.numFaces());
102 mesh_msg.vertex_normals.reserve(normals.numValues());
105 new_indices.
reserve(hem.numVertices());
108 for(
auto vH : hem.vertices())
110 new_indices.
insert(vH, k++);
111 const auto& pi = hem.getVertexPosition(vH);
112 geometry_msgs::Point
p;
113 p.x = pi.x;
p.y = pi.y;
p.z = pi.z;
114 mesh_msg.vertices.push_back(
p);
117 for(
auto fH : hem.faces())
119 mesh_msgs::MeshTriangleIndices indices;
120 auto vHs = hem.getVerticesOfFace(fH);
121 indices.vertex_indices[0] = new_indices[vHs[0]];
122 indices.vertex_indices[1] = new_indices[vHs[1]];
123 indices.vertex_indices[2] = new_indices[vHs[2]];
124 mesh_msg.faces.push_back(indices);
127 for(
auto vH : hem.vertices())
129 const auto& n = normals[vH];
130 geometry_msgs::Point v;
131 v.x = n.x; v.y = n.y; v.z = n.z;
132 mesh_msg.vertex_normals.push_back(v);
138 template<
typename CoordType>
141 const std::string& frame_id,
142 const std::string& uuid,
146 mesh_msgs::MeshGeometryStamped mesh_msg;
147 mesh_msg.mesh_geometry = toMeshGeometry<CoordType>(hem, normals);
148 mesh_msg.uuid = uuid;
149 mesh_msg.header.frame_id = frame_id;
150 mesh_msg.header.stamp = stamp;
156 const size_t num_values,
157 const float default_value)
159 mesh_msgs::MeshVertexCosts costs_msg;
161 for(
auto vH : costs){
162 costs_msg.costs[vH.idx()] = costs[vH];
169 const size_t num_values,
170 const float default_value,
171 const std::string& name,
172 const std::string& frame_id,
173 const std::string& uuid,
177 mesh_msgs::MeshVertexCostsStamped mesh_msg;
179 mesh_msg.uuid = uuid;
180 mesh_msg.type = name;
181 mesh_msg.header.frame_id = frame_id;
182 mesh_msg.header.stamp = stamp;
188 mesh_msgs::MeshVertexCosts costs_msg;
189 costs_msg.costs.reserve(costs.
numValues());
190 for(
auto vH : costs){
191 costs_msg.costs.push_back(costs[vH]);
198 const std::string& name,
199 const std::string& frame_id,
200 const std::string& uuid,
204 mesh_msgs::MeshVertexCostsStamped mesh_msg;
206 mesh_msg.uuid = uuid;
207 mesh_msg.type = name;
208 mesh_msg.header.frame_id = frame_id;
209 mesh_msg.header.stamp = stamp;
216 mesh_msgs::MeshGeometry& mesh_geometry
222 mesh_msgs::MeshGeometry& mesh_geometry,
223 mesh_msgs::MeshMaterials& mesh_materials,
224 mesh_msgs::MeshVertexColors& mesh_vertex_colors,
225 boost::optional<std::vector<mesh_msgs::MeshTexture>&> texture_cache,
226 std::string mesh_uuid
230 const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
235 const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
240 const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
245 const mesh_msgs::MeshGeometry& mesh_geometry,
250 const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
255 const mesh_msgs::MeshGeometry& mesh_geometry,
311 const mesh_msgs::MeshGeometry& mesh_geometry,