58 #ifndef __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED 59 #define __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED 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> 90 TestServerThread(ROS::NodePtr nh = 0,
int ip_port_results = 2201,
int ip_port_cola = 2111);
101 virtual bool start(
void);
107 virtual bool stop(
void);
172 template<
typename Callable>
void runConnectionThreadGenericCb(boost::asio::ip::tcp::acceptor & tcp_acceptor_results,
int ip_port_results, Callable thread_function_cb);
266 #endif // __SIM_LOC_TEST_SERVER_THREAD_H_INCLUDED Default: run test server without simulated errors, send valid telegrams.
virtual void runErrorSimulationThreadCb(void)
void errorSimulationWait(double seconds)
virtual void runWorkerThreadResultCb(boost::asio::ip::tcp::socket *p_socket)
bool errorSimulationWaitForTelegramReceived(double timeout_seconds, sick_scan::SickLocResultPortTelegramMsg &telegram_msg)
void closeSocket(socket_ptr &p_socket)
int m_ip_port_results
ip port for result telegrams, default: The localization controller uses IP port number 2201 to send l...
void closeScandataThread(void)
boost::asio::ip::tcp::acceptor m_tcp_acceptor_cola
boost acceptor for tcp clients for command requests and responses
boost::mutex m_tcp_worker_threads_mutex
mutex to protect m_tcp_worker_threads
virtual void runConnectionThreadColaCb(void)
boost::asio::ip::tcp::socket * socket_ptr
shortcut for pointer to boost::asio::ip::tcp::socket
virtual void closeTcpConnections(bool force_shutdown=false)
thread_ptr m_tcp_connection_thread_results
thread to accept tcp clients for result port telegrams
bool m_tcp_send_scandata_thread_running
true: m_tcp_send_scandata_thread is running, otherwise false
thread_ptr m_error_simulation_thread
thread to run error simulation, switches m_error_simulation_flag through the error test cases ...
Testserver sends invalid telegrams (invalid data, false checksums, etc.)
sick_scan::SetGet< ERROR_SIMULATION_FLAG > m_error_simulation_flag
current error simulation flag, default: NO_ERROR
Testserver does not send any data.
sick_scan::SickLocResultPortTestcaseMsgPublisher m_result_testcases_publisher
ros publisher for testcases with result port telegrams (type SickLocResultPortTestcaseMsg) ...
void runConnectionThreadGenericCb(boost::asio::ip::tcp::acceptor &tcp_acceptor_results, int ip_port_results, Callable thread_function_cb)
thread_ptr m_tcp_send_scandata_thread
thread to send scandata and scandatamon tcp messages
Testserver sends invalid random tcp packets.
TestServerThread(ROS::NodePtr nh=0, int ip_port_results=2201, int ip_port_cola=2111)
sick_scan::SetGet< sick_scan::SickLocResultPortTelegramMsg > m_last_telegram_received
last telegram message received from sick_scan driver
std::list< thread_ptr > m_tcp_worker_threads
list of tcp worker thread (one thread for each tcp client, generating telegrams)
std::string m_scandatafiles
comma separated list of jsonfiles to emulate scandata messages, f.e. "tim781s_scandata.pcapng.json,tim781s_sopas.pcapng.json"
boost::thread * thread_ptr
shortcut for pointer to boost::thread
Testserver does not open listening port.
virtual void runWorkerThreadScandataCb(boost::asio::ip::tcp::socket *p_socket)
void closeWorkerThreads(void)
std::list< boost::asio::ip::tcp::socket * > m_tcp_sockets
list of tcp sockets (one socket for each tcp client)
std::string m_scanner_type
currently supported: "sick_lms_5xx", "sick_tim_7xx"
ERROR_SIMULATION_ENUM
< enumerates testcases for simulation of communication errors
bool m_demo_move_in_circles
true: simulate a sensor moving in circles, false (default): create random based result port telegrams...
bool m_error_simulation_thread_running
true: m_error_simulation_thread is running, otherwise false
Testserver does not accecpt tcp clients.
double m_start_scandata_delay
delay between scandata activation ("LMCstartmeas" request) and first scandata message, default: 1 second
enum sick_scan::TestServerThread::ERROR_SIMULATION_ENUM ERROR_SIMULATION_FLAG
< enumerates testcases for simulation of communication errors
virtual void runConnectionThreadResultCb(void)
thread_ptr m_tcp_connection_thread_cola
thread to accept tcp clients for command requests and responses
virtual void runWorkerThreadColaCb(boost::asio::ip::tcp::socket *p_socket)
bool telegram_is_ascii
true: received telegram_data is Cola-Ascii encoded, false: received telegram_data is Cola-Binary enco...
std::string m_scandatatypes
comma separated list of scandata message types, f.e. "sSN LMDscandata,sSN LMDscandatamon" ...
boost::asio::io_service m_ioservice
boost io service for tcp connections
int m_ip_port_cola
ip port for for command requests and responses, default: The localization controller uses IP port num...
std::vector< uint8_t > telegram_data
received telegram_data (Cola-Ascii or Cola-Binary)
bool m_error_simulation_enabled
default: false (no error simulation), if true, test server simulates errors and communication failure...
virtual void messageCbResultPortTelegramsROS2(const std::shared_ptr< sick_scan::SickLocResultPortTelegramMsg > msg)
bool m_tcp_connection_thread_running
true: m_tcp_connection_thread is running, otherwise false
virtual ~TestServerThread()
void messageCbResultPortTelegrams(const sick_scan::SickLocResultPortTelegramMsg &msg)
bool m_worker_thread_running
true: worker threads started, otherwise false
double m_result_telegram_rate
frequency to generate and send result port telegrams, default: 10 Hz
std::string m_result_testcases_frame_id
ros frame id of testcase messages (type SickLocResultPortTestcaseMsg), default: "result_testcases" ...
ServerColaRequest(const std::vector< uint8_t > &data=std::vector< uint8_t >(), bool ascii=false)
Constructor.
double seconds(ROS::Duration duration)
boost::asio::ip::tcp::acceptor m_tcp_acceptor_results
boost acceptor for tcp clients for result telegrams