input.cc
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  Copyright (C) 2010-2013 Austin Robot Technology, and others
10  All rights reserved.
11 
12 
13 Modified BSD License:
14 --------------------
15 
16  Redistribution and use in source and binary forms, with or without
17  modification, are permitted provided that the following conditions
18  are met:
19 
20  * Redistributions of source code must retain the above copyright
21  notice, this list of conditions and the following disclaimer.
22 
23  * Redistributions in binary form must reproduce the above
24  copyright notice, this list of conditions and the following
25  disclaimer in the documentation and/or other materials provided
26  with the distribution.
27 
28  * Neither the names of the University of Texas at Austin, nor
29  Austin Robot Technology, nor the names of other contributors may
30  be used to endorse or promote products derived from this
31  software without specific prior written permission.
32 
33  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
34  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
35  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
36  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
37  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
39  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
40  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
41  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
42  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
43  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
44 POSSIBILITY OF SUCH DAMAGE.
45  */
46 
60 #include "input.h"
61 
62 extern volatile sig_atomic_t flag;
63 namespace rslidar_driver
64 {
65 static const size_t packet_size = sizeof(rslidar_msgs::rslidarPacket().data);
66 
68 // Input base class implementation
70 
76 Input::Input(ros::NodeHandle private_nh, uint16_t port) : private_nh_(private_nh), port_(port)
77 {
78  private_nh.param("device_ip", devip_str_, std::string(""));
79  if (!devip_str_.empty())
80  ROS_INFO_STREAM("Only accepting packets from IP address: " << devip_str_);
81 }
82 
84 // InputSocket class implementation
86 
92 InputSocket::InputSocket(ros::NodeHandle private_nh, uint16_t port) : Input(private_nh, port)
93 {
94  sockfd_ = -1;
95 
96  if (!devip_str_.empty())
97  {
98  inet_aton(devip_str_.c_str(), &devip_);
99  }
100 
101  ROS_INFO_STREAM("Opening UDP socket: port " << port);
102  sockfd_ = socket(PF_INET, SOCK_DGRAM, 0);
103  if (sockfd_ == -1)
104  {
105  perror("socket"); // TODO: ROS_ERROR errno
106  return;
107  }
108 
109  int opt = 1;
110  if (setsockopt(sockfd_, SOL_SOCKET, SO_REUSEADDR, (const void*)&opt, sizeof(opt)))
111  {
112  perror("setsockopt error!\n");
113  return;
114  }
115 
116  sockaddr_in my_addr; // my address information
117  memset(&my_addr, 0, sizeof(my_addr)); // initialize to zeros
118  my_addr.sin_family = AF_INET; // host byte order
119  my_addr.sin_port = htons(port); // port in network byte order
120  my_addr.sin_addr.s_addr = INADDR_ANY; // automatically fill in my IP
121 
122  if (bind(sockfd_, (sockaddr*)&my_addr, sizeof(sockaddr)) == -1)
123  {
124  perror("bind"); // TODO: ROS_ERROR errno
125  return;
126  }
127 
128  if (fcntl(sockfd_, F_SETFL, O_NONBLOCK | FASYNC) < 0)
129  {
130  perror("non-block");
131  return;
132  }
133 }
134 
137 {
138  (void)close(sockfd_);
139 }
140 
142 int InputSocket::getPacket(rslidar_msgs::rslidarPacket* pkt, const double time_offset)
143 {
144  double time1 = ros::Time::now().toSec();
145  struct pollfd fds[1];
146  fds[0].fd = sockfd_;
147  fds[0].events = POLLIN;
148  static const int POLL_TIMEOUT = 1000; // one second (in msec)
149 
150  sockaddr_in sender_address;
151  socklen_t sender_address_len = sizeof(sender_address);
152  while (flag == 1)
153  {
154  // Receive packets that should now be available from the
155  // socket using a blocking read.
156  // poll() until input available
157  do
158  {
159  int retval = poll(fds, 1, POLL_TIMEOUT);
160  if (retval < 0) // poll() error?
161  {
162  if (errno != EINTR)
163  ROS_ERROR("poll() error: %s", strerror(errno));
164  return 1;
165  }
166  if (retval == 0) // poll() timeout?
167  {
168  ROS_WARN("Rslidar poll() timeout");
169 
170  char buffer_data[8] = "re-con";
171  memset(&sender_address, 0, sender_address_len); // initialize to zeros
172  sender_address.sin_family = AF_INET; // host byte order
173  sender_address.sin_port = htons(MSOP_DATA_PORT_NUMBER); // port in network byte order, set any value
174  sender_address.sin_addr.s_addr = devip_.s_addr; // automatically fill in my IP
175  sendto(sockfd_, &buffer_data, strlen(buffer_data), 0, (sockaddr*)&sender_address, sender_address_len);
176  return 1;
177  }
178  if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) || (fds[0].revents & POLLNVAL)) // device error?
179  {
180  ROS_ERROR("poll() reports Rslidar error");
181  return 1;
182  }
183  } while ((fds[0].revents & POLLIN) == 0);
184  ssize_t nbytes = recvfrom(sockfd_, &pkt->data[0], packet_size, 0, (sockaddr*)&sender_address, &sender_address_len);
185 
186  if (nbytes < 0)
187  {
188  if (errno != EWOULDBLOCK)
189  {
190  perror("recvfail");
191  ROS_INFO("recvfail");
192  return 1;
193  }
194  }
195  else if ((size_t)nbytes == packet_size)
196  {
197  if (devip_str_ != "" && sender_address.sin_addr.s_addr != devip_.s_addr)
198  continue;
199  else
200  break; // done
201  }
202 
203  ROS_DEBUG_STREAM("incomplete rslidar packet read: " << nbytes << " bytes");
204  }
205  if (flag == 0)
206  {
207  abort();
208  }
209  // Average the times at which we begin and end reading. Use that to
210  // estimate when the scan occurred. Add the time offset.
211  double time2 = ros::Time::now().toSec();
212  pkt->stamp = ros::Time((time2 + time1) / 2.0 + time_offset);
213 
214  return 0;
215 }
216 
218 // InputPCAP class implementation
220 
228 InputPCAP::InputPCAP(ros::NodeHandle private_nh, uint16_t port, double packet_rate, std::string filename,
229  bool read_once, bool read_fast, double repeat_delay)
230  : Input(private_nh, port), packet_rate_(packet_rate), filename_(filename)
231 {
232  pcap_ = NULL;
233  empty_ = true;
234 
235  // get parameters using private node handle
236  private_nh.param("read_once", read_once_, false);
237  private_nh.param("read_fast", read_fast_, false);
238  private_nh.param("repeat_delay", repeat_delay_, 0.0);
239 
240  if (read_once_)
241  ROS_INFO("Read input file only once.");
242  if (read_fast_)
243  ROS_INFO("Read input file as quickly as possible.");
244  if (repeat_delay_ > 0.0)
245  ROS_INFO("Delay %.3f seconds before repeating input file.", repeat_delay_);
246 
247  // Open the PCAP dump file
248  // ROS_INFO("Opening PCAP file \"%s\"", filename_.c_str());
249  ROS_INFO_STREAM("Opening PCAP file " << filename_);
250  if ((pcap_ = pcap_open_offline(filename_.c_str(), errbuf_)) == NULL)
251  {
252  ROS_FATAL("Error opening rslidar socket dump file.");
253  return;
254  }
255 
256  std::stringstream filter;
257  if (devip_str_ != "") // using specific IP?
258  {
259  filter << "src host " << devip_str_ << " && ";
260  }
261  filter << "udp dst port " << port;
262  pcap_compile(pcap_, &pcap_packet_filter_, filter.str().c_str(), 1, PCAP_NETMASK_UNKNOWN);
263 }
264 
267 {
268  pcap_close(pcap_);
269 }
270 
272 int InputPCAP::getPacket(rslidar_msgs::rslidarPacket* pkt, const double time_offset)
273 {
274  struct pcap_pkthdr* header;
275  const u_char* pkt_data;
276 
277  while (flag == 1)
278  {
279  int res;
280  if ((res = pcap_next_ex(pcap_, &header, &pkt_data)) >= 0)
281  {
282  // Skip packets not for the correct port and from the
283  // selected IP address.
284  if (!devip_str_.empty() && (0 == pcap_offline_filter(&pcap_packet_filter_, header, pkt_data)))
285  continue;
286 
287  // Keep the reader from blowing through the file.
288  if (read_fast_ == false)
290 
291  memcpy(&pkt->data[0], pkt_data + 42, packet_size);
292  pkt->stamp = ros::Time::now(); // time_offset not considered here, as no
293  // synchronization required
294  empty_ = false;
295  return 0; // success
296  }
297 
298  if (empty_) // no data in file?
299  {
300  ROS_WARN("Error %d reading rslidar packet: %s", res, pcap_geterr(pcap_));
301  return -1;
302  }
303 
304  if (read_once_)
305  {
306  ROS_INFO("end of file reached -- done reading.");
307  return -1;
308  }
309 
310  if (repeat_delay_ > 0.0)
311  {
312  ROS_INFO("end of file reached -- delaying %.3f seconds.", repeat_delay_);
313  usleep(rint(repeat_delay_ * 1000000.0));
314  }
315 
316  ROS_DEBUG("replaying rslidar dump file");
317 
318  // I can't figure out how to rewind the file, because it
319  // starts with some kind of header. So, close the file
320  // and reopen it with pcap.
321  pcap_close(pcap_);
322  pcap_ = pcap_open_offline(filename_.c_str(), errbuf_);
323  empty_ = true; // maybe the file disappeared?
324  } // loop back and try again
325 
326  if (flag == 0)
327  {
328  abort();
329  }
330 }
331 }
ros::Rate packet_rate_
Definition: input.h:146
#define ROS_FATAL(...)
static const size_t packet_size
Definition: input.cc:65
std::string devip_str_
Definition: input.h:109
virtual int getPacket(rslidar_msgs::rslidarPacket *pkt, const double time_offset)
Get one rslidar packet.
Definition: input.cc:142
static uint16_t MSOP_DATA_PORT_NUMBER
Definition: input.h:83
volatile sig_atomic_t flag
Definition: nodelet.cc:59
InputPCAP(ros::NodeHandle private_nh, uint16_t port=MSOP_DATA_PORT_NUMBER, double packet_rate=0.0, std::string filename="", bool read_once=false, bool read_fast=false, double repeat_delay=0.0)
constructor
Definition: input.cc:228
#define ROS_WARN(...)
virtual int getPacket(rslidar_msgs::rslidarPacket *pkt, const double time_offset)
Get one rslidar packet.
Definition: input.cc:272
The Input class,.
Definition: input.h:95
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_DEBUG_STREAM(args)
InputSocket(ros::NodeHandle private_nh, uint16_t port=MSOP_DATA_PORT_NUMBER)
constructor
Definition: input.cc:92
bool sleep()
Input(ros::NodeHandle private_nh, uint16_t port)
constructor
Definition: input.cc:76
#define ROS_INFO_STREAM(args)
static Time now()
bpf_program pcap_packet_filter_
Definition: input.h:149
char errbuf_[PCAP_ERRBUF_SIZE]
Definition: input.h:150
#define ROS_ERROR(...)
std::string filename_
Definition: input.h:147
virtual ~InputSocket()
destructor
Definition: input.cc:136
#define ROS_DEBUG(...)


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