input.h
Go to the documentation of this file.
00001 // Copyright (C) 2007, 2009, 2010, 2012, 2015Yaxin Liu, Patrick Beeson, Austin Robot Technology, Jack O'Quin
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00053 #ifndef VELODYNE_DRIVER_INPUT_H
00054 #define VELODYNE_DRIVER_INPUT_H
00055 
00056 #include <unistd.h>
00057 #include <stdio.h>
00058 #include <pcap.h>
00059 #include <netinet/in.h>
00060 #include <string>
00061 
00062 #include <ros/ros.h>
00063 #include <velodyne_msgs/VelodynePacket.h>
00064 
00065 namespace velodyne_driver
00066 {
00067 
00068 static uint16_t DATA_PORT_NUMBER = 2368;      // default data port
00069 static uint16_t POSITION_PORT_NUMBER = 8308;  // default position port
00070 
00072 class Input
00073 {
00074 public:
00075   Input(ros::NodeHandle private_nh, uint16_t port);
00076   virtual ~Input() {}
00077 
00086   virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
00087                         const double time_offset) = 0;
00088 
00089 protected:
00090   ros::NodeHandle private_nh_;
00091   uint16_t port_;
00092   std::string devip_str_;
00093   bool gps_time_;
00094 };
00095 
00097 class InputSocket: public Input
00098 {
00099 public:
00100   InputSocket(ros::NodeHandle private_nh,
00101               uint16_t port = DATA_PORT_NUMBER);
00102   virtual ~InputSocket();
00103 
00104   virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
00105                         const double time_offset);
00106   void setDeviceIP(const std::string& ip);
00107 
00108 private:
00109   int sockfd_;
00110   in_addr devip_;
00111 };
00112 
00113 
00119 class InputPCAP: public Input
00120 {
00121 public:
00122   InputPCAP(ros::NodeHandle private_nh,
00123             uint16_t port = DATA_PORT_NUMBER,
00124             double packet_rate = 0.0,
00125             std::string filename = "",
00126             bool read_once = false,
00127             bool read_fast = false,
00128             double repeat_delay = 0.0);
00129   virtual ~InputPCAP();
00130 
00131   virtual int getPacket(velodyne_msgs::VelodynePacket *pkt,
00132                         const double time_offset);
00133   void setDeviceIP(const std::string& ip);
00134 
00135 private:
00136   ros::Rate packet_rate_;
00137   std::string filename_;
00138   pcap_t *pcap_;
00139   bpf_program pcap_packet_filter_;
00140   char errbuf_[PCAP_ERRBUF_SIZE];
00141   bool empty_;
00142   bool read_once_;
00143   bool read_fast_;
00144   double repeat_delay_;
00145 };
00146 
00147 }  // namespace velodyne_driver
00148 
00149 #endif  // VELODYNE_DRIVER_INPUT_H


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Wed Jul 3 2019 19:32:21