Velodyne input base class. More...
#include <input.h>
Public Member Functions | |
virtual int | getPacket (velodyne_msgs::VelodynePacket *pkt, const double time_offset)=0 |
Read one Velodyne packet. | |
Input (ros::NodeHandle private_nh, uint16_t port) | |
constructor | |
virtual | ~Input () |
Protected Attributes | |
std::string | devip_str_ |
bool | gps_time_ |
uint16_t | port_ |
ros::NodeHandle | private_nh_ |
velodyne_driver::Input::Input | ( | ros::NodeHandle | private_nh, |
uint16_t | port | ||
) |
virtual velodyne_driver::Input::~Input | ( | ) | [inline, virtual] |
virtual int velodyne_driver::Input::getPacket | ( | velodyne_msgs::VelodynePacket * | pkt, |
const double | time_offset | ||
) | [pure virtual] |
Read one Velodyne packet.
pkt | points to VelodynePacket message |
Implemented in velodyne_driver::InputPCAP, and velodyne_driver::InputSocket.
std::string velodyne_driver::Input::devip_str_ [protected] |
bool velodyne_driver::Input::gps_time_ [protected] |
uint16_t velodyne_driver::Input::port_ [protected] |
ros::NodeHandle velodyne_driver::Input::private_nh_ [protected] |