Go to the documentation of this file.
57 #ifndef __SIM_LOC_COLA_TRANSMITTER_H_INCLUDED
58 #define __SIM_LOC_COLA_TRANSMITTER_H_INCLUDED
80 ColaTransmitter(
const std::string & server_address =
"192.168.0.1",
int tcp_port = 2111,
double default_receive_timeout = 1);
97 virtual bool close(
void);
181 static bool dataEndWithETX(
const std::vector<uint8_t> & data,
const std::vector<uint8_t> & etx);
203 #endif // __SIM_LOC_COLA_TRANSMITTER_H_INCLUDED
std::thread * m_receiver_thread
thread to receive responses from localization server
void runReceiverThreadCb(void)
ROS::Time receive_timestamp
receive timestamp in seconds (ros timestamp immediately after first response byte received)
double m_receive_timeout
default timeout in seconds for receive functions
virtual bool connect(void)
ColaTransmitter(const std::string &server_address="192.168.0.1", int tcp_port=2111, double default_receive_timeout=1)
static bool dataEndWithETX(const std::vector< uint8_t > &data, const std::vector< uint8_t > &etx)
sick_scan_xd::ClientSocket m_tcp_socket
tcp socket connected to the localization controller
::std_msgs::Time_< std::allocator< void > > Time
bool m_receiver_thread_running
true: m_receiver_thread is running, otherwise false
int m_tcp_port
tcp port of the localization controller, default: 2111 for command requests and 2112 for command resp...
std::string m_server_address
ip address of the localization controller, default: 192.168.0.1
virtual bool stopReceiverThread(void)
virtual bool send(const std::vector< uint8_t > &data, ROS::Time &send_timestamp)
virtual ~ColaTransmitter()
virtual bool waitPopResponse(std::vector< uint8_t > &telegram, double timeout, ROS::Time &receive_timestamp)
virtual bool receive(std::vector< uint8_t > &telegram, double timeout, ROS::Time &receive_timestamp)
sick_scan_xd::FifoBuffer< ColaResponseContainer, std::mutex > m_response_fifo
fifo buffer for receiver thread for responses from localization server
virtual bool startReceiverThread(void)
std::vector< uint8_t > telegram_data
received telegram_data (Cola-Ascii or Cola-Binary)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07