test_server_thread.h
Go to the documentation of this file.
1 /*
2  * @brief sim_loc_test_server_thread implements a simple tcp server thread,
3  * simulating a localization controller for unittests. It runs a thread to listen
4  * and accept tcp connections from clients and generates telegrams to test
5  * the ros driver for sim localization.
6  *
7  * Copyright (C) 2019 Ing.-Buero Dr. Michael Lehning, Hildesheim
8  * Copyright (C) 2019 SICK AG, Waldkirch
9  *
10  * Licensed under the Apache License, Version 2.0 (the "License");
11  * you may not use this file except in compliance with the License.
12  * You may obtain a copy of the License at
13  *
14  * http://www.apache.org/licenses/LICENSE-2.0
15  *
16  * Unless required by applicable law or agreed to in writing, software
17  * distributed under the License is distributed on an "AS IS" BASIS,
18  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
19  * See the License for the specific language governing permissions and
20  * limitations under the License.
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 SICK AG 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 Ing.-Buero Dr. Michael Lehning 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  *
39  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
40  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
41  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
42  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
43  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
44  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
45  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
46  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
47  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
48  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
49  * POSSIBILITY OF SUCH DAMAGE.
50  *
51  * Authors:
52  * Michael Lehning <michael.lehning@lehning.de>
53  *
54  * Copyright 2019 SICK AG
55  * Copyright 2019 Ing.-Buero Dr. Michael Lehning
56  *
57  */
58 #ifndef __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED
59 #define __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED
60 
61 #include <boost/asio/buffer.hpp>
62 #include <boost/asio/io_service.hpp>
63 #include <boost/asio/ip/tcp.hpp>
64 #include <boost/asio/read.hpp>
65 #include <boost/asio/write.hpp>
66 #include <boost/thread.hpp>
67 #include <boost/thread/mutex.hpp>
68 #include <boost/thread/recursive_mutex.hpp>
69 #include <list>
70 
71 #include "sick_scan/fifo_buffer.h"
72 #include "sick_scan/utils.h"
73 
74 namespace sick_scan
75 {
81  {
82  public:
83 
90  TestServerThread(ROS::NodePtr nh = 0, int ip_port_results = 2201, int ip_port_cola = 2111);
91 
95  virtual ~TestServerThread();
96 
101  virtual bool start(void);
102 
107  virtual bool stop(void);
108 
114  void messageCbResultPortTelegrams(const sick_scan::SickLocResultPortTelegramMsg & msg);
116  virtual void messageCbResultPortTelegramsROS2(const std::shared_ptr<sick_scan::SickLocResultPortTelegramMsg> msg) { messageCbResultPortTelegrams(*msg); }
117 
118  protected:
119 
124  {
125  public:
126  ServerColaRequest(const std::vector<uint8_t> & data = std::vector<uint8_t>(), bool ascii = false) : telegram_data(data), telegram_is_ascii(ascii) {}
128  std::vector<uint8_t> telegram_data;
129  };
130 
131  typedef boost::thread* thread_ptr;
132  typedef boost::asio::ip::tcp::socket* socket_ptr;
133 
137  void closeScandataThread(void);
138 
143  virtual void closeTcpConnections(bool force_shutdown = false);
144 
149  void closeSocket(socket_ptr & p_socket);
150 
154  void closeWorkerThreads(void);
155 
160  virtual void runConnectionThreadResultCb(void);
161 
166  virtual void runConnectionThreadColaCb(void);
167 
172  template<typename Callable> void runConnectionThreadGenericCb(boost::asio::ip::tcp::acceptor & tcp_acceptor_results, int ip_port_results, Callable thread_function_cb);
173 
179  virtual void runWorkerThreadResultCb(boost::asio::ip::tcp::socket* p_socket);
180 
187  virtual void runWorkerThreadColaCb(boost::asio::ip::tcp::socket* p_socket);
188 
195  virtual void runWorkerThreadScandataCb(boost::asio::ip::tcp::socket* p_socket);
196 
200  virtual void runErrorSimulationThreadCb(void);
201 
206  void errorSimulationWait(double seconds);
207 
214  bool errorSimulationWaitForTelegramReceived(double timeout_seconds, sick_scan::SickLocResultPortTelegramMsg & telegram_msg);
215 
216  /*
217  * member data
218  */
219 
229  boost::asio::io_service m_ioservice;
230  boost::asio::ip::tcp::acceptor m_tcp_acceptor_results;
231  boost::asio::ip::tcp::acceptor m_tcp_acceptor_cola;
232  std::list<boost::asio::ip::tcp::socket*> m_tcp_sockets;
233  std::list<thread_ptr> m_tcp_worker_threads;
236  sick_scan::SickLocResultPortTestcaseMsgPublisher m_result_testcases_publisher;
239  std::string m_scandatafiles;
240  std::string m_scandatatypes;
241  std::string m_scanner_type;
242 
243  /*
244  * configuration and member data for error simulation
245  */
246 
247  typedef enum ERROR_SIMULATION_ENUM
248  {
249  NO_ERROR = 0,
256 
262 
263  };
264 
265 } // namespace sick_scan
266 #endif // __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED
sick_scan::TestServerThread::runWorkerThreadScandataCb
virtual void runWorkerThreadScandataCb(boost::asio::ip::tcp::socket *p_socket)
Definition: test_server_thread.cpp:535
sick_scan::TestServerThread::m_tcp_acceptor_cola
boost::asio::ip::tcp::acceptor m_tcp_acceptor_cola
boost acceptor for tcp clients for command requests and responses
Definition: test_server_thread.h:231
sick_scan::TestServerThread::m_tcp_sockets
std::list< boost::asio::ip::tcp::socket * > m_tcp_sockets
list of tcp sockets (one socket for each tcp client)
Definition: test_server_thread.h:232
sick_scan::TestServerThread::m_error_simulation_enabled
bool m_error_simulation_enabled
default: false (no error simulation), if true, test server simulates errors and communication failure...
Definition: test_server_thread.h:258
msg
msg
sick_scan::TestServerThread::m_error_simulation_thread_running
bool m_error_simulation_thread_running
true: m_error_simulation_thread is running, otherwise false
Definition: test_server_thread.h:260
sick_scan::TestServerThread::closeWorkerThreads
void closeWorkerThreads(void)
Definition: test_server_thread.cpp:269
sick_scan::TestServerThread::m_tcp_connection_thread_results
thread_ptr m_tcp_connection_thread_results
thread to accept tcp clients for result port telegrams
Definition: test_server_thread.h:223
sick_scan::TestServerThread::m_start_scandata_delay
double m_start_scandata_delay
delay between scandata activation ("LMCstartmeas" request) and first scandata message,...
Definition: test_server_thread.h:227
sick_scan::TestServerThread::start
virtual bool start(void)
Definition: test_server_thread.cpp:122
sick_scan::TestServerThread::m_tcp_connection_thread_running
bool m_tcp_connection_thread_running
true: m_tcp_connection_thread is running, otherwise false
Definition: test_server_thread.h:228
sick_scan::TestServerThread::m_result_telegram_rate
double m_result_telegram_rate
frequency to generate and send result port telegrams, default: 10 Hz
Definition: test_server_thread.h:222
sick_scan::TestServerThread::ServerColaRequest
Definition: test_server_thread.h:123
sick_scan::TestServerThread::runConnectionThreadResultCb
virtual void runConnectionThreadResultCb(void)
Definition: test_server_thread.cpp:296
sick_scan::TestServerThread::runWorkerThreadResultCb
virtual void runWorkerThreadResultCb(boost::asio::ip::tcp::socket *p_socket)
Definition: test_server_thread.cpp:366
sick_scan::TestServerThread::m_tcp_worker_threads
std::list< thread_ptr > m_tcp_worker_threads
list of tcp worker thread (one thread for each tcp client, generating telegrams)
Definition: test_server_thread.h:233
sick_scan::TestServerThread::ServerColaRequest::telegram_is_ascii
bool telegram_is_ascii
true: received telegram_data is Cola-Ascii encoded, false: received telegram_data is Cola-Binary enco...
Definition: test_server_thread.h:127
sick_scan::TestServerThread::m_tcp_connection_thread_cola
thread_ptr m_tcp_connection_thread_cola
thread to accept tcp clients for command requests and responses
Definition: test_server_thread.h:224
sick_scan::TestServerThread::errorSimulationWait
void errorSimulationWait(double seconds)
Definition: test_server_thread.cpp:618
sick_scan::TestServerThread::runWorkerThreadColaCb
virtual void runWorkerThreadColaCb(boost::asio::ip::tcp::socket *p_socket)
Definition: test_server_thread.cpp:441
data
data
sick_scan::TestServerThread::m_ioservice
boost::asio::io_service m_ioservice
boost io service for tcp connections
Definition: test_server_thread.h:229
utils.h
sick_scan::TestServerThread::messageCbResultPortTelegramsROS2
virtual void messageCbResultPortTelegramsROS2(const std::shared_ptr< sick_scan::SickLocResultPortTelegramMsg > msg)
Definition: test_server_thread.h:116
sick_scan::TestServerThread::m_worker_thread_running
bool m_worker_thread_running
true: worker threads started, otherwise false
Definition: test_server_thread.h:235
sick_scan::TestServerThread::SEND_INVALID_TELEGRAMS
@ SEND_INVALID_TELEGRAMS
Testserver sends invalid telegrams (invalid data, false checksums, etc.)
Definition: test_server_thread.h:254
sick_scan::TestServerThread::~TestServerThread
virtual ~TestServerThread()
Definition: test_server_thread.cpp:113
sick_scan::TestServerThread::m_tcp_acceptor_results
boost::asio::ip::tcp::acceptor m_tcp_acceptor_results
boost acceptor for tcp clients for result telegrams
Definition: test_server_thread.h:230
sick_scan::TestServerThread::closeSocket
void closeSocket(socket_ptr &p_socket)
Definition: test_server_thread.cpp:238
sick_scan::TestServerThread::errorSimulationWaitForTelegramReceived
bool errorSimulationWaitForTelegramReceived(double timeout_seconds, sick_scan::SickLocResultPortTelegramMsg &telegram_msg)
Definition: test_server_thread.cpp:633
sick_scan::TestServerThread::runConnectionThreadGenericCb
void runConnectionThreadGenericCb(boost::asio::ip::tcp::acceptor &tcp_acceptor_results, int ip_port_results, Callable thread_function_cb)
Definition: test_server_thread.cpp:314
sick_scan
Definition: abstract_parser.cpp:50
sick_scan::TestServerThread::m_last_telegram_received
sick_scan::SetGet< sick_scan::SickLocResultPortTelegramMsg > m_last_telegram_received
last telegram message received from sick_scan driver
Definition: test_server_thread.h:261
sick_scan::TestServerThread::stop
virtual bool stop(void)
Definition: test_server_thread.cpp:151
fifo_buffer.h
sick_scan::TestServerThread::m_ip_port_results
int m_ip_port_results
ip port for result telegrams, default: The localization controller uses IP port number 2201 to send l...
Definition: test_server_thread.h:220
sick_scan::TestServerThread::m_tcp_send_scandata_thread
thread_ptr m_tcp_send_scandata_thread
thread to send scandata and scandatamon tcp messages
Definition: test_server_thread.h:225
sick_scan::TestServerThread::m_scandatatypes
std::string m_scandatatypes
comma separated list of scandata message types, f.e. "sSN LMDscandata,sSN LMDscandatamon"
Definition: test_server_thread.h:240
sick_scan::TestServerThread::thread_ptr
boost::thread * thread_ptr
shortcut for pointer to boost::thread
Definition: test_server_thread.h:131
sick_scan::TestServerThread::m_ip_port_cola
int m_ip_port_cola
ip port for for command requests and responses, default: The localization controller uses IP port num...
Definition: test_server_thread.h:221
sick_scan::TestServerThread::closeScandataThread
void closeScandataThread(void)
Definition: test_server_thread.cpp:197
sick_scan::TestServerThread::m_scandatafiles
std::string m_scandatafiles
comma separated list of jsonfiles to emulate scandata messages, f.e. "tim781s_scandata....
Definition: test_server_thread.h:239
sick_scan::TestServerThread
Definition: test_server_thread.h:80
sick_scan::TestServerThread::DONT_ACCECPT
@ DONT_ACCECPT
Testserver does not accecpt tcp clients.
Definition: test_server_thread.h:251
sick_scan::TestServerThread::DONT_SEND
@ DONT_SEND
Testserver does not send any data.
Definition: test_server_thread.h:252
sick_scan::TestServerThread::ERROR_SIMULATION_ENUM
ERROR_SIMULATION_ENUM
< enumerates testcases for simulation of communication errors
Definition: test_server_thread.h:247
sick_scan::TestServerThread::m_scanner_type
std::string m_scanner_type
currently supported: "sick_lms_5xx", "sick_tim_7xx"
Definition: test_server_thread.h:241
sick_scan::TestServerThread::m_tcp_worker_threads_mutex
boost::mutex m_tcp_worker_threads_mutex
mutex to protect m_tcp_worker_threads
Definition: test_server_thread.h:234
sick_scan::TestServerThread::m_demo_move_in_circles
bool m_demo_move_in_circles
true: simulate a sensor moving in circles, false (default): create random based result port telegrams
Definition: test_server_thread.h:238
sick_scan::SetGet< ERROR_SIMULATION_FLAG >
sick_scan::TestServerThread::closeTcpConnections
virtual void closeTcpConnections(bool force_shutdown=false)
Definition: test_server_thread.cpp:212
sick_scan::TestServerThread::messageCbResultPortTelegrams
void messageCbResultPortTelegrams(const sick_scan::SickLocResultPortTelegramMsg &msg)
Definition: test_server_thread.cpp:287
ROS::seconds
double seconds(ROS::Duration duration)
Definition: ros_wrapper.cpp:180
sick_scan::TestServerThread::m_result_testcases_frame_id
std::string m_result_testcases_frame_id
ros frame id of testcase messages (type SickLocResultPortTestcaseMsg), default: "result_testcases"
Definition: test_server_thread.h:237
sick_scan::TestServerThread::runConnectionThreadColaCb
virtual void runConnectionThreadColaCb(void)
Definition: test_server_thread.cpp:305
sick_scan::TestServerThread::m_tcp_send_scandata_thread_running
bool m_tcp_send_scandata_thread_running
true: m_tcp_send_scandata_thread is running, otherwise false
Definition: test_server_thread.h:226
sick_scan::TestServerThread::m_error_simulation_flag
sick_scan::SetGet< ERROR_SIMULATION_FLAG > m_error_simulation_flag
current error simulation flag, default: NO_ERROR
Definition: test_server_thread.h:257
sick_scan::TestServerThread::m_result_testcases_publisher
sick_scan::SickLocResultPortTestcaseMsgPublisher m_result_testcases_publisher
ros publisher for testcases with result port telegrams (type SickLocResultPortTestcaseMsg)
Definition: test_server_thread.h:236
sick_scan::TestServerThread::socket_ptr
boost::asio::ip::tcp::socket * socket_ptr
shortcut for pointer to boost::asio::ip::tcp::socket
Definition: test_server_thread.h:132
sick_scan::TestServerThread::runErrorSimulationThreadCb
virtual void runErrorSimulationThreadCb(void)
Definition: test_server_thread.cpp:651
sick_scan::TestServerThread::m_error_simulation_thread
thread_ptr m_error_simulation_thread
thread to run error simulation, switches m_error_simulation_flag through the error test cases
Definition: test_server_thread.h:259
sick_scan::TestServerThread::ServerColaRequest::telegram_data
std::vector< uint8_t > telegram_data
received telegram_data (Cola-Ascii or Cola-Binary)
Definition: test_server_thread.h:128
sick_scan::TestServerThread::TestServerThread
TestServerThread(ROS::NodePtr nh=0, int ip_port_results=2201, int ip_port_cola=2111)
Definition: test_server_thread.cpp:74
sick_scan::TestServerThread::ERROR_SIMULATION_FLAG
enum sick_scan::TestServerThread::ERROR_SIMULATION_ENUM ERROR_SIMULATION_FLAG
< enumerates testcases for simulation of communication errors
sick_scan::TestServerThread::SEND_RANDOM_TCP
@ SEND_RANDOM_TCP
Testserver sends invalid random tcp packets.
Definition: test_server_thread.h:253
sick_scan::TestServerThread::NO_ERROR
@ NO_ERROR
Default: run test server without simulated errors, send valid telegrams.
Definition: test_server_thread.h:249
sick_scan::TestServerThread::DONT_LISTEN
@ DONT_LISTEN
Testserver does not open listening port.
Definition: test_server_thread.h:250


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19