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 
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 
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_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
89  service_response.executed = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
90  }
91  return service_response.set;
92 }
93 
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 
114 {
115  if(cola_response.parameter.size() == 13)
116  {
117  service_response.minrange = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
118  service_response.maxrange = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0U);
119  service_response.minangle = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
120  service_response.maxangle = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0);
121  service_response.x = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[4], -1, 0);
122  service_response.y = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[5], -1, 0);
123  service_response.yaw = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[6], -1, 0);
124  service_response.upsidedown = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[7], false);
125  service_response.ip = cola_response.parameter[8];
126  service_response.port = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[9], -1, 0U);
127  service_response.interfacetype = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[10], -1, 0U);
128  service_response.maplayer = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[11], -1, 0U);
129  service_response.active = sick_scan_xd::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_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0U);
135  service_response.maxrange = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0U);
136  service_response.minangle = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
137  service_response.maxangle = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0);
138  service_response.x = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[4], -1, 0);
139  service_response.y = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[5], -1, 0);
140  service_response.yaw = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[6], -1, 0);
141  service_response.upsidedown = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[7], false);
142  int n = 8;
143  int ip_strlen = sick_scan_xd::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_xd::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
150  service_response.interfacetype = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
151  service_response.maplayer = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[n++], -1, 0U);
152  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[n++], false);
153  return true;
154  }
155  return false;
156 }
157 
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 
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_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
183  service_response.executed = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
184  }
185  return service_response.set;
186 }
187 
194 {
195  std::stringstream cola_ascii;
196  cola_ascii << "sRN LocMap";
197  return cola_ascii.str();
198 }
199 
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_xd::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 
233 {
234  std::stringstream cola_ascii;
235  cola_ascii << "sRN LocMapState";
236  return cola_ascii.str();
237 }
238 
246 {
247  service_response.success = false;
248  if(!cola_response.parameter.empty())
249  {
250  service_response.mapstate = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
251  service_response.success = true;
252  }
253  return service_response.success;
254 }
255 
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 
276 {
277  service_response.success = false;
278  if(!cola_response.parameter.empty())
279  {
280  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
281  }
282  return service_response.success;
283 }
284 
291 {
292  std::stringstream cola_ascii;
293  cola_ascii << "sRN LocInitialPose";
294  return cola_ascii.str();
295 }
296 
304 {
305  service_response.success = false;
306  if(cola_response.parameter.size() >= 4)
307  {
308  service_response.x = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
309  service_response.y = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0);
310  service_response.yaw = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
311  service_response.sigmatranslation = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[3], -1, 0U);
312  service_response.success = true;
313  }
314  return service_response.success;
315 }
316 
317 
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 
338 {
339  service_response.success = false;
340  if(!cola_response.parameter.empty())
341  {
342  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
343  }
344  return service_response.success;
345 }
346 
353 {
354  std::stringstream cola_ascii;
355  cola_ascii << "sRN LocReflectorsForSupportActive";
356  return cola_ascii.str();
357 }
358 
366 {
367  service_response.success = false;
368  if(!cola_response.parameter.empty())
369  {
370  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
371  service_response.success = true;
372  }
373  return service_response.success;
374 }
375 
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 
396 {
397  service_response.set = false;
398  service_response.executed = false;
399  if(!cola_response.parameter.empty())
400  {
401  service_response.set = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
402  service_response.executed = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
403  }
404  return service_response.set;
405 }
406 
413 {
414  std::stringstream cola_ascii;
415  cola_ascii << "sRN LocOdometryActive";
416  return cola_ascii.str();
417 }
418 
426 {
427  service_response.success = false;
428  if(!cola_response.parameter.empty())
429  {
430  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
431  service_response.success = true;
432  }
433  return service_response.success;
434 }
435 
442 {
443  std::stringstream cola_ascii;
444  cola_ascii << "sMN LocSetOdometryPort";
445  cola_ascii << " +" << service_request.port;
446  return cola_ascii.str();
447 }
448 
456 {
457  service_response.set = false;
458  if(!cola_response.parameter.empty())
459  {
460  service_response.set = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
461  service_response.executed = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[1], false);
462  }
463  return service_response.set;
464 }
465 
472 {
473  std::stringstream cola_ascii;
474  cola_ascii << "sRN LocOdometryPort";
475  return cola_ascii.str();
476 }
477 
485 {
486  service_response.success = false;
487  if(!cola_response.parameter.empty())
488  {
489  service_response.port = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
490  service_response.success = true;
491  }
492  return service_response.success;
493 }
494 
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 
515 {
516  service_response.success = false;
517  if(!cola_response.parameter.empty())
518  {
519  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
520  }
521  return service_response.success;
522 }
523 
530 {
531  std::stringstream cola_ascii;
532  cola_ascii << "sRN LocOdometryRestrictYMotion";
533  return cola_ascii.str();
534 }
535 
543 {
544  service_response.success = false;
545  if(!cola_response.parameter.empty())
546  {
547  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
548  service_response.success = true;
549  }
550  return service_response.success;
551 }
552 
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 
573 {
574  service_response.success = false;
575  if(!cola_response.parameter.empty())
576  {
577  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
578  }
579  return service_response.success;
580 }
581 
588 {
589  std::stringstream cola_ascii;
590  cola_ascii << "sRN LocAutoStartActive";
591  return cola_ascii.str();
592 }
593 
601 {
602  service_response.success = false;
603  if(!cola_response.parameter.empty())
604  {
605  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
606  service_response.success = true;
607  }
608  return service_response.success;
609 }
610 
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 
631 {
632  service_response.success = false;
633  if(!cola_response.parameter.empty())
634  {
635  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
636  }
637  return service_response.success;
638 }
639 
646 {
647  std::stringstream cola_ascii;
648  cola_ascii << "sRN LocAutoStartSavePoseInterval";
649  return cola_ascii.str();
650 }
651 
659 {
660  service_response.success = false;
661  if(!cola_response.parameter.empty())
662  {
663  service_response.interval = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
664  service_response.success = true;
665  }
666  return service_response.success;
667 }
668 
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 
689 {
690  service_response.success = false;
691  if(!cola_response.parameter.empty())
692  {
693  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
694  }
695  return service_response.success;
696 }
697 
704 {
705  std::stringstream cola_ascii;
706  cola_ascii << "sRN LocRingBufferRecordingActive";
707  return cola_ascii.str();
708 }
709 
717 {
718  service_response.success = false;
719  if(!cola_response.parameter.empty())
720  {
721  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
722  service_response.success = true;
723  }
724  return service_response.success;
725 }
726 
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 
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_xd::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 
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 
787 {
788  service_response.success = false;
789  if(cola_response.parameter.size() >= 3)
790  {
791  service_response.devicestatus = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
792  service_response.deviceconnected = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[1], -1, 0);
793  service_response.receivingdata = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[2], -1, 0);
794  service_response.success = true;
795  }
796  return service_response.success;
797 }
798 
805 {
806  std::stringstream cola_ascii;
807  cola_ascii << "sMN GetSoftwareVersion";
808  return cola_ascii.str();
809 }
810 
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_xd::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 
844 {
845  std::stringstream cola_ascii;
846  cola_ascii << "sMN LocAutoStartSavePose";
847  return cola_ascii.str();
848 }
849 
857 {
858  service_response.success = false;
859  if(!cola_response.parameter.empty())
860  {
861  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
862  }
863  return service_response.success;
864 }
865 
872 {
873  std::stringstream cola_ascii;
874  cola_ascii << "sMN LocForceUpdate";
875  return cola_ascii.str();
876 }
877 
885 {
886  service_response.success = false;
887  if(!cola_response.parameter.empty())
888  {
889  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
890  }
891  return service_response.success;
892 }
893 
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 
914 {
915  service_response.success = false;
916  if(!cola_response.parameter.empty())
917  {
918  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
919  }
920  return service_response.success;
921 }
922 
929 {
930  std::stringstream cola_ascii;
931  cola_ascii << "sMN LocStartDemoMapping";
932  return cola_ascii.str();
933 }
934 
942 {
943  service_response.success = false;
944  if(!cola_response.parameter.empty())
945  {
946  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
947  }
948  return service_response.success;
949 }
950 
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 
971 {
972  service_response.success = false;
973  if(!cola_response.parameter.empty())
974  {
975  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
976  }
977  return service_response.success;
978 }
979 
986 {
987  std::stringstream cola_ascii;
988  cola_ascii << "sMN SavePermanent";
989  return cola_ascii.str();
990 }
991 
999 {
1000  service_response.success = false;
1001  if(!cola_response.parameter.empty())
1002  {
1003  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1004  }
1005  return service_response.success;
1006 }
1007 
1014 {
1015  std::stringstream cola_ascii;
1016  cola_ascii << "sRN LocResultPort";
1017  return cola_ascii.str();
1018 }
1019 
1027 {
1028  service_response.success = false;
1029  if(!cola_response.parameter.empty())
1030  {
1031  service_response.port = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1032  service_response.success = true;
1033  }
1034  return service_response.success;
1035 }
1036 
1043 {
1044  std::stringstream cola_ascii;
1045  cola_ascii << "sRN LocResultMode";
1046  return cola_ascii.str();
1047 }
1048 
1056 {
1057  service_response.success = false;
1058  if(!cola_response.parameter.empty())
1059  {
1060  service_response.mode = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1061  service_response.success = true;
1062  }
1063  return service_response.success;
1064 }
1065 
1072 {
1073  std::stringstream cola_ascii;
1074  cola_ascii << "sRN LocResultEndianness";
1075  return cola_ascii.str();
1076 }
1077 
1085 {
1086  service_response.success = false;
1087  if(!cola_response.parameter.empty())
1088  {
1089  service_response.endianness = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1090  service_response.success = true;
1091  }
1092  return service_response.success;
1093 }
1094 
1101 {
1102  std::stringstream cola_ascii;
1103  cola_ascii << "sRN LocResultState";
1104  return cola_ascii.str();
1105 }
1106 
1114 {
1115  service_response.success = false;
1116  if(!cola_response.parameter.empty())
1117  {
1118  service_response.state = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1119  service_response.success = true;
1120  }
1121  return service_response.success;
1122 }
1123 
1130 {
1131  std::stringstream cola_ascii;
1132  cola_ascii << "sRN LocResultPoseInterval";
1133  return cola_ascii.str();
1134 }
1135 
1143 {
1144  service_response.success = false;
1145  if(!cola_response.parameter.empty())
1146  {
1147  service_response.interval = sick_scan_xd::ColaParser::convertColaArg(cola_response.parameter[0], -1, 0);
1148  service_response.success = true;
1149  }
1150  return service_response.success;
1151 }
1152 
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 
1173 {
1174  service_response.success = false;
1175  if(!cola_response.parameter.empty())
1176  {
1177  service_response.success = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1178  }
1179  return service_response.success;
1180 }
1181 
1188 {
1189  std::stringstream cola_ascii;
1190  cola_ascii << "sRN DevIMUActive";
1191  return cola_ascii.str();
1192 }
1193 
1201 {
1202  service_response.success = false;
1203  if(!cola_response.parameter.empty())
1204  {
1205  service_response.active = sick_scan_xd::ColaParser::convertColaResponseBool(cola_response.parameter[0], false);
1206  service_response.success = true;
1207  }
1208  return service_response.success;
1209 }
sick_scan_xd::SickLocAutoStartSavePoseIntervalSrvRequest_
Definition: SickLocAutoStartSavePoseIntervalSrvRequest.h:23
sick_scan_xd::SickLocResultPoseIntervalSrvResponse_
Definition: SickLocResultPoseIntervalSrvResponse.h:23
sick_scan_xd::SickLocMapSrvResponse_
Definition: SickLocMapSrvResponse.h:23
sick_scan_xd::SickDevSetIMUActiveSrvRequest_
Definition: SickDevSetIMUActiveSrvRequest.h:23
sick_scan_xd::SickDevGetLidarStateSrvResponse_::receivingdata
_receivingdata_type receivingdata
Definition: SickDevGetLidarStateSrvResponse.h:50
sick_scan_xd::SickLocSetReflectorsForSupportActiveSrvRequest_
Definition: SickLocSetReflectorsForSupportActiveSrvRequest.h:23
sick_scan_xd::SickLocInitializePoseSrvRequest_::sigmatranslation
_sigmatranslation_type sigmatranslation
Definition: SickLocInitializePoseSrvRequest.h:53
sick_scan_xd::SickLocResultPortSrvResponse_
Definition: SickLocResultPortSrvResponse.h:23
sick_scan_xd::SickLocRingBufferRecordingActiveSrvResponse_::success
_success_type success
Definition: SickLocRingBufferRecordingActiveSrvResponse.h:43
sick_scan_xd::SickLocResultEndiannessSrvRequest_
Definition: SickLocResultEndiannessSrvRequest.h:23
pcap_json_converter.cola_ascii
bool cola_ascii
Definition: pcap_json_converter.py:132
sick_scan_xd::SickLocSetMapSrvResponse_::executed
_executed_type executed
Definition: SickLocSetMapSrvResponse.h:43
sick_scan_xd::SickLocSetOdometryPortSrvResponse_::executed
_executed_type executed
Definition: SickLocSetOdometryPortSrvResponse.h:43
sick_scan_xd::SickLocInitialPoseSrvResponse_::yaw
_yaw_type yaw
Definition: SickLocInitialPoseSrvResponse.h:52
sick_scan_xd::SickLocOdometryPortSrvResponse_::success
_success_type success
Definition: SickLocOdometryPortSrvResponse.h:43
sick_scan_xd::SickDevSetIMUActiveSrvResponse_
Definition: SickDevSetIMUActiveSrvResponse.h:23
sick_scan_xd::SickLocSetOdometryPortSrvResponse_::set
_set_type set
Definition: SickLocSetOdometryPortSrvResponse.h:40
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::maxrange
_maxrange_type maxrange
Definition: SickDevGetLidarConfigSrvResponse.h:65
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::maxangle
_maxangle_type maxangle
Definition: SickDevGetLidarConfigSrvResponse.h:71
sick_scan_xd::SickLocResultModeSrvResponse_::success
_success_type success
Definition: SickLocResultModeSrvResponse.h:43
sick_scan_xd::SickDevSetLidarConfigSrvResponse_::executed
_executed_type executed
Definition: SickDevSetLidarConfigSrvResponse.h:43
sick_scan_xd::SickLocStartDemoMappingSrvResponse_
Definition: SickLocStartDemoMappingSrvResponse.h:23
sick_scan_xd::SickLocResultPortSrvRequest_
Definition: SickLocResultPortSrvRequest.h:23
sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrvResponse_
Definition: SickLocSetAutoStartSavePoseIntervalSrvResponse.h:23
sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrvRequest_::interval
_interval_type interval
Definition: SickLocSetAutoStartSavePoseIntervalSrvRequest.h:38
sick_scan_xd::SickLocMapStateSrvRequest_
Definition: SickLocMapStateSrvRequest.h:23
sick_scan_xd::SickLocOdometryActiveSrvRequest_
Definition: SickLocOdometryActiveSrvRequest.h:23
sick_scan_xd::SickLocMapSrvRequest_
Definition: SickLocMapSrvRequest.h:23
sick_scan_xd::SickLocSetMapSrvResponse_::set
_set_type set
Definition: SickLocSetMapSrvResponse.h:40
sick_scan_xd::SickLocMapStateSrvResponse_::success
_success_type success
Definition: SickLocMapStateSrvResponse.h:43
sick_scan_xd::SickDevIMUActiveSrvRequest_
Definition: SickDevIMUActiveSrvRequest.h:23
sick_scan_xd::SickDevGetLidarStateSrvResponse_::success
_success_type success
Definition: SickDevGetLidarStateSrvResponse.h:53
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::maplayer
_maplayer_type maplayer
Definition: SickDevGetLidarConfigSrvResponse.h:95
sick_scan_xd::SickLocSetAutoStartActiveSrvRequest_::active
_active_type active
Definition: SickLocSetAutoStartActiveSrvRequest.h:38
sick_scan_xd::SickLocInitializePoseSrvResponse_
Definition: SickLocInitializePoseSrvResponse.h:23
sick_scan_xd::SickLocAutoStartActiveSrvResponse_
Definition: SickLocAutoStartActiveSrvResponse.h:23
sick_scan_xd::SickGetSoftwareVersionSrvResponse_
Definition: SickGetSoftwareVersionSrvResponse.h:23
sick_scan_xd::SickLocColaTelegramMsg_
Definition: SickLocColaTelegramMsg.h:24
sick_scan_xd::SickLocAutoStartSavePoseIntervalSrvResponse_::success
_success_type success
Definition: SickLocAutoStartSavePoseIntervalSrvResponse.h:43
sick_scan_xd::SickLocSaveRingBufferRecordingSrvResponse_::success
_success_type success
Definition: SickLocSaveRingBufferRecordingSrvResponse.h:38
sick_scan_xd::SickLocSetMapSrvRequest_::mapfilename
_mapfilename_type mapfilename
Definition: SickLocSetMapSrvRequest.h:38
sick_scan_xd::SickLocInitialPoseSrvResponse_::x
_x_type x
Definition: SickLocInitialPoseSrvResponse.h:46
sick_scan_xd::SickLocSetOdometryPortSrvResponse_
Definition: SickLocSetOdometryPortSrvResponse.h:23
sick_scan_xd::SickLocResultPortSrvResponse_::port
_port_type port
Definition: SickLocResultPortSrvResponse.h:40
sick_scan_xd::SickLocSaveRingBufferRecordingSrvRequest_::reason
_reason_type reason
Definition: SickLocSaveRingBufferRecordingSrvRequest.h:38
sick_scan_xd::SickDevGetLidarIdentSrvRequest_::index
_index_type index
Definition: SickDevGetLidarIdentSrvRequest.h:38
sick_scan_xd::SickLocSetRingBufferRecordingActiveSrvRequest_::active
_active_type active
Definition: SickLocSetRingBufferRecordingActiveSrvRequest.h:38
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::maxrange
_maxrange_type maxrange
Definition: SickDevSetLidarConfigSrvRequest.h:70
sick_scan_xd::SickDevSetLidarConfigSrvResponse_::set
_set_type set
Definition: SickDevSetLidarConfigSrvResponse.h:40
sick_scan_xd::SickLocResultModeSrvResponse_
Definition: SickLocResultModeSrvResponse.h:23
sick_scan_xd::SickLocAutoStartSavePoseSrvResponse_::success
_success_type success
Definition: SickLocAutoStartSavePoseSrvResponse.h:38
sick_scan_xd::SickLocSetReflectorsForSupportActiveSrvRequest_::active
_active_type active
Definition: SickLocSetReflectorsForSupportActiveSrvRequest.h:38
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::upsidedown
_upsidedown_type upsidedown
Definition: SickDevGetLidarConfigSrvResponse.h:83
sick_scan_xd::SickDevGetLidarStateSrvResponse_::deviceconnected
_deviceconnected_type deviceconnected
Definition: SickDevGetLidarStateSrvResponse.h:47
sick_scan_xd::SickLocSetReflectorsForSupportActiveSrvResponse_
Definition: SickLocSetReflectorsForSupportActiveSrvResponse.h:23
sick_scan_xd::SickLocRingBufferRecordingActiveSrvRequest_
Definition: SickLocRingBufferRecordingActiveSrvRequest.h:23
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::yaw
_yaw_type yaw
Definition: SickDevSetLidarConfigSrvRequest.h:85
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::index
_index_type index
Definition: SickDevSetLidarConfigSrvRequest.h:64
sick_scan_xd::SickDevGetLidarStateSrvResponse_::devicestatus
_devicestatus_type devicestatus
Definition: SickDevGetLidarStateSrvResponse.h:44
sick_scan_xd::ColaParser::convertColaResponseBool
static bool convertColaResponseBool(const std::string &cola_response_arg, bool default_value)
Definition: cola_parser.cpp:286
sick_scan_xd::SickLocSetOdometryActiveSrvRequest_
Definition: SickLocSetOdometryActiveSrvRequest.h:23
sick_scan_xd::SickLocAutoStartActiveSrvResponse_::success
_success_type success
Definition: SickLocAutoStartActiveSrvResponse.h:43
sick_scan_xd::SickLocOdometryRestrictYMotionSrvResponse_::success
_success_type success
Definition: SickLocOdometryRestrictYMotionSrvResponse.h:43
sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrvRequest_
Definition: SickLocSetAutoStartSavePoseIntervalSrvRequest.h:23
sick_scan_xd::SickLocForceUpdateSrvResponse_::success
_success_type success
Definition: SickLocForceUpdateSrvResponse.h:38
sick_scan_xd::SickLocMapSrvResponse_::map
_map_type map
Definition: SickLocMapSrvResponse.h:40
sick_scan_xd::ColaParser::convertColaArg
static int32_t convertColaArg(const std::string &cola_arg, int base=10, int32_t default_value=0)
Definition: cola_parser.cpp:243
sick_scan_xd::SickLocReflectorsForSupportActiveSrvResponse_::success
_success_type success
Definition: SickLocReflectorsForSupportActiveSrvResponse.h:43
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::x
_x_type x
Definition: SickDevSetLidarConfigSrvRequest.h:79
sick_scan_xd::SickDevGetLidarStateSrvRequest_::index
_index_type index
Definition: SickDevGetLidarStateSrvRequest.h:38
sick_scan_xd::SickLocSetOdometryPortSrvRequest_::port
_port_type port
Definition: SickLocSetOdometryPortSrvRequest.h:38
sick_scan_xd::SickLocSetOdometryRestrictYMotionSrvResponse_::success
_success_type success
Definition: SickLocSetOdometryRestrictYMotionSrvResponse.h:38
sick_scan_xd::SickLocInitialPoseSrvResponse_::y
_y_type y
Definition: SickLocInitialPoseSrvResponse.h:49
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::ip
_ip_type ip
Definition: SickDevSetLidarConfigSrvRequest.h:91
sick_scan_xd::SickLocSaveRingBufferRecordingSrvResponse_
Definition: SickLocSaveRingBufferRecordingSrvResponse.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::interfacetype
_interfacetype_type interfacetype
Definition: SickDevGetLidarConfigSrvResponse.h:92
sick_scan_xd::ColaEncoder::encodeServiceRequest
static std::string encodeServiceRequest(const sick_scan_xd::SickDevSetLidarConfigSrv::Request &service_request)
Definition: cola_encoder.cpp:64
sick_scan_xd::SickLocResultPoseIntervalSrvResponse_::interval
_interval_type interval
Definition: SickLocResultPoseIntervalSrvResponse.h:40
sick_scan_xd::SickLocInitializePoseSrvRequest_::x
_x_type x
Definition: SickLocInitializePoseSrvRequest.h:44
sick_scan_xd::SickLocOdometryPortSrvRequest_
Definition: SickLocOdometryPortSrvRequest.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::ip
_ip_type ip
Definition: SickDevGetLidarConfigSrvResponse.h:86
sick_scan_xd::SickLocMapStateSrvResponse_::mapstate
_mapstate_type mapstate
Definition: SickLocMapStateSrvResponse.h:40
sick_scan_xd::SickDevGetLidarConfigSrvRequest_
Definition: SickDevGetLidarConfigSrvRequest.h:23
sick_scan_xd::SickLocSetRingBufferRecordingActiveSrvResponse_
Definition: SickLocSetRingBufferRecordingActiveSrvResponse.h:23
sick_scan_xd::SickDevIMUActiveSrvResponse_::active
_active_type active
Definition: SickDevIMUActiveSrvResponse.h:40
sick_scan_xd::SickLocReflectorsForSupportActiveSrvResponse_::active
_active_type active
Definition: SickLocReflectorsForSupportActiveSrvResponse.h:40
sick_scan_xd::SickLocResultEndiannessSrvResponse_
Definition: SickLocResultEndiannessSrvResponse.h:23
sick_scan_xd::SickDevSetIMUActiveSrvResponse_::success
_success_type success
Definition: SickDevSetIMUActiveSrvResponse.h:38
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::interfacetype
_interfacetype_type interfacetype
Definition: SickDevSetLidarConfigSrvRequest.h:97
sick_scan_xd::SickLocOdometryRestrictYMotionSrvResponse_::active
_active_type active
Definition: SickLocOdometryRestrictYMotionSrvResponse.h:40
sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrvResponse_::success
_success_type success
Definition: SickLocSetAutoStartSavePoseIntervalSrvResponse.h:38
sick_scan_xd::SickGetSoftwareVersionSrvRequest_
Definition: SickGetSoftwareVersionSrvRequest.h:23
sick_scan_xd::SickSavePermanentSrvRequest_
Definition: SickSavePermanentSrvRequest.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::minrange
_minrange_type minrange
Definition: SickDevGetLidarConfigSrvResponse.h:62
sick_scan_xd::SickLocStartDemoMappingSrvResponse_::success
_success_type success
Definition: SickLocStartDemoMappingSrvResponse.h:38
sick_scan_xd::SickLocReflectorsForSupportActiveSrvRequest_
Definition: SickLocReflectorsForSupportActiveSrvRequest.h:23
sick_scan_xd::SickLocResultPoseIntervalSrvRequest_
Definition: SickLocResultPoseIntervalSrvRequest.h:23
sick_scan_xd::SickReportUserMessageSrvRequest_::usermessage
_usermessage_type usermessage
Definition: SickReportUserMessageSrvRequest.h:38
sick_scan_xd::SickLocInitializePoseSrvRequest_
Definition: SickLocInitializePoseSrvRequest.h:23
sick_scan_xd::SickReportUserMessageSrvResponse_
Definition: SickReportUserMessageSrvResponse.h:23
sick_scan_xd::SickLocInitialPoseSrvRequest_
Definition: SickLocInitialPoseSrvRequest.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::active
_active_type active
Definition: SickDevGetLidarConfigSrvResponse.h:98
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::maxangle
_maxangle_type maxangle
Definition: SickDevSetLidarConfigSrvRequest.h:76
sick_scan_xd::ColaEncoder::parseServiceResponse
static bool parseServiceResponse(const sick_scan_xd::SickLocColaTelegramMsg &cola_response, sick_scan_xd::SickDevSetLidarConfigSrv::Response &service_response)
Definition: cola_encoder.cpp:82
sick_scan_xd::SickLocSetAutoStartActiveSrvResponse_::success
_success_type success
Definition: SickLocSetAutoStartActiveSrvResponse.h:38
sick_scan_xd::SickLocInitializePoseSrvRequest_::yaw
_yaw_type yaw
Definition: SickLocInitializePoseSrvRequest.h:50
sick_scan_xd::SickDevGetLidarStateSrvResponse_
Definition: SickDevGetLidarStateSrvResponse.h:23
sick_scan_xd::SickLocSetRingBufferRecordingActiveSrvRequest_
Definition: SickLocSetRingBufferRecordingActiveSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryRestrictYMotionSrvRequest_
Definition: SickLocSetOdometryRestrictYMotionSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryActiveSrvRequest_::active
_active_type active
Definition: SickLocSetOdometryActiveSrvRequest.h:38
sick_scan_xd::SickLocOdometryActiveSrvResponse_::success
_success_type success
Definition: SickLocOdometryActiveSrvResponse.h:43
sick_scan_xd::SickLocInitialPoseSrvResponse_::sigmatranslation
_sigmatranslation_type sigmatranslation
Definition: SickLocInitialPoseSrvResponse.h:55
sick_scan_xd::SickLocResultEndiannessSrvResponse_::endianness
_endianness_type endianness
Definition: SickLocResultEndiannessSrvResponse.h:40
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::yaw
_yaw_type yaw
Definition: SickDevGetLidarConfigSrvResponse.h:80
sick_scan_xd::SickLocOdometryPortSrvResponse_::port
_port_type port
Definition: SickLocOdometryPortSrvResponse.h:40
sick_scan_xd::SickDevSetLidarConfigSrvRequest_
Definition: SickDevSetLidarConfigSrvRequest.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::x
_x_type x
Definition: SickDevGetLidarConfigSrvResponse.h:74
sick_scan_xd::SickLocSetOdometryRestrictYMotionSrvRequest_::active
_active_type active
Definition: SickLocSetOdometryRestrictYMotionSrvRequest.h:38
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::minangle
_minangle_type minangle
Definition: SickDevGetLidarConfigSrvResponse.h:68
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::maplayer
_maplayer_type maplayer
Definition: SickDevSetLidarConfigSrvRequest.h:100
sick_scan_xd::SickLocSetOdometryActiveSrvResponse_::set
_set_type set
Definition: SickLocSetOdometryActiveSrvResponse.h:40
sick_scan_xd::SickGetSoftwareVersionSrvResponse_::success
_success_type success
Definition: SickGetSoftwareVersionSrvResponse.h:43
sick_scan_xd::SickLocInitialPoseSrvResponse_
Definition: SickLocInitialPoseSrvResponse.h:23
sick_scan_xd::SickLocOdometryRestrictYMotionSrvRequest_
Definition: SickLocOdometryRestrictYMotionSrvRequest.h:23
sick_scan_xd::SickLocResultStateSrvResponse_::success
_success_type success
Definition: SickLocResultStateSrvResponse.h:43
sick_scan_xd::SickDevGetLidarIdentSrvResponse_::success
_success_type success
Definition: SickDevGetLidarIdentSrvResponse.h:43
sick_scan_xd::SickLocResultPoseIntervalSrvResponse_::success
_success_type success
Definition: SickLocResultPoseIntervalSrvResponse.h:43
sick_scan_xd::SickLocInitializePoseSrvResponse_::success
_success_type success
Definition: SickLocInitializePoseSrvResponse.h:38
sick_scan_xd::SickLocForceUpdateSrvRequest_
Definition: SickLocForceUpdateSrvRequest.h:23
sick_scan_xd::SickLocMapStateSrvResponse_
Definition: SickLocMapStateSrvResponse.h:23
sick_scan_xd::SickDevGetLidarConfigSrvRequest_::scannerindex
_scannerindex_type scannerindex
Definition: SickDevGetLidarConfigSrvRequest.h:38
sick_scan_xd::SickLocResultStateSrvRequest_
Definition: SickLocResultStateSrvRequest.h:23
sick_scan_xd::SickLocOdometryActiveSrvResponse_::active
_active_type active
Definition: SickLocOdometryActiveSrvResponse.h:40
sick_scan_xd::SickDevIMUActiveSrvResponse_
Definition: SickDevIMUActiveSrvResponse.h:23
sick_scan_xd::SickReportUserMessageSrvResponse_::success
_success_type success
Definition: SickReportUserMessageSrvResponse.h:38
sick_scan_xd::SickDevSetIMUActiveSrvRequest_::active
_active_type active
Definition: SickDevSetIMUActiveSrvRequest.h:38
sick_scan_xd::SickDevGetLidarStateSrvRequest_
Definition: SickDevGetLidarStateSrvRequest.h:23
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::minangle
_minangle_type minangle
Definition: SickDevSetLidarConfigSrvRequest.h:73
sick_scan_xd::SickLocMapSrvResponse_::success
_success_type success
Definition: SickLocMapSrvResponse.h:43
sick_scan_xd::SickLocAutoStartSavePoseIntervalSrvResponse_
Definition: SickLocAutoStartSavePoseIntervalSrvResponse.h:23
sick_scan_xd::SickLocAutoStartActiveSrvResponse_::active
_active_type active
Definition: SickLocAutoStartActiveSrvResponse.h:40
sick_scan_xd::SickLocResultStateSrvResponse_::state
_state_type state
Definition: SickLocResultStateSrvResponse.h:40
sick_scan_xd::SickLocOdometryRestrictYMotionSrvResponse_
Definition: SickLocOdometryRestrictYMotionSrvResponse.h:23
sick_scan_xd::SickLocResultStateSrvResponse_
Definition: SickLocResultStateSrvResponse.h:23
sick_scan_xd::SickLocStartDemoMappingSrvRequest_
Definition: SickLocStartDemoMappingSrvRequest.h:23
sick_scan_xd::SickLocResultModeSrvResponse_::mode
_mode_type mode
Definition: SickLocResultModeSrvResponse.h:40
sick_scan_xd::SickLocSetOdometryRestrictYMotionSrvResponse_
Definition: SickLocSetOdometryRestrictYMotionSrvResponse.h:23
sick_scan_xd::SickLocOdometryActiveSrvResponse_
Definition: SickLocOdometryActiveSrvResponse.h:23
sick_scan_xd::SickLocAutoStartActiveSrvRequest_
Definition: SickLocAutoStartActiveSrvRequest.h:23
sick_scan_xd::SickDevIMUActiveSrvResponse_::success
_success_type success
Definition: SickDevIMUActiveSrvResponse.h:43
sick_scan_xd::SickSavePermanentSrvResponse_
Definition: SickSavePermanentSrvResponse.h:23
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::y
_y_type y
Definition: SickDevSetLidarConfigSrvRequest.h:82
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::y
_y_type y
Definition: SickDevGetLidarConfigSrvResponse.h:77
sick_scan_xd::SickLocSetRingBufferRecordingActiveSrvResponse_::success
_success_type success
Definition: SickLocSetRingBufferRecordingActiveSrvResponse.h:38
sick_scan_xd::SickDevGetLidarIdentSrvRequest_
Definition: SickDevGetLidarIdentSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryActiveSrvResponse_::executed
_executed_type executed
Definition: SickLocSetOdometryActiveSrvResponse.h:43
sick_scan_xd::SickLocSetAutoStartActiveSrvRequest_
Definition: SickLocSetAutoStartActiveSrvRequest.h:23
sick_scan_xd::SickLocSetMapSrvResponse_
Definition: SickLocSetMapSrvResponse.h:23
sick_scan_xd::SickLocColaTelegramMsg_::parameter
_parameter_type parameter
Definition: SickLocColaTelegramMsg.h:54
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::minrange
_minrange_type minrange
Definition: SickDevSetLidarConfigSrvRequest.h:67
sick_scan_xd::SickLocAutoStartSavePoseIntervalSrvResponse_::interval
_interval_type interval
Definition: SickLocAutoStartSavePoseIntervalSrvResponse.h:40
sick_scan_xd::SickLocReflectorsForSupportActiveSrvResponse_
Definition: SickLocReflectorsForSupportActiveSrvResponse.h:23
sick_scan_xd::SickGetSoftwareVersionSrvResponse_::version
_version_type version
Definition: SickGetSoftwareVersionSrvResponse.h:40
sick_scan_xd::SickLocForceUpdateSrvResponse_
Definition: SickLocForceUpdateSrvResponse.h:23
sick_scan_xd::SickLocSaveRingBufferRecordingSrvRequest_
Definition: SickLocSaveRingBufferRecordingSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryActiveSrvResponse_
Definition: SickLocSetOdometryActiveSrvResponse.h:23
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::active
_active_type active
Definition: SickDevSetLidarConfigSrvRequest.h:103
ros_wrapper.h
sick_scan_xd::SickLocSetAutoStartActiveSrvResponse_
Definition: SickLocSetAutoStartActiveSrvResponse.h:23
sick_scan_xd::SickDevGetLidarIdentSrvResponse_
Definition: SickDevGetLidarIdentSrvResponse.h:23
sick_scan_xd::SickLocAutoStartSavePoseSrvRequest_
Definition: SickLocAutoStartSavePoseSrvRequest.h:23
sick_scan_xd::SickSavePermanentSrvResponse_::success
_success_type success
Definition: SickSavePermanentSrvResponse.h:38
sick_scan_xd::SickLocOdometryPortSrvResponse_
Definition: SickLocOdometryPortSrvResponse.h:23
sick_scan_xd::SickDevGetLidarConfigSrvResponse_::port
_port_type port
Definition: SickDevGetLidarConfigSrvResponse.h:89
sick_scan_xd::SickLocSetMapSrvRequest_
Definition: SickLocSetMapSrvRequest.h:23
sick_scan_xd::SickDevGetLidarIdentSrvResponse_::scannerident
_scannerident_type scannerident
Definition: SickDevGetLidarIdentSrvResponse.h:40
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::port
_port_type port
Definition: SickDevSetLidarConfigSrvRequest.h:94
sick_scan_xd::SickLocRingBufferRecordingActiveSrvResponse_::active
_active_type active
Definition: SickLocRingBufferRecordingActiveSrvResponse.h:40
sick_scan_xd::SickLocResultEndiannessSrvResponse_::success
_success_type success
Definition: SickLocResultEndiannessSrvResponse.h:43
sick_scan_xd::SickLocResultPortSrvResponse_::success
_success_type success
Definition: SickLocResultPortSrvResponse.h:43
sick_scan_xd::SickReportUserMessageSrvRequest_
Definition: SickReportUserMessageSrvRequest.h:23
sick_scan_xd::SickLocInitialPoseSrvResponse_::success
_success_type success
Definition: SickLocInitialPoseSrvResponse.h:58
sick_scan_xd::SickDevGetLidarConfigSrvResponse_
Definition: SickDevGetLidarConfigSrvResponse.h:23
sick_scan_xd::SickLocSetOdometryPortSrvRequest_
Definition: SickLocSetOdometryPortSrvRequest.h:23
sick_scan_xd::SickDevSetLidarConfigSrvResponse_
Definition: SickDevSetLidarConfigSrvResponse.h:23
sick_scan_xd::SickLocRingBufferRecordingActiveSrvResponse_
Definition: SickLocRingBufferRecordingActiveSrvResponse.h:23
sick_scan_xd::SickLocInitializePoseSrvRequest_::y
_y_type y
Definition: SickLocInitializePoseSrvRequest.h:47
sick_scan_xd::SickLocSetReflectorsForSupportActiveSrvResponse_::success
_success_type success
Definition: SickLocSetReflectorsForSupportActiveSrvResponse.h:38
cola_encoder.h
sick_scan_xd::SickLocAutoStartSavePoseSrvResponse_
Definition: SickLocAutoStartSavePoseSrvResponse.h:23
sick_scan_xd::SickLocResultModeSrvRequest_
Definition: SickLocResultModeSrvRequest.h:23
sick_scan_xd::SickDevSetLidarConfigSrvRequest_::upsidedown
_upsidedown_type upsidedown
Definition: SickDevSetLidarConfigSrvRequest.h:88


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07