mesh_client.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
38 
39 #include <curl/curl.h>
40 #include <ros/ros.h>
41 
42 namespace mesh_client
43 {
44 MeshClient::MeshClient(const std::string& server_url, const std::string& server_username,
45  const std::string& server_password, const std::string& mesh_layer)
46  : server_url_(server_url)
47  , server_username_(server_username)
48  , server_password_(server_password)
49  , mesh_layer_(mesh_layer)
50 {
51 }
52 
53 void MeshClient::setBoundingBox(float min_x, float min_y, float min_z, const float max_x, const float max_y,
54  const float max_z)
55 {
56  bounding_box_[0] = min_x;
57  bounding_box_[1] = min_y;
58  bounding_box_[2] = min_z;
59  bounding_box_[3] = max_x;
60  bounding_box_[4] = max_y;
61  bounding_box_[5] = max_z;
62 }
63 
64 void MeshClient::addFilter(std::string channel, float min_value, float max_value)
65 {
66  mesh_filters_[channel] = std::make_pair(min_value, max_value);
67 }
68 
69 std::string MeshClient::buildJson(const std::string& attribute_name)
70 {
71  Json::Value attr;
72  attr["name"] = attribute_name;
73 
74  if (mesh_filters_.size() > 0)
75  {
76  Json::Value filters;
77  for (auto& mesh_filter : mesh_filters_)
78  {
79  Json::Value filter;
80 
81  filter["attribute_name"] = mesh_filter.first;
82  filter["min_val"] = mesh_filter.second.first;
83  filter["max_val"] = mesh_filter.second.second;
84 
85  filters.append(filter);
86  }
87  attr["filters"] = filters;
88  }
89 
90  Json::Value json_bb;
91  json_bb["x_min"] = bounding_box_[0];
92  json_bb["y_min"] = bounding_box_[1];
93  json_bb["z_min"] = bounding_box_[2];
94  json_bb["x_max"] = bounding_box_[3];
95  json_bb["y_max"] = bounding_box_[4];
96  json_bb["z_max"] = bounding_box_[5];
97 
98  Json::Value request;
99  request["boundingbox"] = json_bb;
100  request["attribute"] = attr;
101  request["layer"] = mesh_layer_;
102  Json::FastWriter fast_writer;
103  return fast_writer.write(request);
104 }
105 
106 bool parseByteDataString(std::string string, char& type, unsigned long& size, unsigned long& width, char*& data)
107 {
108  if (string.length() < 10)
109  {
110  return false;
111  }
112 
113  // parse body
114  const char* body = string.c_str();
115  type = body[0]; // one byte for type of message
116  size = *reinterpret_cast<const unsigned long*>(body + 1); // eight bytes for length of message
117  width = *reinterpret_cast<const unsigned long*>(body + 9); // eight bytes for amount of values per element
118  data = reinterpret_cast<char*>(const_cast<char*>(body + 17)); // raw data
119 
120  return true;
121 }
122 
124 {
125  if (float_channels.find("vertices") != float_channels.end())
126  {
127  return float_channels["vertices"];
128  }
129 
130  unique_ptr<std::string> str = requestChannel("vertices");
131 
132  if (str && str->size() > 17)
133  {
134  char type;
135  unsigned long size, width;
136  char* data;
137 
138  ROS_DEBUG_STREAM("Received vertices channel");
139 
140  if (parseByteDataString(*str, type, size, width, data) && type == Type::FLOAT)
141  {
142  float* float_data = reinterpret_cast<float*>(data);
143  auto channel = lvr2::FloatChannel(size, width);
144  memcpy(channel.dataPtr().get(), float_data, size * width * sizeof(float));
145 
146  return channel;
147  }
148  }
149  ROS_ERROR_STREAM("Failed to load vertices channel!");
151 }
152 
154 {
155  if (index_channels.find("face_indices") != index_channels.end())
156  {
157  return index_channels["face_indices"];
158  }
159 
160  unique_ptr<std::string> str = requestChannel("face_indices");
161 
162  if (str && str->size() > 17)
163  {
164  char type;
165  unsigned long size, width;
166  char* data;
167 
168  ROS_DEBUG_STREAM("Received indices channel");
169 
170  if (parseByteDataString(*str, type, size, width, data) && type == Type::UINT)
171  {
172  unsigned int* index_data = reinterpret_cast<unsigned int*>(data);
173  auto channel = lvr2::IndexChannel(size, width);
174  memcpy(channel.dataPtr().get(), index_data, size * width * sizeof(lvr2::Index));
175 
176  return channel;
177  }
178  }
179  ROS_ERROR_STREAM("Failed to load indices channel!");
181 }
182 
184 {
185  float_channels["vertices"] = channel;
186  return true;
187 }
188 
190 {
191  index_channels["face_indices"] = channel;
192  return true;
193 }
194 
195 bool MeshClient::getChannel(const std::string group, const std::string name, lvr2::FloatChannelOptional& channel)
196 {
197  std::cout << "channel " << name << std::endl;
198  if (float_channels.find(name) != float_channels.end())
199  {
200  channel = float_channels[name];
201  return true;
202  }
203 
204  unique_ptr<std::string> str = requestChannel(name);
205 
206  if (str && str->size() > 17)
207  {
208  char type;
209  unsigned long size, width;
210  char* data;
211 
212  ROS_DEBUG_STREAM("Received " << name << " channel");
213 
214  if (parseByteDataString(*str, type, size, width, data) && type == Type::FLOAT)
215  {
216  float* float_data = reinterpret_cast<float*>(data);
217  channel = lvr2::FloatChannel(size, width);
218  memcpy(channel.get().dataPtr().get(), float_data, size * width * sizeof(float));
219  return true;
220  }
221  }
222  ROS_ERROR_STREAM("Failed to load " << name << " channel!");
223  return false;
224 }
225 
226 bool MeshClient::getChannel(const std::string group, const std::string name, lvr2::IndexChannelOptional& channel)
227 {
228  if (index_channels.find(name) != index_channels.end())
229  {
230  channel = index_channels[name];
231  return true;
232  }
233 
234  unique_ptr<std::string> str = requestChannel(name);
235 
236  if (str && str->size() > 17)
237  {
238  char type;
239  unsigned long size, width;
240  char* data;
241 
242  ROS_DEBUG_STREAM("Received " << name << " channel");
243 
244  if (parseByteDataString(*str, type, size, width, data) && type == Type::UINT)
245  {
246  unsigned int* index_data = reinterpret_cast<unsigned int*>(data);
247  channel = lvr2::IndexChannel(size, width);
248  memcpy(channel.get().dataPtr().get(), index_data, size * width * sizeof(lvr2::Index));
249  return true;
250  }
251  }
252  ROS_ERROR_STREAM("Failed to load " << name << " channel!");
253  return false;
254 }
255 
256 bool MeshClient::getChannel(const std::string group, const std::string name, lvr2::UCharChannelOptional& channel)
257 {
258  if (uchar_channels.find(name) != uchar_channels.end())
259  {
260  channel = uchar_channels[name];
261  return true;
262  }
263 
264  unique_ptr<std::string> str = requestChannel(name);
265 
266  if (str && str->size() > 17)
267  {
268  char type;
269  unsigned long size, width;
270  char* data;
271 
272  ROS_DEBUG_STREAM("Received " << name << " channel");
273 
274  if (parseByteDataString(*str, type, size, width, data) && type == Type::UINT)
275  {
276  unsigned char* uchar_data = reinterpret_cast<unsigned char*>(data);
277  channel = lvr2::UCharChannel(size, width);
278  memcpy(channel.get().dataPtr().get(), uchar_data, size * width * sizeof(unsigned char));
279  return true;
280  }
281  }
282  ROS_ERROR_STREAM("Failed to load " << name << " channel!");
283  return false;
284 }
285 
286 bool MeshClient::addChannel(const std::string group, const std::string name, const lvr2::FloatChannel& channel)
287 {
288  float_channels[name] = channel;
289  return true;
290 }
291 
292 bool MeshClient::addChannel(const std::string group, const std::string name, const lvr2::IndexChannel& channel)
293 {
294  index_channels[name] = channel;
295  return true;
296 }
297 
298 bool MeshClient::addChannel(const std::string group, const std::string name, const lvr2::UCharChannel& channel)
299 {
300  uchar_channels[name] = channel;
301  return true;
302 }
303 
304 std::unique_ptr<std::string> MeshClient::requestChannel(std::string channel)
305 {
306  CURL* curl;
307 
308  curl_global_init(CURL_GLOBAL_ALL);
309 
310  curl = curl_easy_init();
311  if (!curl)
312  {
313  curl_global_cleanup();
314  return nullptr;
315  }
316 
317  std::string post_body = buildJson(channel);
318  curl_easy_setopt(curl, CURLOPT_URL, server_url_.c_str());
319 
320  struct curl_slist* list = curl_slist_append(list, "Content-Type: application/json");
321 
322  curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list);
323  curl_easy_setopt(curl, CURLOPT_POSTFIELDS, post_body.c_str());
324  curl_easy_setopt(curl, CURLOPT_HTTPAUTH, CURLAUTH_ANY);
325  std::string usr_pwd = server_username_ + ":" + server_password_;
326  curl_easy_setopt(curl, CURLOPT_USERPWD, usr_pwd.c_str());
327 
328  unique_ptr<std::string> result = std::make_unique<std::string>();
329  curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, writeFunction);
330  curl_easy_setopt(curl, CURLOPT_WRITEDATA, result.get());
331 
332  CURLcode res = curl_easy_perform(curl);
333  if (res != CURLE_OK)
334  {
335  std::cout << "error" << std::endl;
336  curl_easy_cleanup(curl);
337  return nullptr;
338  }
339 
340  curl_easy_cleanup(curl);
341  return result;
342 }
343 
344 } /* namespace mesh_client */
mesh_client::MeshClient::float_channels
std::map< std::string, lvr2::FloatChannel > float_channels
Definition: mesh_client.h:170
mesh_client::parseByteDataString
bool parseByteDataString(std::string string, char &type, unsigned long &size, unsigned long &width, char *&data)
Definition: mesh_client.cpp:106
lvr2::IndexChannelOptional
IndexChannel::Optional IndexChannelOptional
mesh_client::MeshClient::uchar_channels
std::map< std::string, lvr2::UCharChannel > uchar_channels
Definition: mesh_client.h:168
lvr2::UCharChannelOptional
UCharChannel::Optional UCharChannelOptional
mesh_client::MeshClient::setBoundingBox
void setBoundingBox(float min_x, float min_y, float min_z, const float max_x, const float max_y, const float max_z)
sets the Bounding box for the query which is send to the server
Definition: mesh_client.cpp:53
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
mesh_client::MeshClient::addIndices
bool addIndices(const lvr2::IndexChannel &channel_ptr)
Persistence layer interface, Writes the face indices of the mesh to the persistence layer.
Definition: mesh_client.cpp:189
mesh_client::MeshClient::requestChannel
std::unique_ptr< std::string > requestChannel(std::string channel)
Definition: mesh_client.cpp:304
ros.h
mesh_client.h
mesh_client::MeshClient::mesh_filters_
std::map< std::string, std::pair< float, float > > mesh_filters_
Definition: mesh_client.h:178
mesh_client::MeshClient::server_password_
std::string server_password_
Definition: mesh_client.h:174
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
mesh_client::MeshClient::server_url_
std::string server_url_
Definition: mesh_client.h:172
lvr2::FloatChannelOptional
FloatChannel::Optional FloatChannelOptional
lvr2::IndexChannel
Channel< unsigned int > IndexChannel
mesh_client::MeshClient::getIndices
lvr2::IndexChannelOptional getIndices()
Persistence layer interface, Accesses the face indices of the mesh in the persistence layer.
Definition: mesh_client.cpp:153
mesh_client::MeshClient::addChannel
bool addChannel(const std::string group, const std::string name, const lvr2::FloatChannel &channel)
addChannel Writes a float attribute channel from the given group with the given name
Definition: mesh_client.cpp:286
mesh_client::MeshClient::buildJson
std::string buildJson(const std::string &attribute_name)
Builds a JSON string containing the set bounding box and the attribute name and the attribute group.
Definition: mesh_client.cpp:69
mesh_client::MeshClient::mesh_layer_
std::string mesh_layer_
Definition: mesh_client.h:176
mesh_client::MeshClient::MeshClient
MeshClient(const std::string &srv_url, const std::string &server_username, const std::string &server_password, const std::string &mesh_layer)
Constructs a mesh client which receaves.
Definition: mesh_client.cpp:44
mesh_client::MeshClient::bounding_box_
std::array< float, 6 > bounding_box_
Definition: mesh_client.h:177
mesh_client::MeshClient::server_username_
std::string server_username_
Definition: mesh_client.h:173
mesh_client::MeshClient::getVertices
lvr2::FloatChannelOptional getVertices()
Persistence layer interface, Accesses the vertices of the mesh in the persistence layer.
Definition: mesh_client.cpp:123
filter
void filter(lvr2::PointBufferPtr &cloud, lvr2::indexArray &inlier, size_t j)
Channel< float >
lvr2::FloatChannel
Channel< float > FloatChannel
mesh_client::MeshClient::addVertices
bool addVertices(const lvr2::FloatChannel &channel_ptr)
Persistence layer interface, Writes the vertices of the mesh to the persistence layer.
Definition: mesh_client.cpp:183
mesh_client::MeshClient::getChannel
bool getChannel(const std::string group, const std::string name, lvr2::FloatChannelOptional &channel)
getChannel Reads a float attribute channel in the given group with the given name
Definition: mesh_client.cpp:195
lvr2::Index
uint32_t Index
mesh_client::MeshClient::addFilter
void addFilter(std::string channel, float min_value, float max_value)
Definition: mesh_client.cpp:64
mesh_client
Definition: mesh_client.h:50
mesh_client::writeFunction
size_t writeFunction(void *ptr, size_t size, size_t nmemb, std::string *data)
Definition: mesh_client.h:181
mesh_client::MeshClient::index_channels
std::map< std::string, lvr2::IndexChannel > index_channels
Definition: mesh_client.h:169
lvr2::UCharChannel
Channel< unsigned char > UCharChannel


mesh_client
Author(s): Sebastian Pütz , Malte kl. Piening
autogenerated on Thu Jan 25 2024 03:42:42