sick_scan_services.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 Implementation of ROS services for sick_scan
4  *
5  * Copyright (C) 2021, Ing.-Buero Dr. Michael Lehning, Hildesheim
6  * Copyright (C) 2021, SICK AG, Waldkirch
7  * All rights reserved.
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 *
22 * All rights reserved.
23 *
24 * Redistribution and use in source and binary forms, with or without
25 * modification, are permitted provided that the following conditions are met:
26 *
27 * * Redistributions of source code must retain the above copyright
28 * notice, this list of conditions and the following disclaimer.
29 * * Redistributions in binary form must reproduce the above copyright
30 * notice, this list of conditions and the following disclaimer in the
31 * documentation and/or other materials provided with the distribution.
32 * * Neither the name of Osnabrueck University nor the names of its
33 * contributors may be used to endorse or promote products derived from
34 * this software without specific prior written permission.
35 * * Neither the name of SICK AG nor the names of its
36 * contributors may be used to endorse or promote products derived from
37 * this software without specific prior written permission
38 * * Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
39 * contributors may be used to endorse or promote products derived from
40 * this software without specific prior written permission
41 *
42 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
43 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
44 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
45 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
46 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
47 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
48 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
49 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
50 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
51 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
52 * POSSIBILITY OF SUCH DAMAGE.
53  *
54  * Created on: 12.01.2021
55  *
56  * Authors:
57  * Michael Lehning <michael.lehning@lehning.de>
58  *
59  * Based on the TiM communication example by SICK AG.
60  *
61  */
62 
63 #ifndef SICK_SCAN_SERVICES_H_
64 #define SICK_SCAN_SERVICES_H_
65 
69 #if defined SCANSEGMENT_XD_SUPPORT && SCANSEGMENT_XD_SUPPORT > 0
71 #endif // SCANSEGMENT_XD_SUPPORT
72 
73 namespace sick_scan_xd
74 {
75 
77  {
78  public:
79 
80  SickScanServices(rosNodePtr nh = 0, sick_scan_xd::SickScanCommonTcp* common_tcp = 0, ScannerBasicParam * lidar_param = 0);
81 
82  virtual ~SickScanServices();
83 
87  bool sendAuthorization();
88 
92  bool sendSopasCmdCheckResponse(const std::string& sopas_request, const std::string& expected_response);
93 
100  bool serviceCbColaMsg(sick_scan_srv::ColaMsgSrv::Request &service_request, sick_scan_srv::ColaMsgSrv::Response &service_response);
101  bool serviceCbColaMsgROS2(std::shared_ptr<sick_scan_srv::ColaMsgSrv::Request> service_request, std::shared_ptr<sick_scan_srv::ColaMsgSrv::Response> service_response) { return serviceCbColaMsg(*service_request, *service_response); }
102 
110  bool serviceCbECRChangeArr(sick_scan_srv::ECRChangeArrSrv::Request &service_request, sick_scan_srv::ECRChangeArrSrv::Response &service_response);
111  bool serviceCbECRChangeArrROS2(std::shared_ptr<sick_scan_srv::ECRChangeArrSrv::Request> service_request, std::shared_ptr<sick_scan_srv::ECRChangeArrSrv::Response> service_response) { return serviceCbECRChangeArr(*service_request, *service_response); }
112 
120  bool serviceCbGetContaminationResult(sick_scan_srv::GetContaminationResultSrv::Request &service_request, sick_scan_srv::GetContaminationResultSrv::Response &service_response);
121  bool serviceCbGetContaminationResultROS2(std::shared_ptr<sick_scan_srv::GetContaminationResultSrv::Request> service_request, std::shared_ptr<sick_scan_srv::GetContaminationResultSrv::Response> service_response) { return serviceCbGetContaminationResult(*service_request, *service_response); }
122 
130  bool serviceCbLIDoutputstate(sick_scan_srv::LIDoutputstateSrv::Request &service_request, sick_scan_srv::LIDoutputstateSrv::Response &service_response);
131  bool serviceCbLIDoutputstateROS2(std::shared_ptr<sick_scan_srv::LIDoutputstateSrv::Request> service_request, std::shared_ptr<sick_scan_srv::LIDoutputstateSrv::Response> service_response) { return serviceCbLIDoutputstate(*service_request, *service_response); }
132 
140  bool serviceCbSCdevicestate(sick_scan_srv::SCdevicestateSrv::Request &service_request, sick_scan_srv::SCdevicestateSrv::Response &service_response);
141  bool serviceCbSCdevicestateROS2(std::shared_ptr<sick_scan_srv::SCdevicestateSrv::Request> service_request, std::shared_ptr<sick_scan_srv::SCdevicestateSrv::Response> service_response) { return serviceCbSCdevicestate(*service_request, *service_response); }
142 
143  bool serviceCbSCreboot(sick_scan_srv::SCrebootSrv::Request &service_request, sick_scan_srv::SCrebootSrv::Response &service_response);
144  bool serviceCbSCrebootROS2(std::shared_ptr<sick_scan_srv::SCrebootSrv::Request> service_request, std::shared_ptr<sick_scan_srv::SCrebootSrv::Response> service_response) { return serviceCbSCreboot(*service_request, *service_response); }
145 
146  bool serviceCbSCsoftreset(sick_scan_srv::SCsoftresetSrv::Request &service_request, sick_scan_srv::SCsoftresetSrv::Response &service_response);
147  bool serviceCbSCsoftresetROS2(std::shared_ptr<sick_scan_srv::SCsoftresetSrv::Request> service_request, std::shared_ptr<sick_scan_srv::SCsoftresetSrv::Response> service_response) { return serviceCbSCsoftreset(*service_request, *service_response); }
148 
149  bool serviceCbSickScanExit(sick_scan_srv::SickScanExitSrv::Request &service_request, sick_scan_srv::SickScanExitSrv::Response &service_response);
150  bool serviceCbSickScanExitROS2(std::shared_ptr<sick_scan_srv::SickScanExitSrv::Request> service_request, std::shared_ptr<sick_scan_srv::SickScanExitSrv::Response> service_response) { return serviceCbSickScanExit(*service_request, *service_response); }
151 
152 #if __ROS_VERSION > 0
153  bool serviceCbFieldSetRead(sick_scan_srv::FieldSetReadSrv::Request &service_request, sick_scan_srv::FieldSetReadSrv::Response &service_response);
154  bool serviceCbFieldSetReadROS2(std::shared_ptr<sick_scan_srv::FieldSetReadSrv::Request> service_request, std::shared_ptr<sick_scan_srv::FieldSetReadSrv::Response> service_response) { return serviceCbFieldSetRead(*service_request, *service_response); }
155  bool serviceCbFieldSetWrite(sick_scan_srv::FieldSetWriteSrv::Request &service_request, sick_scan_srv::FieldSetWriteSrv::Response &service_response);
156  bool serviceCbFieldSetWriteROS2(std::shared_ptr<sick_scan_srv::FieldSetWriteSrv::Request> service_request, std::shared_ptr<sick_scan_srv::FieldSetWriteSrv::Response> service_response) { return serviceCbFieldSetWrite(*service_request, *service_response); }
157 #endif
158 
159 #if defined SCANSEGMENT_XD_SUPPORT && SCANSEGMENT_XD_SUPPORT > 0
160 
171  bool sendMultiScanStartCmd(const std::string& hostname, int port, const std::string& scanner_type, int scandataformat, bool& imu_enable, int imu_udp_port, int performanceprofilenumber, bool check_udp_receiver_ip, int check_udp_receiver_port);
172 
177  bool sendMultiScanStopCmd(bool imu_enable);
178 
186  bool queryMultiScanFiltersettings(int& host_FREchoFilter, std::string& host_LFPangleRangeFilter, std::string& host_LFPlayerFilter, sick_scansegment_xd::MsgpackValidatorFilterConfig& msgpack_validator_filter_settings, const std::string& scanner_type);
187 
195  bool writeMultiScanFiltersettings(int host_FREchoFilter, const std::string& host_LFPangleRangeFilter, const std::string& host_LFPlayerFilter, const std::string& host_LFPintervalFilter, const std::string& scanner_type);
196 
197 #endif // defined SCANSEGMENT_XD_SUPPORT && SCANSEGMENT_XD_SUPPORT > 0
198 
206  bool sendSopasAndCheckAnswer(const std::string& sopasCmd, std::vector<unsigned char>& sopasReplyBin, std::string& sopasReplyString);
207 
215  static float convertHexStringToFloat(const std::string& hex_str, bool hexStrIsBigEndian);
216 
224  static std::string convertFloatToHexString(float value, bool hexStrIsBigEndian);
225 
229  static float convertHexStringToAngleDeg(const std::string& hex_str, bool hexStrIsBigEndian);
230 
234  static std::string convertAngleDegToHexString(float angle_deg, bool hexStrIsBigEndian);
235 
236  protected:
237 
241  bool sendRun();
242 
243  /*
244  * Member data
245  */
246 
258 #if __ROS_VERSION > 0
259  rosServiceServer<sick_scan_srv::FieldSetReadSrv> m_srv_server_FieldSetRead ;
260  rosServiceServer<sick_scan_srv::FieldSetWriteSrv> m_srv_server_FieldSetWrite;
261 #endif
262 
263  }; /* class SickScanServices */
264 
265 } /* namespace sick_scan_xd */
266 #endif /* SICK_SCAN_SERVICES_H_ */
sick_scan_xd::SickScanServices::m_srv_server_SCsoftreset
rosServiceServer< sick_scan_srv::SCsoftresetSrv > m_srv_server_SCsoftreset
service "SCsoftreset", &sick_scan::SickScanServices::serviceCbSCsoftreset
Definition: sick_scan_services.h:256
sick_scan_xd::SickScanServices::m_srv_server_SCreboot
rosServiceServer< sick_scan_srv::SCrebootSrv > m_srv_server_SCreboot
service "SCreboot", &sick_scan::SickScanServices::serviceCbSCreboot
Definition: sick_scan_services.h:255
sick_scan_xd::SickScanServices::convertHexStringToAngleDeg
static float convertHexStringToAngleDeg(const std::string &hex_str, bool hexStrIsBigEndian)
Definition: sick_scan_services.cpp:690
sick_scan_xd::SickScanServices::serviceCbGetContaminationResultROS2
bool serviceCbGetContaminationResultROS2(std::shared_ptr< sick_scan_srv::GetContaminationResultSrv::Request > service_request, std::shared_ptr< sick_scan_srv::GetContaminationResultSrv::Response > service_response)
Definition: sick_scan_services.h:121
sick_scan_xd::SickScanServices::convertFloatToHexString
static std::string convertFloatToHexString(float value, bool hexStrIsBigEndian)
Definition: sick_scan_services.cpp:668
sick_scan_xd::SickScanServices::sendSopasAndCheckAnswer
bool sendSopasAndCheckAnswer(const std::string &sopasCmd, std::vector< unsigned char > &sopasReplyBin, std::string &sopasReplyString)
Definition: sick_scan_services.cpp:207
sick_scan_xd::SickScanServices::serviceCbColaMsg
bool serviceCbColaMsg(sick_scan_srv::ColaMsgSrv::Request &service_request, sick_scan_srv::ColaMsgSrv::Response &service_response)
Definition: sick_scan_services.cpp:248
sick_scan_xd::SickScanServices::~SickScanServices
virtual ~SickScanServices()
Definition: sick_scan_services.cpp:196
sick_scan_xd::SickScanServices
Definition: sick_scan_services.h:76
rosServiceServer< sick_scan_srv::ColaMsgSrv >
sick_scan_xd::SickScanServices::m_client_authorization_pw
std::string m_client_authorization_pw
Definition: sick_scan_services.h:249
sick_scan_xd::SickScanServices::serviceCbLIDoutputstate
bool serviceCbLIDoutputstate(sick_scan_srv::LIDoutputstateSrv::Request &service_request, sick_scan_srv::LIDoutputstateSrv::Response &service_response)
Definition: sick_scan_services.cpp:349
sick_scan_xd::SickScanServices::sendSopasCmdCheckResponse
bool sendSopasCmdCheckResponse(const std::string &sopas_request, const std::string &expected_response)
Definition: sick_scan_services.cpp:414
sick_scan_xd::SickScanServices::m_srv_server_GetContaminationResult
rosServiceServer< sick_scan_srv::GetContaminationResultSrv > m_srv_server_GetContaminationResult
service "GetContaminationResult", &sick_scan::SickScanServices::serviceCbGetContaminationResult
Definition: sick_scan_services.h:252
sick_scan_xd::SickScanServices::serviceCbColaMsgROS2
bool serviceCbColaMsgROS2(std::shared_ptr< sick_scan_srv::ColaMsgSrv::Request > service_request, std::shared_ptr< sick_scan_srv::ColaMsgSrv::Response > service_response)
Definition: sick_scan_services.h:101
sick_scan_xd::SickScanServices::m_common_tcp
sick_scan_xd::SickScanCommonTcp * m_common_tcp
common tcp handler
Definition: sick_scan_services.h:248
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_xd::SickScanServices::m_srv_server_SickScanExit
rosServiceServer< sick_scan_srv::SickScanExitSrv > m_srv_server_SickScanExit
service "SickScanExitSrv", &sick_scan::SickScanServices::serviceCbSickScanExit
Definition: sick_scan_services.h:257
sick_scan_common.h
sick_ros_wrapper.h
sick_scan_xd::SickScanServices::m_srv_server_ColaMsg
rosServiceServer< sick_scan_srv::ColaMsgSrv > m_srv_server_ColaMsg
service "ColaMsg", &sick_scan::SickScanServices::serviceCbColaMsg
Definition: sick_scan_services.h:250
sick_scansegment_xd::MsgpackValidatorFilterConfig
Definition: config.h:69
sick_scan_xd::SickScanServices::SickScanServices
SickScanServices(rosNodePtr nh=0, sick_scan_xd::SickScanCommonTcp *common_tcp=0, ScannerBasicParam *lidar_param=0)
Definition: sick_scan_services.cpp:70
sick_scan_xd::SickScanServices::serviceCbECRChangeArrROS2
bool serviceCbECRChangeArrROS2(std::shared_ptr< sick_scan_srv::ECRChangeArrSrv::Request > service_request, std::shared_ptr< sick_scan_srv::ECRChangeArrSrv::Response > service_response)
Definition: sick_scan_services.h:111
sick_scan_xd::SickScanServices::serviceCbLIDoutputstateROS2
bool serviceCbLIDoutputstateROS2(std::shared_ptr< sick_scan_srv::LIDoutputstateSrv::Request > service_request, std::shared_ptr< sick_scan_srv::LIDoutputstateSrv::Response > service_response)
Definition: sick_scan_services.h:131
sick_scan_xd::SickScanServices::m_srv_server_SCdevicestate
rosServiceServer< sick_scan_srv::SCdevicestateSrv > m_srv_server_SCdevicestate
service "SCdevicestate", &sick_scan::SickScanServices::serviceCbSCdevicestate
Definition: sick_scan_services.h:254
sick_scan_xd::SickScanServices::serviceCbECRChangeArr
bool serviceCbECRChangeArr(sick_scan_srv::ECRChangeArrSrv::Request &service_request, sick_scan_srv::ECRChangeArrSrv::Response &service_response)
Definition: sick_scan_services.cpp:274
sick_scan_common_tcp.h
sick_scan_xd::SickScanServices::serviceCbSCdevicestate
bool serviceCbSCdevicestate(sick_scan_srv::SCdevicestateSrv::Request &service_request, sick_scan_srv::SCdevicestateSrv::Response &service_response)
Definition: sick_scan_services.cpp:1007
sick_scan_xd::SickScanServices::m_srv_server_ECRChangeArr
rosServiceServer< sick_scan_srv::ECRChangeArrSrv > m_srv_server_ECRChangeArr
service "ECRChangeArr", &sick_scan::SickScanServices::serviceCbECRChangeArr
Definition: sick_scan_services.h:251
sick_scan_xd::SickScanServices::sendRun
bool sendRun()
Definition: sick_scan_services.cpp:393
sick_scan_xd::SickScanServices::serviceCbSCdevicestateROS2
bool serviceCbSCdevicestateROS2(std::shared_ptr< sick_scan_srv::SCdevicestateSrv::Request > service_request, std::shared_ptr< sick_scan_srv::SCdevicestateSrv::Response > service_response)
Definition: sick_scan_services.h:141
ros::NodeHandle
sick_scan_xd::SickScanServices::serviceCbSCsoftreset
bool serviceCbSCsoftreset(sick_scan_srv::SCsoftresetSrv::Request &service_request, sick_scan_srv::SCsoftresetSrv::Response &service_response)
Definition: sick_scan_services.cpp:1069
sick_scan_xd::SickScanServices::m_cola_binary
bool m_cola_binary
cola ascii or cola binary messages
Definition: sick_scan_services.h:247
sick_scan_xd::SickScanServices::serviceCbGetContaminationResult
bool serviceCbGetContaminationResult(sick_scan_srv::GetContaminationResultSrv::Request &service_request, sick_scan_srv::GetContaminationResultSrv::Response &service_response)
Definition: sick_scan_services.cpp:300
sick_scan_xd::SickScanServices::serviceCbSCrebootROS2
bool serviceCbSCrebootROS2(std::shared_ptr< sick_scan_srv::SCrebootSrv::Request > service_request, std::shared_ptr< sick_scan_srv::SCrebootSrv::Response > service_response)
Definition: sick_scan_services.h:144
sick_scan_xd::SickScanServices::convertAngleDegToHexString
static std::string convertAngleDegToHexString(float angle_deg, bool hexStrIsBigEndian)
Definition: sick_scan_services.cpp:720
sick_scan_xd::SickScanCommonTcp
Definition: sick_scan_common_tcp.h:91
sick_scan_xd::SickScanServices::serviceCbSCsoftresetROS2
bool serviceCbSCsoftresetROS2(std::shared_ptr< sick_scan_srv::SCsoftresetSrv::Request > service_request, std::shared_ptr< sick_scan_srv::SCsoftresetSrv::Response > service_response)
Definition: sick_scan_services.h:147
sick_scan_base.h
sick_scan_xd::SickScanServices::convertHexStringToFloat
static float convertHexStringToFloat(const std::string &hex_str, bool hexStrIsBigEndian)
Definition: sick_scan_services.cpp:638
config.h
sick_scan_xd::SickScanServices::serviceCbSCreboot
bool serviceCbSCreboot(sick_scan_srv::SCrebootSrv::Request &service_request, sick_scan_srv::SCrebootSrv::Response &service_response)
Definition: sick_scan_services.cpp:1037
sick_scan_xd::SickScanServices::sendAuthorization
bool sendAuthorization()
Definition: sick_scan_services.cpp:372
sick_scan_xd::SickScanServices::serviceCbSickScanExit
bool serviceCbSickScanExit(sick_scan_srv::SickScanExitSrv::Request &service_request, sick_scan_srv::SickScanExitSrv::Response &service_response)
Definition: sick_scan_services.cpp:1101
sick_scan_xd::ScannerBasicParam
Definition: sick_generic_parser.h:110
sick_scan_xd::SickScanServices::serviceCbSickScanExitROS2
bool serviceCbSickScanExitROS2(std::shared_ptr< sick_scan_srv::SickScanExitSrv::Request > service_request, std::shared_ptr< sick_scan_srv::SickScanExitSrv::Response > service_response)
Definition: sick_scan_services.h:150
sick_scan_xd::SickScanServices::m_srv_server_LIDoutputstate
rosServiceServer< sick_scan_srv::LIDoutputstateSrv > m_srv_server_LIDoutputstate
service "LIDoutputstate", &sick_scan::SickScanServices::serviceCbLIDoutputstate
Definition: sick_scan_services.h:253


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