cola_encoder.cpp
Go to the documentation of this file.
1 /*
2  * @brief cola_encoder encodes service requests to cola telegrams, parses cola responses and
3  * converts them to service responses.
4  *
5  * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim
6  * Copyright (C) 2019 SICK AG, Waldkirch
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13  *
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  *
20  * All rights reserved.
21  *
22  * Redistribution and use in source and binary forms, with or without
23  * modification, are permitted provided that the following conditions are met:
24  *
25  * * Redistributions of source code must retain the above copyright
26  * notice, this list of conditions and the following disclaimer.
27  * * Redistributions in binary form must reproduce the above copyright
28  * notice, this list of conditions and the following disclaimer in the
29  * documentation and/or other materials provided with the distribution.
30  * * Neither the name of SICK AG nor the names of its
31  * contributors may be used to endorse or promote products derived from
32  * this software without specific prior written permission
33  * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
34  * contributors may be used to endorse or promote products derived from
35  * this software without specific prior written permission
36  *
37  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
38  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
39  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
40  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
41  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
42  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
43  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
44  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
45  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
46  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
47  * POSSIBILITY OF SUCH DAMAGE.
48  *
49  * Authors:
50  * Michael Lehning <michael.lehning@lehning.de>
51  *
52  * Copyright 2019 SICK AG
53  * Copyright 2019 Ing.-Buero Dr. Michael Lehning
54  *
55  */
56 #include "sick_scan/ros_wrapper.h"
57 #include "sick_scan/cola_encoder.h"
58 
64 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevSetLidarConfigSrv::Request& service_request)
65 {
66  std::stringstream cola_ascii;
67  cola_ascii << "sMN DevSetLidarConfig";
68  cola_ascii << std::showpos << " +" << service_request.index << " +" << service_request.minrange << " +" << service_request.maxrange << " " << service_request.minangle << " " << service_request.maxangle
69  << " " << service_request.x << " " << service_request.y << " " << service_request.yaw
70  << std::noshowpos << " " << (service_request.upsidedown?1:0)
71  << " +" << service_request.ip.length() << " " << service_request.ip << " +" << service_request.port
72  << " " << service_request.interfacetype << " " << service_request.maplayer << " " << (service_request.active?1:0);
73  return cola_ascii.str();
74 }
75 
82 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevSetLidarConfigSrv::Response& service_response)
83 {
84  service_response.set = false;
85  service_response.executed = false;
86  if(cola_response.parameter.size() == 2)
87  {
88  service_response.set = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
89  service_response.executed = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
90  }
91  return service_response.set;
92 }
93 
99 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevGetLidarConfigSrv::Request& service_request)
100 {
101  std::stringstream cola_ascii;
102  cola_ascii << "sMN DevGetLidarConfig";
103  cola_ascii << std::showpos << " " << service_request.scannerindex;
104  return cola_ascii.str();
105 }
106 
113 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevGetLidarConfigSrv::Response& service_response)
114 {
115  if(cola_response.parameter.size() == 13)
116  {
117  service_response.minrange = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
118  service_response.maxrange = sick_scan::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0U);
119  service_response.minangle = sick_scan::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
120  service_response.maxangle = sick_scan::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0);
121  service_response.x = sick_scan::ColaParser::convertColaArg(cola_response.parameter[4], -1, 0);
122  service_response.y = sick_scan::ColaParser::convertColaArg(cola_response.parameter[5], -1, 0);
123  service_response.yaw = sick_scan::ColaParser::convertColaArg(cola_response.parameter[6], -1, 0);
124  service_response.upsidedown = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[7], false);
125  service_response.ip = cola_response.parameter[8];
126  service_response.port = sick_scan::ColaParser::convertColaArg(cola_response.parameter[9], -1, 0U);
127  service_response.interfacetype = sick_scan::ColaParser::convertColaArg(cola_response.parameter[10], -1, 0U);
128  service_response.maplayer = sick_scan::ColaParser::convertColaArg(cola_response.parameter[11], -1, 0U);
129  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[12], false);
130  return true;
131  }
132  if(cola_response.parameter.size() >= 14)
133  {
134  service_response.minrange = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
135  service_response.maxrange = sick_scan::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0U);
136  service_response.minangle = sick_scan::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
137  service_response.maxangle = sick_scan::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0);
138  service_response.x = sick_scan::ColaParser::convertColaArg(cola_response.parameter[4], -1, 0);
139  service_response.y = sick_scan::ColaParser::convertColaArg(cola_response.parameter[5], -1, 0);
140  service_response.yaw = sick_scan::ColaParser::convertColaArg(cola_response.parameter[6], -1, 0);
141  service_response.upsidedown = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[7], false);
142  int n = 8;
143  int ip_strlen = sick_scan::ColaParser::convertColaArg(cola_response.parameter[n++], 10, 0U);
144  service_response.ip = cola_response.parameter[n++];
145  while (n + 4 < cola_response.parameter.size() && service_response.ip.length() < ip_strlen)
146  {
147  service_response.ip = service_response.ip + " " + cola_response.parameter[n++];
148  }
149  service_response.port = sick_scan::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
150  service_response.interfacetype = sick_scan::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
151  service_response.maplayer = sick_scan::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
152  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[n++], false);
153  return true;
154  }
155  return false;
156 }
157 
163 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetMapSrv::Request& service_request)
164 {
165  std::stringstream cola_ascii;
166  cola_ascii << "sMN LocSetMap +" << service_request.mapfilename.length() << " " << service_request.mapfilename;
167  return cola_ascii.str();
168 }
169 
176 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetMapSrv::Response& service_response)
177 {
178  service_response.set = false;
179  service_response.executed = false;
180  if(cola_response.parameter.size() == 2)
181  {
182  service_response.set = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
183  service_response.executed = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
184  }
185  return service_response.set;
186 }
187 
193 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocMapSrv::Request& service_request)
194 {
195  std::stringstream cola_ascii;
196  cola_ascii << "sRN LocMap";
197  return cola_ascii.str();
198 }
199 
206 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocMapSrv::Response& service_response)
207 {
208  service_response.success = false;
209  if(cola_response.parameter.size() == 1)
210  {
211  service_response.map = cola_response.parameter[0];
212  service_response.success = true;
213  }
214  if(cola_response.parameter.size() > 1)
215  {
216  int str_len = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
217  service_response.map = cola_response.parameter[1];
218  for (int n = 2; n < cola_response.parameter.size() && service_response.map.length() < str_len; n++)
219  {
220  service_response.map = service_response.map + " " + cola_response.parameter[n];
221  }
222  service_response.success = true;
223  }
224  return service_response.success;
225 }
226 
232 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocMapStateSrv::Request& service_request)
233 {
234  std::stringstream cola_ascii;
235  cola_ascii << "sRN LocMapState";
236  return cola_ascii.str();
237 }
238 
245 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocMapStateSrv::Response& service_response)
246 {
247  service_response.success = false;
248  if(!cola_response.parameter.empty())
249  {
250  service_response.mapstate = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
251  service_response.success = true;
252  }
253  return service_response.success;
254 }
255 
261 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocInitializePoseSrv::Request& service_request)
262 {
263  std::stringstream cola_ascii;
264  cola_ascii << "sMN LocInitializePose";
265  cola_ascii << std::showpos << " " << service_request.x << " " << service_request.y << " " << service_request.yaw << " +" << service_request.sigmatranslation;
266  return cola_ascii.str();
267 }
268 
275 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocInitializePoseSrv::Response& service_response)
276 {
277  service_response.success = false;
278  if(!cola_response.parameter.empty())
279  {
280  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
281  }
282  return service_response.success;
283 }
284 
290 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocInitialPoseSrv::Request& service_request)
291 {
292  std::stringstream cola_ascii;
293  cola_ascii << "sRN LocInitialPose";
294  return cola_ascii.str();
295 }
296 
303 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocInitialPoseSrv::Response& service_response)
304 {
305  service_response.success = false;
306  if(cola_response.parameter.size() >= 4)
307  {
308  service_response.x = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
309  service_response.y = sick_scan::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0);
310  service_response.yaw = sick_scan::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
311  service_response.sigmatranslation = sick_scan::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0U);
312  service_response.success = true;
313  }
314  return service_response.success;
315 }
316 
317 
323 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetReflectorsForSupportActiveSrv::Request& service_request)
324 {
325  std::stringstream cola_ascii;
326  cola_ascii << "sMN LocSetReflectorsForSupportActive";
327  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
328  return cola_ascii.str();
329 }
330 
337 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetReflectorsForSupportActiveSrv::Response& service_response)
338 {
339  service_response.success = false;
340  if(!cola_response.parameter.empty())
341  {
342  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
343  }
344  return service_response.success;
345 }
346 
352 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocReflectorsForSupportActiveSrv::Request& service_request)
353 {
354  std::stringstream cola_ascii;
355  cola_ascii << "sRN LocReflectorsForSupportActive";
356  return cola_ascii.str();
357 }
358 
365 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocReflectorsForSupportActiveSrv::Response& service_response)
366 {
367  service_response.success = false;
368  if(!cola_response.parameter.empty())
369  {
370  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
371  service_response.success = true;
372  }
373  return service_response.success;
374 }
375 
381 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetOdometryActiveSrv::Request& service_request)
382 {
383  std::stringstream cola_ascii;
384  cola_ascii << "sMN LocSetOdometryActive";
385  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
386  return cola_ascii.str();
387 }
388 
395 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetOdometryActiveSrv::Response& service_response)
396 {
397  service_response.set = false;
398  service_response.executed = false;
399  if(!cola_response.parameter.empty())
400  {
401  service_response.set = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
402  service_response.executed = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
403  }
404  return service_response.set;
405 }
406 
412 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocOdometryActiveSrv::Request& service_request)
413 {
414  std::stringstream cola_ascii;
415  cola_ascii << "sRN LocOdometryActive";
416  return cola_ascii.str();
417 }
418 
425 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocOdometryActiveSrv::Response& service_response)
426 {
427  service_response.success = false;
428  if(!cola_response.parameter.empty())
429  {
430  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
431  service_response.success = true;
432  }
433  return service_response.success;
434 }
435 
441 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetOdometryPortSrv::Request& service_request)
442 {
443  std::stringstream cola_ascii;
444  cola_ascii << "sMN LocSetOdometryPort";
445  cola_ascii << " +" << service_request.port;
446  return cola_ascii.str();
447 }
448 
455 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetOdometryPortSrv::Response& service_response)
456 {
457  service_response.set = false;
458  if(!cola_response.parameter.empty())
459  {
460  service_response.set = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
461  service_response.executed = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
462  }
463  return service_response.set;
464 }
465 
471 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocOdometryPortSrv::Request& service_request)
472 {
473  std::stringstream cola_ascii;
474  cola_ascii << "sRN LocOdometryPort";
475  return cola_ascii.str();
476 }
477 
484 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocOdometryPortSrv::Response& service_response)
485 {
486  service_response.success = false;
487  if(!cola_response.parameter.empty())
488  {
489  service_response.port = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
490  service_response.success = true;
491  }
492  return service_response.success;
493 }
494 
500 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetOdometryRestrictYMotionSrv::Request& service_request)
501 {
502  std::stringstream cola_ascii;
503  cola_ascii << "sMN LocSetOdometryRestrictYMotion";
504  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
505  return cola_ascii.str();
506 }
507 
514 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetOdometryRestrictYMotionSrv::Response& service_response)
515 {
516  service_response.success = false;
517  if(!cola_response.parameter.empty())
518  {
519  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
520  }
521  return service_response.success;
522 }
523 
529 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocOdometryRestrictYMotionSrv::Request& service_request)
530 {
531  std::stringstream cola_ascii;
532  cola_ascii << "sRN LocOdometryRestrictYMotion";
533  return cola_ascii.str();
534 }
535 
542 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocOdometryRestrictYMotionSrv::Response& service_response)
543 {
544  service_response.success = false;
545  if(!cola_response.parameter.empty())
546  {
547  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
548  service_response.success = true;
549  }
550  return service_response.success;
551 }
552 
558 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetAutoStartActiveSrv::Request& service_request)
559 {
560  std::stringstream cola_ascii;
561  cola_ascii << "sMN LocSetAutoStartActive";
562  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
563  return cola_ascii.str();
564 }
565 
572 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetAutoStartActiveSrv::Response& service_response)
573 {
574  service_response.success = false;
575  if(!cola_response.parameter.empty())
576  {
577  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
578  }
579  return service_response.success;
580 }
581 
587 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocAutoStartActiveSrv::Request& service_request)
588 {
589  std::stringstream cola_ascii;
590  cola_ascii << "sRN LocAutoStartActive";
591  return cola_ascii.str();
592 }
593 
600 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocAutoStartActiveSrv::Response& service_response)
601 {
602  service_response.success = false;
603  if(!cola_response.parameter.empty())
604  {
605  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
606  service_response.success = true;
607  }
608  return service_response.success;
609 }
610 
616 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetAutoStartSavePoseIntervalSrv::Request& service_request)
617 {
618  std::stringstream cola_ascii;
619  cola_ascii << "sMN LocSetAutoStartSavePoseInterval";
620  cola_ascii << std::showpos << " " << service_request.interval;
621  return cola_ascii.str();
622 }
623 
630 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetAutoStartSavePoseIntervalSrv::Response& service_response)
631 {
632  service_response.success = false;
633  if(!cola_response.parameter.empty())
634  {
635  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
636  }
637  return service_response.success;
638 }
639 
645 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocAutoStartSavePoseIntervalSrv::Request& service_request)
646 {
647  std::stringstream cola_ascii;
648  cola_ascii << "sRN LocAutoStartSavePoseInterval";
649  return cola_ascii.str();
650 }
651 
658 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocAutoStartSavePoseIntervalSrv::Response& service_response)
659 {
660  service_response.success = false;
661  if(!cola_response.parameter.empty())
662  {
663  service_response.interval = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
664  service_response.success = true;
665  }
666  return service_response.success;
667 }
668 
674 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSetRingBufferRecordingActiveSrv::Request& service_request)
675 {
676  std::stringstream cola_ascii;
677  cola_ascii << "sMN LocSetRingBufferRecordingActive";
678  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
679  return cola_ascii.str();
680 }
681 
688 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSetRingBufferRecordingActiveSrv::Response& service_response)
689 {
690  service_response.success = false;
691  if(!cola_response.parameter.empty())
692  {
693  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
694  }
695  return service_response.success;
696 }
697 
703 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocRingBufferRecordingActiveSrv::Request& service_request)
704 {
705  std::stringstream cola_ascii;
706  cola_ascii << "sRN LocRingBufferRecordingActive";
707  return cola_ascii.str();
708 }
709 
716 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocRingBufferRecordingActiveSrv::Response& service_response)
717 {
718  service_response.success = false;
719  if(!cola_response.parameter.empty())
720  {
721  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
722  service_response.success = true;
723  }
724  return service_response.success;
725 }
726 
732 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevGetLidarIdentSrv::Request& service_request)
733 {
734  std::stringstream cola_ascii;
735  cola_ascii << "sMN DevGetLidarIdent";
736  cola_ascii << std::showpos << " " << service_request.index;
737  return cola_ascii.str();
738 }
739 
746 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevGetLidarIdentSrv::Response& service_response)
747 {
748  service_response.success = false;
749  if(cola_response.parameter.size() == 1)
750  {
751  service_response.scannerident = cola_response.parameter[0];
752  service_response.success = true;
753  }
754  if(cola_response.parameter.size() > 1)
755  {
756  int str_len = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
757  service_response.scannerident = cola_response.parameter[1];
758  for (int n = 2; n < cola_response.parameter.size() && service_response.scannerident.length() < str_len; n++)
759  {
760  service_response.scannerident = service_response.scannerident + " " + cola_response.parameter[n];
761  }
762  service_response.success = true;
763  }
764  return service_response.success;
765 }
766 
772 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevGetLidarStateSrv::Request& service_request)
773 {
774  std::stringstream cola_ascii;
775  cola_ascii << "sMN DevGetLidarState";
776  cola_ascii << std::showpos << " " << service_request.index;
777  return cola_ascii.str();
778 }
779 
786 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevGetLidarStateSrv::Response& service_response)
787 {
788  service_response.success = false;
789  if(cola_response.parameter.size() >= 3)
790  {
791  service_response.devicestatus = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
792  service_response.deviceconnected = sick_scan::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0);
793  service_response.receivingdata = sick_scan::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
794  service_response.success = true;
795  }
796  return service_response.success;
797 }
798 
804 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickGetSoftwareVersionSrv::Request& service_request)
805 {
806  std::stringstream cola_ascii;
807  cola_ascii << "sMN GetSoftwareVersion";
808  return cola_ascii.str();
809 }
810 
817 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickGetSoftwareVersionSrv::Response& service_response)
818 {
819  service_response.success = false;
820  if(cola_response.parameter.size() == 1)
821  {
822  service_response.version = cola_response.parameter[0];
823  service_response.success = true;
824  }
825  if(cola_response.parameter.size() > 1)
826  {
827  int str_len = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
828  service_response.version = cola_response.parameter[1];
829  for (int n = 2; n < cola_response.parameter.size() && service_response.version.length() < str_len; n++)
830  {
831  service_response.version = service_response.version + " " + cola_response.parameter[n];
832  }
833  service_response.success = true;
834  }
835  return service_response.success;
836 }
837 
843 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocAutoStartSavePoseSrv::Request& service_request)
844 {
845  std::stringstream cola_ascii;
846  cola_ascii << "sMN LocAutoStartSavePose";
847  return cola_ascii.str();
848 }
849 
856 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocAutoStartSavePoseSrv::Response& service_response)
857 {
858  service_response.success = false;
859  if(!cola_response.parameter.empty())
860  {
861  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
862  }
863  return service_response.success;
864 }
865 
871 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocForceUpdateSrv::Request& service_request)
872 {
873  std::stringstream cola_ascii;
874  cola_ascii << "sMN LocForceUpdate";
875  return cola_ascii.str();
876 }
877 
884 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocForceUpdateSrv::Response& service_response)
885 {
886  service_response.success = false;
887  if(!cola_response.parameter.empty())
888  {
889  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
890  }
891  return service_response.success;
892 }
893 
899 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocSaveRingBufferRecordingSrv::Request& service_request)
900 {
901  std::stringstream cola_ascii;
902  cola_ascii << "sMN LocSaveRingBufferRecording";
903  cola_ascii << " +" << service_request.reason.length() << " " << service_request.reason;
904  return cola_ascii.str();
905 }
906 
913 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocSaveRingBufferRecordingSrv::Response& service_response)
914 {
915  service_response.success = false;
916  if(!cola_response.parameter.empty())
917  {
918  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
919  }
920  return service_response.success;
921 }
922 
928 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocStartDemoMappingSrv::Request& service_request)
929 {
930  std::stringstream cola_ascii;
931  cola_ascii << "sMN LocStartDemoMapping";
932  return cola_ascii.str();
933 }
934 
941 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocStartDemoMappingSrv::Response& service_response)
942 {
943  service_response.success = false;
944  if(!cola_response.parameter.empty())
945  {
946  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
947  }
948  return service_response.success;
949 }
950 
956 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickReportUserMessageSrv::Request& service_request)
957 {
958  std::stringstream cola_ascii;
959  cola_ascii << "sMN ReportUserMessage";
960  cola_ascii << " +" << service_request.usermessage.length() << " " << service_request.usermessage;
961  return cola_ascii.str();
962 }
963 
970 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickReportUserMessageSrv::Response& service_response)
971 {
972  service_response.success = false;
973  if(!cola_response.parameter.empty())
974  {
975  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
976  }
977  return service_response.success;
978 }
979 
985 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickSavePermanentSrv::Request& service_request)
986 {
987  std::stringstream cola_ascii;
988  cola_ascii << "sMN SavePermanent";
989  return cola_ascii.str();
990 }
991 
998 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickSavePermanentSrv::Response& service_response)
999 {
1000  service_response.success = false;
1001  if(!cola_response.parameter.empty())
1002  {
1003  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1004  }
1005  return service_response.success;
1006 }
1007 
1013 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocResultPortSrv::Request& service_request)
1014 {
1015  std::stringstream cola_ascii;
1016  cola_ascii << "sRN LocResultPort";
1017  return cola_ascii.str();
1018 }
1019 
1026 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocResultPortSrv::Response& service_response)
1027 {
1028  service_response.success = false;
1029  if(!cola_response.parameter.empty())
1030  {
1031  service_response.port = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1032  service_response.success = true;
1033  }
1034  return service_response.success;
1035 }
1036 
1042 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocResultModeSrv::Request& service_request)
1043 {
1044  std::stringstream cola_ascii;
1045  cola_ascii << "sRN LocResultMode";
1046  return cola_ascii.str();
1047 }
1048 
1055 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocResultModeSrv::Response& service_response)
1056 {
1057  service_response.success = false;
1058  if(!cola_response.parameter.empty())
1059  {
1060  service_response.mode = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1061  service_response.success = true;
1062  }
1063  return service_response.success;
1064 }
1065 
1071 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocResultEndiannessSrv::Request& service_request)
1072 {
1073  std::stringstream cola_ascii;
1074  cola_ascii << "sRN LocResultEndianness";
1075  return cola_ascii.str();
1076 }
1077 
1084 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocResultEndiannessSrv::Response& service_response)
1085 {
1086  service_response.success = false;
1087  if(!cola_response.parameter.empty())
1088  {
1089  service_response.endianness = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1090  service_response.success = true;
1091  }
1092  return service_response.success;
1093 }
1094 
1100 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocResultStateSrv::Request& service_request)
1101 {
1102  std::stringstream cola_ascii;
1103  cola_ascii << "sRN LocResultState";
1104  return cola_ascii.str();
1105 }
1106 
1113 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocResultStateSrv::Response& service_response)
1114 {
1115  service_response.success = false;
1116  if(!cola_response.parameter.empty())
1117  {
1118  service_response.state = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1119  service_response.success = true;
1120  }
1121  return service_response.success;
1122 }
1123 
1129 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickLocResultPoseIntervalSrv::Request& service_request)
1130 {
1131  std::stringstream cola_ascii;
1132  cola_ascii << "sRN LocResultPoseInterval";
1133  return cola_ascii.str();
1134 }
1135 
1142 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickLocResultPoseIntervalSrv::Response& service_response)
1143 {
1144  service_response.success = false;
1145  if(!cola_response.parameter.empty())
1146  {
1147  service_response.interval = sick_scan::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1148  service_response.success = true;
1149  }
1150  return service_response.success;
1151 }
1152 
1158 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevSetIMUActiveSrv::Request& service_request)
1159 {
1160  std::stringstream cola_ascii;
1161  cola_ascii << "sMN DevSetIMUActive";
1162  cola_ascii << std::noshowpos << " " << (service_request.active?1:0);
1163  return cola_ascii.str();
1164 }
1165 
1172 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevSetIMUActiveSrv::Response& service_response)
1173 {
1174  service_response.success = false;
1175  if(!cola_response.parameter.empty())
1176  {
1177  service_response.success = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1178  }
1179  return service_response.success;
1180 }
1181 
1187 std::string sick_scan::ColaEncoder::encodeServiceRequest(const sick_scan::SickDevIMUActiveSrv::Request& service_request)
1188 {
1189  std::stringstream cola_ascii;
1190  cola_ascii << "sRN DevIMUActive";
1191  return cola_ascii.str();
1192 }
1193 
1200 bool sick_scan::ColaEncoder::parseServiceResponse(const sick_scan::SickLocColaTelegramMsg& cola_response, sick_scan::SickDevIMUActiveSrv::Response& service_response)
1201 {
1202  service_response.success = false;
1203  if(!cola_response.parameter.empty())
1204  {
1205  service_response.active = sick_scan::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1206  service_response.success = true;
1207  }
1208  return service_response.success;
1209 }
static std::string encodeServiceRequest(const sick_scan::SickDevSetLidarConfigSrv::Request &service_request)
static int32_t convertColaArg(const std::string &cola_arg, int base=10, int32_t default_value=0)
static bool convertColaResponseBool(const std::string &cola_response_arg, bool default_value)
static bool parseServiceResponse(const sick_scan::SickLocColaTelegramMsg &cola_response, sick_scan::SickDevSetLidarConfigSrv::Response &service_response)


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Wed May 5 2021 03:05:47