input.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2007 Austin Robot Technology, Patrick Beeson
3  * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
4  * Copyright (C) 2015, Jack O'Quin
5  * Copyright (C) 2017, Robosense, Tony Zhang
6  *
7  *
8  *
9 
10  Copyright (C) 2010-2013 Austin Robot Technology, and others
11  All rights reserved.
12 
13 
14 Modified BSD License:
15 --------------------
16 
17  Redistribution and use in source and binary forms, with or without
18  modification, are permitted provided that the following conditions
19  are met:
20 
21  * Redistributions of source code must retain the above copyright
22  notice, this list of conditions and the following disclaimer.
23 
24  * Redistributions in binary form must reproduce the above
25  copyright notice, this list of conditions and the following
26  disclaimer in the documentation and/or other materials provided
27  with the distribution.
28 
29  * Neither the names of the University of Texas at Austin, nor
30  Austin Robot Technology, nor the names of other contributors may
31  be used to endorse or promote products derived from this
32  software without specific prior written permission.
33 
34  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
35  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
36  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
37  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
38  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
40  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
41  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
42  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
43  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
44  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
45 POSSIBILITY OF SUCH DAMAGE.
46  */
47 
62 #ifndef __RSLIDAR_INPUT_H_
63 #define __RSLIDAR_INPUT_H_
64 
65 #include <unistd.h>
66 #include <stdio.h>
67 #include <pcap.h>
68 #include <netinet/in.h>
69 #include <ros/ros.h>
70 #include <rslidar_msgs/rslidarPacket.h>
71 #include <string>
72 #include <sstream>
73 #include <sys/socket.h>
74 #include <arpa/inet.h>
75 #include <poll.h>
76 #include <errno.h>
77 #include <fcntl.h>
78 #include <sys/file.h>
79 #include <signal.h>
80 
81 namespace rslidar_driver
82 {
83 static uint16_t MSOP_DATA_PORT_NUMBER = 6699; // rslidar default data port on PC
84 static uint16_t DIFOP_DATA_PORT_NUMBER = 7788; // rslidar default difop data port on PC
95 class Input
96 {
97 public:
98  Input(ros::NodeHandle private_nh, uint16_t port);
99 
100  virtual ~Input()
101  {
102  }
103 
104  virtual int getPacket(rslidar_msgs::rslidarPacket* pkt, const double time_offset) = 0;
105 
106 protected:
108  uint16_t port_;
109  std::string devip_str_;
110 };
111 
113 class InputSocket : public Input
114 {
115 public:
116  InputSocket(ros::NodeHandle private_nh, uint16_t port = MSOP_DATA_PORT_NUMBER);
117 
118  virtual ~InputSocket();
119 
120  virtual int getPacket(rslidar_msgs::rslidarPacket* pkt, const double time_offset);
121 
122 private:
123 private:
124  int sockfd_;
125  in_addr devip_;
126 
127  int Ret;
128  int len;
129 };
130 
135 class InputPCAP : public Input
136 {
137 public:
138  InputPCAP(ros::NodeHandle private_nh, uint16_t port = MSOP_DATA_PORT_NUMBER, double packet_rate = 0.0,
139  std::string filename = "", bool read_once = false, bool read_fast = false, double repeat_delay = 0.0);
140 
141  virtual ~InputPCAP();
142 
143  virtual int getPacket(rslidar_msgs::rslidarPacket* pkt, const double time_offset);
144 
145 private:
147  std::string filename_;
148  pcap_t* pcap_;
149  bpf_program pcap_packet_filter_;
150  char errbuf_[PCAP_ERRBUF_SIZE];
151  bool empty_;
155 };
156 }
157 
158 #endif // __RSLIDAR_INPUT_H
ros::Rate packet_rate_
Definition: input.h:146
filename
std::string devip_str_
Definition: input.h:109
static uint16_t MSOP_DATA_PORT_NUMBER
Definition: input.h:83
The Input class,.
Definition: input.h:95
uint16_t port_
Definition: input.h:108
Live rslidar input from socket.
Definition: input.h:113
Input(ros::NodeHandle private_nh, uint16_t port)
constructor
Definition: input.cc:76
rslidar input from PCAP dump file.
Definition: input.h:135
virtual int getPacket(rslidar_msgs::rslidarPacket *pkt, const double time_offset)=0
bpf_program pcap_packet_filter_
Definition: input.h:149
virtual ~Input()
Definition: input.h:100
static uint16_t DIFOP_DATA_PORT_NUMBER
Definition: input.h:84
std::string filename_
Definition: input.h:147
ros::NodeHandle private_nh_
Definition: input.h:107


rslidar_driver
Author(s): Tony Zhang , Tony Zhang
autogenerated on Mon Jun 10 2019 14:41:07