sick_scan_common_tcp.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013, Freiburg University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Osnabrück University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 15.11.2013
30  *
31  * Authors:
32  * Christian Dornhege <c.dornhege@googlemail.com>
33  */
34 
35 #ifndef SICK_TIM3XX_COMMON_TCP_H
36 #define SICK_TIM3XX_COMMON_TCP_H
37 
38 #include <stdio.h>
39 #include <stdlib.h>
40 #include <string.h>
41 #include <boost/asio.hpp>
42 
43 #undef NOMINMAX // to get rid off warning C4005: "NOMINMAX": Makro-Neudefinition
44 
45 #include "sick_scan_common.h"
46 #include "sick_generic_parser.h"
47 #include "template_queue.h"
48 
49 namespace sick_scan
50 {
51 /* class prepared for optimized time stamping */
52 
54  {
55  public:
56  DatagramWithTimeStamp(ros::Time timeStamp_, std::vector<unsigned char> datagram_)
57  {
58  timeStamp = timeStamp_;
59  datagram = datagram_;
60  }
61 
62 // private:
64  std::vector<unsigned char> datagram;
65  };
66 
67 
69  {
70  public:
71  static void disconnectFunctionS(void *obj);
72 
73  SickScanCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, SickGenericParser *parser,
74  char cola_dialect_id);
75 
76  virtual ~SickScanCommonTcp();
77 
78  static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes);
79 
80  void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes);
81 
82  void setReplyMode(int _mode);
83 
84  int getReplyMode();
85 
86  void setEmulSensor(bool _emulFlag);
87 
88  bool getEmulSensor();
89 
90  bool stopScanData();
91 
93 
95 
97 
98  // Queue<std::vector<unsigned char> > recvQueue;
108  protected:
109  void disconnectFunction();
110 
111  void readCallbackFunctionOld(UINT8 *buffer, UINT32 &numOfBytes);
112 
113  virtual int init_device();
114 
115  virtual int close_device();
116 
118  virtual int sendSOPASCommand(const char *request, std::vector<unsigned char> *reply, int cmdLen);
119 
121 
128  virtual int
129  get_datagram(ros::Time &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length,
130  bool isBinaryProtocol, int *numberOfRemainingFifoEntries);
131 
132  // Helpers for boost asio
133  int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read = 0,
134  bool *exception_occured = 0, bool isBinary = false);
135 
136  void handleRead(boost::system::error_code error, size_t bytes_transfered);
137 
138  void checkDeadline();
139 
140  private:
141 
142 
143  // Response buffer
147 
148  // Receive buffer
151 
154 
155  boost::asio::io_service io_service_;
156  boost::asio::ip::tcp::socket socket_;
157  boost::asio::deadline_timer deadline_;
158  boost::asio::streambuf input_buffer_;
159  boost::system::error_code ec_;
161 
162  std::string hostname_;
163  std::string port_;
166  };
167 
168 
169 } /* namespace sick_scan */
170 #endif /* SICK_TIM3XX_COMMON_TCP_H */
171 
UINT8
uint8_t UINT8
Definition: BasicDatatypes.hpp:29
sick_scan::SickScanCommonTcp::handleRead
void handleRead(boost::system::error_code error, size_t bytes_transfered)
Definition: sick_scan_common_tcp.cpp:595
sick_scan::SickScanCommonTcp::m_numberOfBytesInReceiveBuffer
UINT32 m_numberOfBytesInReceiveBuffer
Number of bytes in buffer.
Definition: sick_scan_common_tcp.h:149
sick_scan::SickScanCommonTcp::readCallbackFunction
void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes)
Definition: sick_scan_common_tcp.cpp:493
sick_scan::SickScanCommonTcp::checkDeadline
void checkDeadline()
Definition: sick_scan_common_tcp.cpp:602
sick_scan::SickScanCommonTcp::sendSOPASCommand
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply, int cmdLen)
Send a SOPAS command to the device and print out the response to the console.
Definition: sick_scan_common_tcp.cpp:664
sick_scan::SickScanCommonTcp::m_receiveBuffer
UINT8 m_receiveBuffer[480000]
Low-Level receive buffer for all data.
Definition: sick_scan_common_tcp.h:150
sick_scan::SickGenericParser
Definition: sick_generic_parser.h:159
sick_scan::SickScanCommonTcp::disconnectFunctionS
static void disconnectFunctionS(void *obj)
Definition: sick_scan_common_tcp.cpp:224
sick_scan::SickScanCommonTcp::m_replyMode
int m_replyMode
Definition: sick_scan_common_tcp.h:165
sick_scan::SickScanCommonTcp::recvQueue
Queue< DatagramWithTimeStamp > recvQueue
Definition: sick_scan_common_tcp.h:99
sick_scan::SickScanCommonTcp::m_numberOfBytesInResponseBuffer
UINT32 m_numberOfBytesInResponseBuffer
Number of bytes in buffer.
Definition: sick_scan_common_tcp.h:144
sick_scan::SickScanCommonTcp::socket_
boost::asio::ip::tcp::socket socket_
Definition: sick_scan_common_tcp.h:156
sick_scan::DatagramWithTimeStamp::DatagramWithTimeStamp
DatagramWithTimeStamp(ros::Time timeStamp_, std::vector< unsigned char > datagram_)
Definition: sick_scan_common_tcp.h:56
sick_scan::SickScanCommonTcp::getReplyMode
int getReplyMode()
Definition: sick_scan_common_tcp.cpp:243
sick_scan::SickScanCommonTcp::m_receiveDataMutex
Mutex m_receiveDataMutex
Access mutex for buffer.
Definition: sick_scan_common_tcp.h:146
sick_scan::SickScanCommonTcp::m_responseBuffer
UINT8 m_responseBuffer[1024]
Receive buffer for everything except scan data and eval case data.
Definition: sick_scan_common_tcp.h:145
sick_scan::SickScanCommon
Definition: sick_scan_common.h:86
sick_scan::SickScanCommonTcp::get_datagram
virtual int get_datagram(ros::Time &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length, bool isBinaryProtocol, int *numberOfRemainingFifoEntries)
Read a datagram from the device.
Definition: sick_scan_common_tcp.cpp:783
sick_scan::SickScanCommonTcp::m_lastPacketSize
UINT32 m_lastPacketSize
Definition: sick_scan_common_tcp.h:101
sick_scan_common.h
sick_scan::SickScanCommonTcp::getEmulSensor
bool getEmulSensor()
get emulation flag (using emulation instead of "real" scanner - currently implemented for radar
Definition: sick_scan_common_tcp.cpp:277
sick_scan::SickScanCommonTcp::init_device
virtual int init_device()
Definition: sick_scan_common_tcp.cpp:564
sick_scan::SickScanCommonTcp::setEmulSensor
void setEmulSensor(bool _emulFlag)
Set emulation flag (using emulation instead of "real" scanner - currently implemented for radar.
Definition: sick_scan_common_tcp.cpp:267
sick_scan::SickScanCommonTcp::~SickScanCommonTcp
virtual ~SickScanCommonTcp()
Definition: sick_scan_common_tcp.cpp:208
sick_scan::SickScanCommonTcp::bytes_transfered_
size_t bytes_transfered_
Definition: sick_scan_common_tcp.h:160
sick_scan::SickScanCommonTcp::disconnectFunction
void disconnectFunction()
Definition: sick_scan_common_tcp.cpp:219
sick_generic_parser.h
sick_scan::SickScanCommonTcp::port_
std::string port_
Definition: sick_scan_common_tcp.h:163
sick_scan::SickScanCommonTcp::readWithTimeout
int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read=0, bool *exception_occured=0, bool isBinary=false)
Definition: sick_scan_common_tcp.cpp:624
sick_scan::SickScanCommonTcp::m_beVerbose
bool m_beVerbose
Definition: sick_scan_common_tcp.h:152
sick_scan::SickScanCommonTcp::findFrameInReceiveBuffer
SopasEventMessage findFrameInReceiveBuffer()
Definition: sick_scan_common_tcp.cpp:289
sick_scan::SickScanCommonTcp::close_device
virtual int close_device()
Definition: sick_scan_common_tcp.cpp:581
sick_scan::SickScanCommonTcp::hostname_
std::string hostname_
Definition: sick_scan_common_tcp.h:162
sick_scan::SickScanCommonTcp::m_packetBuffer
UINT8 m_packetBuffer[480000]
Definition: sick_scan_common_tcp.h:102
sick_scan
Definition: abstract_parser.cpp:50
Mutex
Definition: Mutex.hpp:15
sick_scan::SickScanCommonTcp::m_alreadyReceivedBytes
UINT32 m_alreadyReceivedBytes
Definition: sick_scan_common_tcp.h:100
sick_scan::SickScanCommonTcp
Definition: sick_scan_common_tcp.h:68
sick_scan::DatagramWithTimeStamp::timeStamp
ros::Time timeStamp
Definition: sick_scan_common_tcp.h:63
sick_scan::SickScanCommonTcp::m_emulSensor
bool m_emulSensor
Definition: sick_scan_common_tcp.h:153
sick_scan::SickScanCommonTcp::stopScanData
bool stopScanData()
Definition: sick_scan_common_tcp.cpp:589
sick_scan::DatagramWithTimeStamp::datagram
std::vector< unsigned char > datagram
Definition: sick_scan_common_tcp.h:64
ros::Time
sick_scan::SickScanCommonTcp::readCallbackFunctionOld
void readCallbackFunctionOld(UINT8 *buffer, UINT32 &numOfBytes)
sick_scan::DatagramWithTimeStamp
Definition: sick_scan_common_tcp.h:53
timeStamp
ros::Time const * timeStamp(const M &m)
sick_scan::SickScanCommonTcp::timelimit_
int timelimit_
Definition: sick_scan_common_tcp.h:164
Queue
Definition: template_queue.h:12
sick_scan::SickScanCommonTcp::io_service_
boost::asio::io_service io_service_
Definition: sick_scan_common_tcp.h:155
sick_scan::SickScanCommonTcp::deadline_
boost::asio::deadline_timer deadline_
Definition: sick_scan_common_tcp.h:157
sick_scan::SickScanCommonTcp::processFrame
void processFrame(ros::Time timeStamp, SopasEventMessage &frame)
Definition: sick_scan_common_tcp.cpp:466
sick_scan::SickScanCommonTcp::readCallbackFunctionS
static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes)
Definition: sick_scan_common_tcp.cpp:232
UINT32
uint32_t UINT32
Definition: BasicDatatypes.hpp:26
sick_scan::SickScanCommonTcp::SickScanCommonTcp
SickScanCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, SickGenericParser *parser, char cola_dialect_id)
Definition: sick_scan_common_tcp.cpp:171
sick_scan::SickScanCommonTcp::input_buffer_
boost::asio::streambuf input_buffer_
Definition: sick_scan_common_tcp.h:158
sick_scan::SickScanCommonTcp::ec_
boost::system::error_code ec_
Definition: sick_scan_common_tcp.h:159
SopasEventMessage
Class that represents a message that was sent by a sensor. (Event message)
Definition: sick_scan_common_nw.h:130
sick_scan::SickScanCommonTcp::numberOfDatagramInInputFifo
int numberOfDatagramInInputFifo()
Definition: sick_scan_common_tcp.cpp:617
template_queue.h
sick_scan::SickScanCommonTcp::setReplyMode
void setReplyMode(int _mode)
Definition: sick_scan_common_tcp.cpp:238


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