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 
92  int numberOfDatagramInInputFifo();
93 
94  SopasEventMessage findFrameInReceiveBuffer();
95 
96  void processFrame(ros::Time timeStamp, SopasEventMessage &frame);
97 
98  // Queue<std::vector<unsigned char> > recvQueue;
102  UINT8 m_packetBuffer[480000];
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
145  UINT8 m_responseBuffer[1024];
147 
148  // Receive buffer
150  UINT8 m_receiveBuffer[480000];
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 
boost::asio::io_service io_service_
boost::asio::ip::tcp::socket socket_
DatagramWithTimeStamp(ros::Time timeStamp_, std::vector< unsigned char > datagram_)
uint32_t UINT32
Definition: Mutex.hpp:15
Queue< DatagramWithTimeStamp > recvQueue
std::vector< unsigned char > datagram
boost::asio::streambuf input_buffer_
boost::asio::deadline_timer deadline_
UINT32 m_numberOfBytesInReceiveBuffer
Number of bytes in buffer.
boost::system::error_code ec_
UINT32 m_numberOfBytesInResponseBuffer
Number of bytes in buffer.
Class that represents a message that was sent by a sensor. (Event message)
parser
Mutex m_receiveDataMutex
Access mutex for buffer.
uint8_t UINT8


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Wed May 5 2021 03:05:48