00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00033 #ifndef __VELODYNE_INPUT_H
00034 #define __VELODYNE_INPUT_H
00035
00036 #include <unistd.h>
00037 #include <stdio.h>
00038 #include <pcap.h>
00039
00040 #include <ros/ros.h>
00041 #include <velodyne_common/RawScan.h>
00042 #include <velodyne_msgs/VelodynePacket.h>
00043
00044 namespace velodyne
00045 {
00046 static uint16_t UDP_PORT_NUMBER = 2368;
00047
00048
00049 class Input
00050 {
00051 public:
00052 Input() {};
00053
00062 virtual int getPacket(velodyne_msgs::VelodynePacket *pkt);
00063
00076 virtual int getPackets(uint8_t *buffer, int npacks, double *data_time) = 0;
00077
00083 virtual int vclose(void) = 0;
00084
00091 virtual int vopen(void) = 0;
00092 };
00093
00095 class InputSocket: public Input
00096 {
00097 public:
00098 InputSocket(uint16_t udp_port = UDP_PORT_NUMBER):
00099 Input()
00100 {
00101 udp_port_ = udp_port;
00102 sockfd_ = -1;
00103 }
00104 ~InputSocket() {}
00105
00106 virtual int getPackets(uint8_t *buffer, int npacks, double *data_time);
00107 virtual int vclose(void);
00108 virtual int vopen(void);
00109
00110 private:
00111 uint16_t udp_port_;
00112 int sockfd_;
00113 };
00114
00115
00121 class InputPCAP: public Input
00122 {
00123 public:
00124 InputPCAP(std::string filename="",
00125 bool read_once=false,
00126 bool read_fast=false,
00127 double repeat_delay=0.0):
00128 Input(), delay_(2600.0)
00129 {
00130 filename_ = filename;
00131 fp_ = NULL;
00132 pcap_ = NULL;
00133 empty_ = true;
00134
00135
00136 ros::NodeHandle private_nh("~/input");
00137 private_nh.param("read_once", read_once_, read_once);
00138 private_nh.param("read_fast", read_fast_, read_fast);
00139 private_nh.param("repeat_delay", repeat_delay_, repeat_delay);
00140
00141 if (read_once_)
00142 ROS_INFO("Read input file only once.");
00143 if (read_fast_)
00144 ROS_INFO("Read input file as quickly as possible.");
00145 if (repeat_delay_ > 0.0)
00146 ROS_INFO("Delay %.3f seconds before repeating input file.",
00147 repeat_delay_);
00148 }
00149 ~InputPCAP() {}
00150
00151 virtual int getPackets(uint8_t *buffer, int npacks, double *data_time);
00152 virtual int vclose(void);
00153 virtual int vopen(void);
00154
00155 private:
00156 std::string filename_;
00157 FILE *fp_;
00158 pcap_t *pcap_;
00159 char errbuf_[PCAP_ERRBUF_SIZE];
00160 bool empty_;
00161 bool read_once_;
00162 bool read_fast_;
00163 double repeat_delay_;
00164 ros::Rate delay_;
00165 };
00166
00167 }
00168
00169 #endif // __VELODYNE_INPUT_H