sick_scan_common_tcp.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Copyright (C) 2013, Freiburg University
4  * All rights reserved.
5  *
6 * Licensed under the Apache License, Version 2.0 (the "License");
7 * you may not use this file except in compliance with the License.
8 * You may obtain a copy of the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS,
14 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 * See the License for the specific language governing permissions and
16 * limitations under the License.
17 *
18 *
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions are met:
23 *
24 * * Redistributions of source code must retain the above copyright
25 * notice, this list of conditions and the following disclaimer.
26 * * Redistributions in binary form must reproduce the above copyright
27 * notice, this list of conditions and the following disclaimer in the
28 * documentation and/or other materials provided with the distribution.
29 * * Neither the name of Osnabrueck University nor the names of its
30 * contributors may be used to endorse or promote products derived from
31 * this software without specific prior written permission.
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  * Created on: 15.11.2013
52  *
53  * Authors:
54  * Christian Dornhege <c.dornhege@googlemail.com>
55  */
56 
57 #ifndef SICK_TIM3XX_COMMON_TCP_H
58 #define SICK_TIM3XX_COMMON_TCP_H
59 
60 #include <stdio.h>
61 #include <stdlib.h>
62 #include <string.h>
63 
64 #undef NOMINMAX // to get rid off warning C4005: "NOMINMAX": Makro-Neudefinition
65 
66 #include "sick_scan_common.h"
67 #include "sick_generic_parser.h"
68 #include "template_queue.h"
69 
70 namespace sick_scan_xd
71 {
72 /* class prepared for optimized time stamping */
73 
75  {
76  public:
77  DatagramWithTimeStamp(rosTime timeStamp_, std::vector<unsigned char> datagram_)
78  {
79  timeStamp = timeStamp_;
80  datagram = datagram_;
81  }
82 
83  virtual std::vector<unsigned char> & data(void) { return datagram; }
84 
85 // private:
87  std::vector<unsigned char> datagram;
88  };
89 
90 
92  {
93  public:
94  static void disconnectFunctionS(void *obj);
95 
96  SickScanCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, rosNodePtr nh, SickGenericParser *parser,
97  char cola_dialect_id);
98 
99  virtual ~SickScanCommonTcp();
100 
101  static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes);
102 
103  void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes);
104 
105  void setReplyMode(int _mode);
106 
107  int getReplyMode();
108 
109  void setEmulSensor(bool _emulFlag);
110 
111  bool getEmulSensor();
112 
113  bool stopScanData(bool force_immediate_shutdown = false);
114 
116 
118 
120 
121  int reinit(rosNodePtr nh, int delay_millisec);
122 
123  virtual int init_device();
124 
125  virtual int close_device();
126 
127  bool isConnected() { return m_nw.isConnected(); }
128 
129  // Queue<std::vector<unsigned char> > recvQueue;
139  protected:
140  void disconnectFunction();
141 
142  void readCallbackFunctionOld(UINT8 *buffer, UINT32 &numOfBytes);
143 
145  virtual int sendSOPASCommand(const char *request, std::vector<unsigned char> *reply, int cmdLen, bool wait_for_reply = true);
146 
148 
156  virtual int
157  get_datagram(rosNodePtr nh, rosTime &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length,
158  bool isBinaryProtocol, int *numberOfRemainingFifoEntries, const std::vector<std::string>& datagram_keywords);
159 
160  // Helpers for boost asio
161  virtual int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read, const std::vector<std::string>& datagram_keywords);
162 
163  /*void handleRead(boost::system::error_code error, size_t bytes_transfered);*/
164 
165  /*void checkDeadline();*/
166 
167  private:
168 
169 
170  // Response buffer
174 
175  // Receive buffer
178 
181 
182  //boost::asio::io_service io_service_;
183  //boost::asio::deadline_timer deadline_;
184  //boost::asio::streambuf input_buffer_;
185  //boost::system::error_code ec_;
187 
188  std::string hostname_;
189  std::string port_;
192  };
193 
194 
195 } /* namespace sick_scan_xd */
196 #endif /* SICK_TIM3XX_COMMON_TCP_H */
197 
UINT8
uint8_t UINT8
Definition: BasicDatatypes.hpp:75
sick_scan_xd::DatagramWithTimeStamp::DatagramWithTimeStamp
DatagramWithTimeStamp(rosTime timeStamp_, std::vector< unsigned char > datagram_)
Definition: sick_scan_common_tcp.h:77
sick_scan_xd::SickScanCommonTcp::hostname_
std::string hostname_
Definition: sick_scan_common_tcp.h:188
sick_scan_xd::SickScanCommonTcp::m_beVerbose
bool m_beVerbose
Definition: sick_scan_common_tcp.h:179
sick_scan_xd::SickScanCommonTcp::readWithTimeout
virtual int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read, const std::vector< std::string > &datagram_keywords)
Definition: sick_scan_common_tcp.cpp:664
sick_scan_xd::SickScanCommonTcp::reinit
int reinit(rosNodePtr nh, int delay_millisec)
Definition: sick_scan_common_tcp.cpp:240
sick_scan_xd::SickScanCommonTcp::disconnectFunction
void disconnectFunction()
Definition: sick_scan_common_tcp.cpp:253
sick_scan_xd::SickScanCommonTcp::port_
std::string port_
Definition: sick_scan_common_tcp.h:189
sick_scan_xd::SickScanCommonTcp::isConnected
bool isConnected()
Definition: sick_scan_common_tcp.h:127
sick_scan_xd::SickScanCommon
Definition: sick_scan_common.h:102
sick_scan_xd::SickScanCommonTcp::disconnectFunctionS
static void disconnectFunctionS(void *obj)
Definition: sick_scan_common_tcp.cpp:258
sick_scan_xd::SickScanCommonTcp::bytes_transfered_
size_t bytes_transfered_
Definition: sick_scan_common_tcp.h:186
sick_scan_xd::SickScanCommonTcp::m_receiveBuffer
UINT8 m_receiveBuffer[480000]
Low-Level receive buffer for all data.
Definition: sick_scan_common_tcp.h:177
sick_scan_xd::SickGenericParser
Definition: sick_generic_parser.h:239
sick_scan_xd::SickScanCommonTcp::m_receiveDataMutex
Mutex m_receiveDataMutex
Access mutex for buffer.
Definition: sick_scan_common_tcp.h:173
sick_scan_xd::SickScanCommonTcp::timelimit_
int timelimit_
Definition: sick_scan_common_tcp.h:190
sick_scan_xd::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:301
sick_scan_xd::SickScanCommonTcp::findFrameInReceiveBuffer
SopasEventMessage findFrameInReceiveBuffer()
Definition: sick_scan_common_tcp.cpp:323
sick_scan_xd
Definition: abstract_parser.cpp:65
sick_scan_common.h
sick_scan_xd::SickScanCommonTcp::m_packetBuffer
UINT8 m_packetBuffer[480000]
Definition: sick_scan_common_tcp.h:133
sick_scan_xd::SickScanCommonTcp::m_emulSensor
bool m_emulSensor
Definition: sick_scan_common_tcp.h:180
sick_scan_xd::SickScanCommonTcp::readCallbackFunctionOld
void readCallbackFunctionOld(UINT8 *buffer, UINT32 &numOfBytes)
sick_scan_xd::SickScanCommonTcp::init_device
virtual int init_device()
Definition: sick_scan_common_tcp.cpp:598
sick_generic_parser.h
sick_scan_xd::SickScanCommonTcp::m_numberOfBytesInResponseBuffer
UINT32 m_numberOfBytesInResponseBuffer
Number of bytes in buffer.
Definition: sick_scan_common_tcp.h:171
sick_scan_xd::SickScanCommonTcp::recvQueue
Queue< DatagramWithTimeStamp > recvQueue
Definition: sick_scan_common_tcp.h:130
imu_delay_tester.parser
parser
Definition: imu_delay_tester.py:116
sick_scan_xd::SickScanCommonTcp::processFrame
void processFrame(rosTime timeStamp, SopasEventMessage &frame)
Definition: sick_scan_common_tcp.cpp:500
Mutex
Definition: Mutex.hpp:19
sick_scan_xd::SickScanCommonTcp::~SickScanCommonTcp
virtual ~SickScanCommonTcp()
Definition: sick_scan_common_tcp.cpp:233
sick_scan_xd::SickScanCommonTcp::sendSOPASCommand
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply, int cmdLen, bool wait_for_reply=true)
Send a SOPAS command to the device and print out the response to the console.
Definition: sick_scan_common_tcp.cpp:687
ros::NodeHandle
sick_scan_xd::SickScanCommon::m_nw
SickScanCommonNw m_nw
Definition: sick_scan_common.h:341
sick_scan_xd::SickScanCommonTcp::getEmulSensor
bool getEmulSensor()
get emulation flag (using emulation instead of "real" scanner - currently implemented for radar
Definition: sick_scan_common_tcp.cpp:311
sick_scan_xd::SickScanCommonTcp::setReplyMode
void setReplyMode(int _mode)
Definition: sick_scan_common_tcp.cpp:272
sick_scan_xd::SickScanCommonTcp::stopScanData
bool stopScanData(bool force_immediate_shutdown=false)
Definition: sick_scan_common_tcp.cpp:630
sick_scan_xd::SickScanCommonTcp::m_replyMode
int m_replyMode
Definition: sick_scan_common_tcp.h:191
ros::Time
sick_scan_xd::SickScanCommonTcp::getReplyMode
int getReplyMode()
Definition: sick_scan_common_tcp.cpp:277
sick_scan_xd::DatagramWithTimeStamp::timeStamp
rosTime timeStamp
Definition: sick_scan_common_tcp.h:86
sick_scan_xd::SickScanCommonTcp::SickScanCommonTcp
SickScanCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, rosNodePtr nh, SickGenericParser *parser, char cola_dialect_id)
Definition: sick_scan_common_tcp.cpp:197
sick_scan_xd::SickScanCommonTcp::m_responseBuffer
UINT8 m_responseBuffer[1024]
Receive buffer for everything except scan data and eval case data.
Definition: sick_scan_common_tcp.h:172
sick_scan_xd::SickScanCommonTcp
Definition: sick_scan_common_tcp.h:91
Queue
Definition: template_queue.h:13
sick_scan_base.h
sick_scan_xd::SickScanCommonTcp::get_datagram
virtual int get_datagram(rosNodePtr nh, rosTime &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length, bool isBinaryProtocol, int *numberOfRemainingFifoEntries, const std::vector< std::string > &datagram_keywords)
Read a datagram from the device.
Definition: sick_scan_common_tcp.cpp:799
sick_scan_xd::SickScanCommonTcp::readCallbackFunctionS
static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes)
Definition: sick_scan_common_tcp.cpp:266
sick_scan_xd::SickScanCommonTcp::readCallbackFunction
void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes)
Definition: sick_scan_common_tcp.cpp:527
SickScanCommonNw::isConnected
bool isConnected()
Returns true if the tcp connection is established.
Definition: sick_scan_common_nw.cpp:171
sick_scan_xd::SickScanCommonTcp::close_device
virtual int close_device()
Definition: sick_scan_common_tcp.cpp:615
UINT32
uint32_t UINT32
Definition: BasicDatatypes.hpp:72
sick_scan_xd::DatagramWithTimeStamp::data
virtual std::vector< unsigned char > & data(void)
Definition: sick_scan_common_tcp.h:83
roswrap::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:317
sick_scan_xd::SickScanCommonTcp::numberOfDatagramInInputFifo
int numberOfDatagramInInputFifo()
Definition: sick_scan_common_tcp.cpp:657
sick_scan_xd::DatagramWithTimeStamp::datagram
std::vector< unsigned char > datagram
Definition: sick_scan_common_tcp.h:87
SopasEventMessage
Class that represents a message that was sent by a sensor. (Event message)
Definition: sick_scan_common_nw.h:134
template_queue.h
sick_scan_xd::SickScanCommonTcp::m_alreadyReceivedBytes
UINT32 m_alreadyReceivedBytes
Definition: sick_scan_common_tcp.h:131
sick_scan_xd::SickScanCommonTcp::m_lastPacketSize
UINT32 m_lastPacketSize
Definition: sick_scan_common_tcp.h:132
sick_scan_xd::DatagramWithTimeStamp
Definition: sick_scan_common_tcp.h:74
sick_scan_xd::SickScanCommonTcp::m_numberOfBytesInReceiveBuffer
UINT32 m_numberOfBytesInReceiveBuffer
Number of bytes in buffer.
Definition: sick_scan_common_tcp.h:176


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:11