input.h
Go to the documentation of this file.
1 // Copyright (C) 2007, 2009, 2010, 2012, 2015Yaxin Liu, Patrick Beeson, Austin Robot Technology, Jack O'Quin
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
53 #ifndef VELODYNE_DRIVER_INPUT_H
54 #define VELODYNE_DRIVER_INPUT_H
55 
56 #include <unistd.h>
57 #include <stdio.h>
58 #include <pcap.h>
59 #include <netinet/in.h>
60 #include <string>
61 
62 #include <ros/ros.h>
63 #include <velodyne_msgs/VelodynePacket.h>
64 
65 namespace velodyne_driver
66 {
67 
68 static uint16_t DATA_PORT_NUMBER = 2368; // default data port
69 static uint16_t POSITION_PORT_NUMBER = 8308; // default position port
70 
72 class Input
73 {
74 public:
75  Input(ros::NodeHandle private_nh, uint16_t port);
76  virtual ~Input() {}
77 
86  virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
87  const double time_offset) = 0;
88 
89 protected:
91  uint16_t port_;
92  std::string devip_str_;
93  bool gps_time_;
94 };
95 
97 class InputSocket: public Input
98 {
99 public:
100  InputSocket(ros::NodeHandle private_nh,
101  uint16_t port = DATA_PORT_NUMBER);
102  virtual ~InputSocket();
103 
104  virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
105  const double time_offset);
106  void setDeviceIP(const std::string& ip);
107 
108 private:
109  int sockfd_;
110  in_addr devip_;
111 };
112 
113 
119 class InputPCAP: public Input
120 {
121 public:
122  InputPCAP(ros::NodeHandle private_nh,
123  uint16_t port = DATA_PORT_NUMBER,
124  double packet_rate = 0.0,
125  std::string filename = "",
126  bool read_once = false,
127  bool read_fast = false,
128  double repeat_delay = 0.0);
129  virtual ~InputPCAP();
130 
131  virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
132  const double time_offset);
133  void setDeviceIP(const std::string& ip);
134 
135 private:
137  std::string filename_;
138  pcap_t *pcap_;
139  bpf_program pcap_packet_filter_;
140  char errbuf_[PCAP_ERRBUF_SIZE];
141  bool empty_;
146 };
147 
148 } // namespace velodyne_driver
149 
150 #endif // VELODYNE_DRIVER_INPUT_H
velodyne_driver::InputPCAP::pcap_
pcap_t * pcap_
Definition: input.h:138
velodyne_driver::InputSocket::~InputSocket
virtual ~InputSocket()
destructor
Definition: input.cc:142
velodyne_driver::Input::port_
uint16_t port_
Definition: input.h:91
velodyne_driver::InputPCAP::setDeviceIP
void setDeviceIP(const std::string &ip)
velodyne_driver::InputSocket
Live Velodyne input from socket.
Definition: input.h:97
ros.h
velodyne_driver::InputSocket::sockfd_
int sockfd_
Definition: input.h:109
velodyne_driver::InputPCAP::read_fast_
bool read_fast_
Definition: input.h:144
velodyne_driver::Input::gps_time_
bool gps_time_
Definition: input.h:93
velodyne_driver::Input
Velodyne input base class.
Definition: input.h:72
velodyne_driver::InputPCAP::errbuf_
char errbuf_[PCAP_ERRBUF_SIZE]
Definition: input.h:140
velodyne_driver::InputPCAP::pcap_packet_filter_
bpf_program pcap_packet_filter_
Definition: input.h:139
velodyne_driver::InputPCAP::read_once_
bool read_once_
Definition: input.h:143
velodyne_driver::InputSocket::getPacket
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt, const double time_offset)
Get one velodyne packet.
Definition: input.cc:148
velodyne_driver::InputPCAP::InputPCAP
InputPCAP(ros::NodeHandle private_nh, uint16_t port=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:260
velodyne_driver::Input::getPacket
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt, const double time_offset)=0
Read one Velodyne packet.
velodyne_driver::Input::~Input
virtual ~Input()
Definition: input.h:76
velodyne_driver::InputPCAP::empty_
bool empty_
Definition: input.h:141
velodyne_driver::POSITION_PORT_NUMBER
static uint16_t POSITION_PORT_NUMBER
Definition: input.h:69
velodyne_driver::InputSocket::InputSocket
InputSocket(ros::NodeHandle private_nh, uint16_t port=DATA_PORT_NUMBER)
constructor
Definition: input.cc:95
velodyne_driver::InputPCAP::pcap_time_
bool pcap_time_
Definition: input.h:142
velodyne_driver::DATA_PORT_NUMBER
static uint16_t DATA_PORT_NUMBER
Definition: input.h:68
velodyne_driver::InputPCAP::getPacket
virtual int getPacket(velodyne_msgs::VelodynePacket *pkt, const double time_offset)
Get one velodyne packet.
Definition: input.cc:309
velodyne_driver::Input::devip_str_
std::string devip_str_
Definition: input.h:92
velodyne_driver::InputSocket::devip_
in_addr devip_
Definition: input.h:110
velodyne_driver::InputPCAP::~InputPCAP
virtual ~InputPCAP()
Definition: input.cc:303
velodyne_driver::InputPCAP::packet_rate_
ros::Rate packet_rate_
Definition: input.h:136
ros::Rate
velodyne_driver::Input::private_nh_
ros::NodeHandle private_nh_
Definition: input.h:90
velodyne_driver
Definition: driver.h:45
velodyne_driver::InputPCAP
Velodyne input from PCAP dump file.
Definition: input.h:119
velodyne_driver::InputPCAP::repeat_delay_
double repeat_delay_
Definition: input.h:145
velodyne_driver::InputSocket::setDeviceIP
void setDeviceIP(const std::string &ip)
velodyne_driver::Input::Input
Input(ros::NodeHandle private_nh, uint16_t port)
constructor
Definition: input.cc:75
velodyne_driver::InputPCAP::filename_
std::string filename_
Definition: input.h:137
ros::NodeHandle


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Tue May 2 2023 02:28:00