cola_encoder.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * @brief cola_encoder encodes service requests to cola telegrams, parses cola responses and
4  * converts them to service responses.
5  *
6  * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim
7  * Copyright (C) 2019 SICK AG, Waldkirch
8  *
9  * Licensed under the Apache License, Version 2.0 (the "License");
10  * you may not use this file except in compliance with the License.
11  * You may obtain a copy of the License at
12  *
13  * http://www.apache.org/licenses/LICENSE-2.0
14  *
15  * Unless required by applicable law or agreed to in writing, software
16  * distributed under the License is distributed on an "AS IS" BASIS,
17  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18  * See the License for the specific language governing permissions and
19  * limitations under the License.
20  *
21  * All rights reserved.
22  *
23  * Redistribution and use in source and binary forms, with or without
24  * modification, are permitted provided that the following conditions are met:
25  *
26  * * Redistributions of source code must retain the above copyright
27  * notice, this list of conditions and the following disclaimer.
28  * * Redistributions in binary form must reproduce the above copyright
29  * notice, this list of conditions and the following disclaimer in the
30  * documentation and/or other materials provided with the distribution.
31  * * Neither the name of SICK AG nor the names of its
32  * contributors may be used to endorse or promote products derived from
33  * this software without specific prior written permission
34  * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
35  * contributors may be used to endorse or promote products derived from
36  * this software without specific prior written permission
37  *
38  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
39  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
40  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
41  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
42  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
43  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
44  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
45  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
46  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
47  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
48  * POSSIBILITY OF SUCH DAMAGE.
49  *
50  * Authors:
51  * Michael Lehning <michael.lehning@lehning.de>
52  *
53  * Copyright 2019 SICK AG
54  * Copyright 2019 Ing.-Buero Dr. Michael Lehning
55  *
56  */
57 #ifndef __SIM_LOC_COLA_ENCODER_H_INCLUDED
58 #define __SIM_LOC_COLA_ENCODER_H_INCLUDED
59 
60 #include <string>
61 #include <vector>
62 #include "sick_scan/ros_wrapper.h"
63 #include "sick_scan/cola_parser.h"
64 
65 namespace sick_scan_xd
66 {
72  {
73  public:
74 
80  static std::string encodeServiceRequest(const sick_scan_xd::SickDevSetLidarConfigSrv::Request& service_request);
81 
89 
95  static std::string encodeServiceRequest(const sick_scan_xd::SickDevGetLidarConfigSrv::Request& service_request);
96 
104 
110  static std::string encodeServiceRequest(const sick_scan_xd::SickLocSetMapSrv::Request& service_request);
111 
119 
125  static std::string encodeServiceRequest(const sick_scan_xd::SickLocMapSrv::Request& service_request);
126 
133  static bool parseServiceResponse(const sick_scan_xd::SickLocColaTelegramMsg& cola_response, sick_scan_xd::SickLocMapSrv::Response& service_response);
134 
140  static std::string encodeServiceRequest(const sick_scan_xd::SickLocMapStateSrv::Request& service_request);
141 
149 
155  static std::string encodeServiceRequest(const sick_scan_xd::SickLocInitializePoseSrv::Request& service_request);
156 
164 
170  static std::string encodeServiceRequest(const sick_scan_xd::SickLocInitialPoseSrv::Request& service_request);
171 
179 
180 
187 
195 
202 
210 
216  static std::string encodeServiceRequest(const sick_scan_xd::SickLocSetOdometryActiveSrv::Request& service_request);
217 
225 
231  static std::string encodeServiceRequest(const sick_scan_xd::SickLocOdometryActiveSrv::Request& service_request);
232 
240 
246  static std::string encodeServiceRequest(const sick_scan_xd::SickLocSetOdometryPortSrv::Request& service_request);
247 
255 
261  static std::string encodeServiceRequest(const sick_scan_xd::SickLocOdometryPortSrv::Request& service_request);
262 
270 
277 
285 
291  static std::string encodeServiceRequest(const sick_scan_xd::SickLocOdometryRestrictYMotionSrv::Request& service_request);
292 
300 
306  static std::string encodeServiceRequest(const sick_scan_xd::SickLocSetAutoStartActiveSrv::Request& service_request);
307 
315 
321  static std::string encodeServiceRequest(const sick_scan_xd::SickLocAutoStartActiveSrv::Request& service_request);
322 
330 
337 
345 
351  static std::string encodeServiceRequest(const sick_scan_xd::SickLocAutoStartSavePoseIntervalSrv::Request& service_request);
352 
360 
367 
375 
381  static std::string encodeServiceRequest(const sick_scan_xd::SickLocRingBufferRecordingActiveSrv::Request& service_request);
382 
390 
396  static std::string encodeServiceRequest(const sick_scan_xd::SickDevGetLidarIdentSrv::Request& service_request);
397 
405 
411  static std::string encodeServiceRequest(const sick_scan_xd::SickDevGetLidarStateSrv::Request& service_request);
412 
420 
426  static std::string encodeServiceRequest(const sick_scan_xd::SickGetSoftwareVersionSrv::Request& service_request);
427 
435 
441  static std::string encodeServiceRequest(const sick_scan_xd::SickLocAutoStartSavePoseSrv::Request& service_request);
442 
450 
456  static std::string encodeServiceRequest(const sick_scan_xd::SickLocForceUpdateSrv::Request& service_request);
457 
465 
471  static std::string encodeServiceRequest(const sick_scan_xd::SickLocSaveRingBufferRecordingSrv::Request& service_request);
472 
480 
486  static std::string encodeServiceRequest(const sick_scan_xd::SickLocStartDemoMappingSrv::Request& service_request);
487 
495 
501  static std::string encodeServiceRequest(const sick_scan_xd::SickReportUserMessageSrv::Request& service_request);
502 
510 
516  static std::string encodeServiceRequest(const sick_scan_xd::SickSavePermanentSrv::Request& service_request);
517 
525 
531  static std::string encodeServiceRequest(const sick_scan_xd::SickLocResultPortSrv::Request& service_request);
532 
540 
546  static std::string encodeServiceRequest(const sick_scan_xd::SickLocResultModeSrv::Request& service_request);
547 
555 
561  static std::string encodeServiceRequest(const sick_scan_xd::SickLocResultEndiannessSrv::Request& service_request);
562 
570 
576  static std::string encodeServiceRequest(const sick_scan_xd::SickLocResultStateSrv::Request& service_request);
577 
585 
591  static std::string encodeServiceRequest(const sick_scan_xd::SickLocResultPoseIntervalSrv::Request& service_request);
592 
600 
606  static std::string encodeServiceRequest(const sick_scan_xd::SickDevSetIMUActiveSrv::Request& service_request);
607 
615 
621  static std::string encodeServiceRequest(const sick_scan_xd::SickDevIMUActiveSrv::Request& service_request);
622 
630 
631  }; // class ColaEncoder
632 
633 } // namespace sick_scan_xd
634 #endif // __SIM_LOC_COLA_ENCODER_H_INCLUDED
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::SickLocSetReflectorsForSupportActiveSrvRequest_
Definition: SickLocSetReflectorsForSupportActiveSrvRequest.h:23
sick_scan_xd::SickLocResultPortSrvResponse_
Definition: SickLocResultPortSrvResponse.h:23
sick_scan_xd::SickLocResultEndiannessSrvRequest_
Definition: SickLocResultEndiannessSrvRequest.h:23
sick_scan_xd::SickDevSetIMUActiveSrvResponse_
Definition: SickDevSetIMUActiveSrvResponse.h:23
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::SickLocMapStateSrvRequest_
Definition: SickLocMapStateSrvRequest.h:23
sick_scan_xd::SickLocOdometryActiveSrvRequest_
Definition: SickLocOdometryActiveSrvRequest.h:23
sick_scan_xd::SickLocMapSrvRequest_
Definition: SickLocMapSrvRequest.h:23
sick_scan_xd::SickDevIMUActiveSrvRequest_
Definition: SickDevIMUActiveSrvRequest.h:23
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::SickLocSetOdometryPortSrvResponse_
Definition: SickLocSetOdometryPortSrvResponse.h:23
sick_scan_xd::SickLocResultModeSrvResponse_
Definition: SickLocResultModeSrvResponse.h:23
sick_scan_xd::SickLocSetReflectorsForSupportActiveSrvResponse_
Definition: SickLocSetReflectorsForSupportActiveSrvResponse.h:23
sick_scan_xd::SickLocRingBufferRecordingActiveSrvRequest_
Definition: SickLocRingBufferRecordingActiveSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryActiveSrvRequest_
Definition: SickLocSetOdometryActiveSrvRequest.h:23
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_xd::SickLocSetAutoStartSavePoseIntervalSrvRequest_
Definition: SickLocSetAutoStartSavePoseIntervalSrvRequest.h:23
sick_scan_xd::SickLocSaveRingBufferRecordingSrvResponse_
Definition: SickLocSaveRingBufferRecordingSrvResponse.h:23
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::SickLocOdometryPortSrvRequest_
Definition: SickLocOdometryPortSrvRequest.h:23
sick_scan_xd::SickDevGetLidarConfigSrvRequest_
Definition: SickDevGetLidarConfigSrvRequest.h:23
sick_scan_xd::SickLocSetRingBufferRecordingActiveSrvResponse_
Definition: SickLocSetRingBufferRecordingActiveSrvResponse.h:23
sick_scan_xd::SickLocResultEndiannessSrvResponse_
Definition: SickLocResultEndiannessSrvResponse.h:23
sick_scan_xd::SickGetSoftwareVersionSrvRequest_
Definition: SickGetSoftwareVersionSrvRequest.h:23
sick_scan_xd::SickSavePermanentSrvRequest_
Definition: SickSavePermanentSrvRequest.h:23
sick_scan_xd::SickLocReflectorsForSupportActiveSrvRequest_
Definition: SickLocReflectorsForSupportActiveSrvRequest.h:23
sick_scan_xd::SickLocResultPoseIntervalSrvRequest_
Definition: SickLocResultPoseIntervalSrvRequest.h:23
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::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::ColaEncoder
class ColaEncoder encodes service requests to cola telegrams, parses cola responses and converts them...
Definition: cola_encoder.h:71
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::SickDevSetLidarConfigSrvRequest_
Definition: SickDevSetLidarConfigSrvRequest.h:23
sick_scan_xd::SickLocInitialPoseSrvResponse_
Definition: SickLocInitialPoseSrvResponse.h:23
sick_scan_xd::SickLocOdometryRestrictYMotionSrvRequest_
Definition: SickLocOdometryRestrictYMotionSrvRequest.h:23
sick_scan_xd::SickLocForceUpdateSrvRequest_
Definition: SickLocForceUpdateSrvRequest.h:23
sick_scan_xd::SickLocMapStateSrvResponse_
Definition: SickLocMapStateSrvResponse.h:23
sick_scan_xd::SickLocResultStateSrvRequest_
Definition: SickLocResultStateSrvRequest.h:23
sick_scan_xd::SickDevIMUActiveSrvResponse_
Definition: SickDevIMUActiveSrvResponse.h:23
sick_scan_xd::SickDevGetLidarStateSrvRequest_
Definition: SickDevGetLidarStateSrvRequest.h:23
sick_scan_xd::SickLocAutoStartSavePoseIntervalSrvResponse_
Definition: SickLocAutoStartSavePoseIntervalSrvResponse.h:23
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::SickLocSetOdometryRestrictYMotionSrvResponse_
Definition: SickLocSetOdometryRestrictYMotionSrvResponse.h:23
sick_scan_base.h
sick_scan_xd::SickLocOdometryActiveSrvResponse_
Definition: SickLocOdometryActiveSrvResponse.h:23
sick_scan_xd::SickLocAutoStartActiveSrvRequest_
Definition: SickLocAutoStartActiveSrvRequest.h:23
sick_scan_xd::SickSavePermanentSrvResponse_
Definition: SickSavePermanentSrvResponse.h:23
sick_scan_xd::SickDevGetLidarIdentSrvRequest_
Definition: SickDevGetLidarIdentSrvRequest.h:23
sick_scan_xd::SickLocSetAutoStartActiveSrvRequest_
Definition: SickLocSetAutoStartActiveSrvRequest.h:23
sick_scan_xd::SickLocSetMapSrvResponse_
Definition: SickLocSetMapSrvResponse.h:23
sick_scan_xd::SickLocReflectorsForSupportActiveSrvResponse_
Definition: SickLocReflectorsForSupportActiveSrvResponse.h:23
sick_scan_xd::SickLocForceUpdateSrvResponse_
Definition: SickLocForceUpdateSrvResponse.h:23
sick_scan_xd::SickLocSaveRingBufferRecordingSrvRequest_
Definition: SickLocSaveRingBufferRecordingSrvRequest.h:23
sick_scan_xd::SickLocSetOdometryActiveSrvResponse_
Definition: SickLocSetOdometryActiveSrvResponse.h:23
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::SickLocOdometryPortSrvResponse_
Definition: SickLocOdometryPortSrvResponse.h:23
cola_parser.h
sick_scan_xd::SickLocSetMapSrvRequest_
Definition: SickLocSetMapSrvRequest.h:23
sick_scan_xd::SickReportUserMessageSrvRequest_
Definition: SickReportUserMessageSrvRequest.h:23
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::SickLocAutoStartSavePoseSrvResponse_
Definition: SickLocAutoStartSavePoseSrvResponse.h:23
sick_scan_xd::SickLocResultModeSrvRequest_
Definition: SickLocResultModeSrvRequest.h:23


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