conversions.h
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2013 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * conversions.h
20  *
21  * created on: 30.04.2014
22  *
23  * Author: Henning Deeken <hdeeken@uos.de>,
24  * Sebastian Pütz <spuetz@uos.de>,
25  * Marcel Mrozinski <mmrozins@uos.de>,
26  * Tristan Igelbrink <tigelbri@uos.de>
27  *
28  */
29 
30 #ifndef MESH_MSGS_CONVERSIONS_H_
31 #define MESH_MSGS_CONVERSIONS_H_
32 
33 #include <map>
34 
35 #include <ros/ros.h>
36 #include <ros/console.h>
37 
39 #include <lvr2/io/PointBuffer.hpp>
40 #include <lvr2/io/MeshBuffer.hpp>
43 
44 #include <lvr2/io/Model.hpp>
45 #include <lvr2/io/PLYIO.hpp>
46 #include <lvr2/io/DataStruct.hpp>
47 #include <lvr2/io/ModelFactory.hpp>
48 
49 #include <lvr2/texture/Texture.hpp>
51 
52 #include <std_msgs/String.h>
53 #include <sensor_msgs/PointCloud2.h>
54 #include <sensor_msgs/fill_image.h>
55 
56 #include <mesh_msgs/MeshFaceCluster.h>
57 #include <mesh_msgs/MeshMaterial.h>
58 #include <mesh_msgs/MeshTriangleIndices.h>
59 
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>
69 
71 
72 
74 {
75 
79 
81 {
83  unsigned char r;
84  unsigned char g;
85  unsigned char b;
86  std::vector<unsigned int> faceBuffer;
87 };
88 
89 typedef std::vector <boost::shared_ptr<MaterialGroup>> GroupVector;
91 
92 
93 template<typename CoordType>
94 inline const mesh_msgs::MeshGeometry toMeshGeometry(
97 {
98  mesh_msgs::MeshGeometry mesh_msg;
99  mesh_msg.vertices.reserve(hem.numVertices());
100  mesh_msg.faces.reserve(hem.numFaces());
101 
102  mesh_msg.vertex_normals.reserve(normals.numValues());
103 
104  lvr2::DenseVertexMap<size_t> new_indices;
105  new_indices.reserve(hem.numVertices());
106 
107  size_t k = 0;
108  for(auto vH : hem.vertices())
109  {
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);
115  }
116 
117  for(auto fH : hem.faces())
118  {
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);
125  }
126 
127  for(auto vH : hem.vertices())
128  {
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);
133  }
134 
135  return mesh_msg;
136 }
137 
138 template<typename CoordType>
139 inline const mesh_msgs::MeshGeometryStamped toMeshGeometryStamped(
141  const std::string& frame_id,
142  const std::string& uuid,
144  const ros::Time& stamp = ros::Time::now())
145 {
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;
151  return mesh_msg;
152 }
153 
154 inline const mesh_msgs::MeshVertexCosts toVertexCosts(
155  const lvr2::VertexMap<float>& costs,
156  const size_t num_values,
157  const float default_value)
158 {
159  mesh_msgs::MeshVertexCosts costs_msg;
160  costs_msg.costs.resize(num_values, default_value);
161  for(auto vH : costs){
162  costs_msg.costs[vH.idx()] = costs[vH];
163  }
164  return costs_msg;
165 }
166 
167 inline const mesh_msgs::MeshVertexCostsStamped toVertexCostsStamped(
168  const lvr2::VertexMap<float>& costs,
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,
174  const ros::Time& stamp = ros::Time::now()
175 )
176 {
177  mesh_msgs::MeshVertexCostsStamped mesh_msg;
178  mesh_msg.mesh_vertex_costs = toVertexCosts(costs, num_values, default_value);
179  mesh_msg.uuid = uuid;
180  mesh_msg.type = name;
181  mesh_msg.header.frame_id = frame_id;
182  mesh_msg.header.stamp = stamp;
183  return mesh_msg;
184 }
185 
186 inline const mesh_msgs::MeshVertexCosts toVertexCosts(const lvr2::DenseVertexMap<float>& costs)
187 {
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]);
192  }
193  return costs_msg;
194 }
195 
196 inline const mesh_msgs::MeshVertexCostsStamped toVertexCostsStamped(
197  const lvr2::DenseVertexMap<float>& costs,
198  const std::string& name,
199  const std::string& frame_id,
200  const std::string& uuid,
201  const ros::Time& stamp = ros::Time::now()
202  )
203 {
204  mesh_msgs::MeshVertexCostsStamped mesh_msg;
205  mesh_msg.mesh_vertex_costs = toVertexCosts(costs);
206  mesh_msg.uuid = uuid;
207  mesh_msg.type = name;
208  mesh_msg.header.frame_id = frame_id;
209  mesh_msg.header.stamp = stamp;
210  return mesh_msg;
211 }
212 
213 
215  const lvr2::MeshBufferPtr& buffer,
216  mesh_msgs::MeshGeometry& mesh_geometry
217 );
218 
221  const lvr2::MeshBufferPtr& buffer,
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
227 );
228 
230  const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
231  lvr2::MeshBufferPtr& buffer_ptr
232 );
233 
235  const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
236  lvr2::MeshBuffer& buffer
237 );
238 
240  const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
241  lvr2::MeshBufferPtr& buffer_ptr
242 );
243 
245  const mesh_msgs::MeshGeometry& mesh_geometry,
246  lvr2::MeshBufferPtr& buffer_ptr
247 );
248 
250  const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
251  lvr2::MeshBuffer& buffer
252 );
253 
255  const mesh_msgs::MeshGeometry& mesh_geometry,
256  lvr2::MeshBuffer& buffer
257 );
258 
259 /* TODO
260 void removeDuplicates(lvr2::MeshBuffer& buffer);
261 */
262 
270 bool readMeshBuffer(lvr2::MeshBufferPtr& buffer, string path);
271 
278 bool writeMeshBuffer(lvr2::MeshBufferPtr& mesh, string path);
279 
280 bool fromPointCloud2ToPointBuffer(const sensor_msgs::PointCloud2& cloud, PointBuffer& buffer);
281 
290 void PointBufferToPointCloud2(const lvr2::PointBufferPtr& buffer, std::string frame, sensor_msgs::PointCloud2Ptr& cloud);
291 
301 void PointCloud2ToPointBuffer(const sensor_msgs::PointCloud2Ptr& cloud, lvr2::PointBufferPtr& buffer);
302 
303 
311  const mesh_msgs::MeshGeometry& mesh_geometry,
312  const lvr2::MeshBufferPtr& buffer
313 );
314 
315 } // end namespace
316 
317 #endif /* MESH_MSGS_CONVERSIONS_H_ */
point_cloud2_iterator.h
fill_image.h
PointBuffer.hpp
lvr2::BaseVector< float >
DataStruct.hpp
mesh_msgs_conversions::MaterialGroup::faceBuffer
std::vector< unsigned int > faceBuffer
Definition: conversions.h:86
mesh_msgs_conversions::fromMeshBufferToMeshMessages
bool fromMeshBufferToMeshMessages(const lvr2::MeshBufferPtr &buffer, mesh_msgs::MeshGeometry &mesh_geometry, mesh_msgs::MeshMaterials &mesh_materials, mesh_msgs::MeshVertexColors &mesh_vertex_colors, boost::optional< std::vector< mesh_msgs::MeshTexture > & > texture_cache, std::string mesh_uuid)
Convert lvr2::MeshBuffer to various messages for services.
Definition: conversions.cpp:89
boost::shared_ptr
mesh_msgs_conversions::toMeshGeometry
const mesh_msgs::MeshGeometry toMeshGeometry(const lvr2::HalfEdgeMesh< lvr2::BaseVector< CoordType >> &hem, const lvr2::VertexMap< lvr2::Normal< CoordType >> &normals=lvr2::DenseVertexMap< lvr2::Normal< CoordType >>())
Definition: conversions.h:94
lvr2::VectorMap::numValues
size_t numValues() const final
mesh_msgs_conversions::MaterialGroup
Definition: conversions.h:80
ros.h
lvr2::AttributeMap
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
mesh_msgs_conversions::PointCloud2ToPointBuffer
void PointCloud2ToPointBuffer(const sensor_msgs::PointCloud2Ptr &cloud, lvr2::PointBufferPtr &buffer)
converts pointcloud2 to a newly created Pointerbuffer. Every pointfield is written into its own chann...
Definition: conversions.cpp:742
p
SharedPointer p
lvr2::PointBuffer
mesh_msgs_conversions::MaterialGroup::b
unsigned char b
Definition: conversions.h:85
mesh_msgs_conversions::PointBufferPtr
lvr2::PointBufferPtr PointBufferPtr
Definition: conversions.h:78
BaseMesh.hpp
mesh_msgs_conversions
Definition: conversions.h:73
mesh_msgs_conversions::toMeshGeometryStamped
const mesh_msgs::MeshGeometryStamped toMeshGeometryStamped(const lvr2::HalfEdgeMesh< lvr2::BaseVector< CoordType >> &hem, const std::string &frame_id, const std::string &uuid, const lvr2::VertexMap< lvr2::Normal< CoordType >> &normals=lvr2::DenseVertexMap< lvr2::Normal< CoordType >>(), const ros::Time &stamp=ros::Time::now())
Definition: conversions.h:139
BaseVector.hpp
Texture.hpp
lvr2::VectorMap
console.h
AttrMaps.hpp
lvr2::Normal< CoordType >
mesh_msgs_conversions::MaterialGroup::texture_index
int texture_index
Definition: conversions.h:82
Model.hpp
lvr2::MeshBuffer
mesh_msgs_conversions::PointBufferToPointCloud2
void PointBufferToPointCloud2(const lvr2::PointBufferPtr &buffer, std::string frame, sensor_msgs::PointCloud2Ptr &cloud)
converts lvr2::Pointbuffer to pointcloud2. Every channel is added as a pointfield.
Definition: conversions.cpp:590
mesh_msgs_conversions::fromMeshGeometryToMeshBuffer
bool fromMeshGeometryToMeshBuffer(const mesh_msgs::MeshGeometryConstPtr &mesh_geometry_ptr, lvr2::MeshBufferPtr &buffer_ptr)
Definition: conversions.cpp:229
mesh_msgs_conversions::toVertexCostsStamped
const mesh_msgs::MeshVertexCostsStamped toVertexCostsStamped(const lvr2::VertexMap< float > &costs, const size_t num_values, const float default_value, const std::string &name, const std::string &frame_id, const std::string &uuid, const ros::Time &stamp=ros::Time::now())
Definition: conversions.h:167
mesh_msgs_conversions::toVertexCosts
const mesh_msgs::MeshVertexCosts toVertexCosts(const lvr2::VertexMap< float > &costs, const size_t num_values, const float default_value)
Definition: conversions.h:154
mesh_msgs_conversions::fromPointCloud2ToPointBuffer
bool fromPointCloud2ToPointBuffer(const sensor_msgs::PointCloud2 &cloud, PointBuffer &buffer)
Definition: conversions.cpp:384
mesh_msgs_conversions::fromMeshGeometryMessageToMeshBuffer
bool fromMeshGeometryMessageToMeshBuffer(const mesh_msgs::MeshGeometry &mesh_geometry, const lvr2::MeshBufferPtr &buffer)
Convert mesh_msgs::MeshGeometry to lvr2::MeshBuffer.
Definition: conversions.cpp:538
mesh_msgs_conversions::fromMeshBufferToMeshGeometryMessage
bool fromMeshBufferToMeshGeometryMessage(const lvr2::MeshBufferPtr &buffer, mesh_msgs::MeshGeometry &mesh_geometry)
Definition: conversions.cpp:37
mesh_msgs_conversions::MaterialGroup::g
unsigned char g
Definition: conversions.h:84
ros::Time
mesh_msgs_conversions::writeMeshBuffer
bool writeMeshBuffer(lvr2::MeshBufferPtr &mesh, string path)
Writes a LVR-MeshBufferPointer to a file.
Definition: conversions.cpp:317
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
default_value
def default_value(type_)
ModelFactory.hpp
lvr2::VectorMap::insert
boost::optional< ValueT > insert(HandleT key, const ValueT &value) final
PLYIO.hpp
lvr2::VectorMap::reserve
void reserve(size_t newCap)
mesh_msgs_conversions::MaterialGroupPtr
boost::shared_ptr< MaterialGroup > MaterialGroupPtr
Definition: conversions.h:90
mesh_msgs_conversions::GroupVector
std::vector< boost::shared_ptr< MaterialGroup > > GroupVector
Definition: conversions.h:89
mesh_msgs_conversions::PointBuffer
lvr2::PointBuffer PointBuffer
Definition: conversions.h:77
MeshBuffer.hpp
mesh_msgs_conversions::MaterialGroup::r
unsigned char r
Definition: conversions.h:83
HalfEdgeMesh.hpp
lvr2::HalfEdgeMesh
ros::Time::now
static Time now()
mesh_msgs_conversions::readMeshBuffer
bool readMeshBuffer(lvr2::MeshBufferPtr &buffer, string path)
Creates a LVR-MeshBufferPointer from a file.
Definition: conversions.cpp:301


mesh_msgs_conversions
Author(s): Sebastian Pütz , Henning Deeken
autogenerated on Sun Jan 21 2024 04:06:17