Public Member Functions | Protected Attributes | List of all members
velodyne_driver::Input Class Referenceabstract

Velodyne input base class. More...

#include <input.h>

Inheritance diagram for velodyne_driver::Input:
Inheritance graph
[legend]

Public Member Functions

virtual int getPacket (velodyne_msgs::VelodynePacket *pkt, const double time_offset)=0
 Read one Velodyne packet. More...
 
 Input (ros::NodeHandle private_nh, uint16_t port)
 constructor More...
 
virtual ~Input ()
 

Protected Attributes

std::string devip_str_
 
bool gps_time_
 
uint16_t port_
 
ros::NodeHandle private_nh_
 

Detailed Description

Velodyne input base class.

Definition at line 72 of file input.h.

Constructor & Destructor Documentation

velodyne_driver::Input::Input ( ros::NodeHandle  private_nh,
uint16_t  port 
)

constructor

Parameters
private_nhROS private handle for calling node.
portUDP port number.

Definition at line 73 of file input.cc.

virtual velodyne_driver::Input::~Input ( )
inlinevirtual

Definition at line 76 of file input.h.

Member Function Documentation

virtual int velodyne_driver::Input::getPacket ( velodyne_msgs::VelodynePacket *  pkt,
const double  time_offset 
)
pure virtual

Read one Velodyne packet.

Parameters
pktpoints to VelodynePacket message
Returns
0 if successful, -1 if end of file > 0 if incomplete packet (is this possible?)

Implemented in velodyne_driver::InputPCAP, and velodyne_driver::InputSocket.

Member Data Documentation

std::string velodyne_driver::Input::devip_str_
protected

Definition at line 92 of file input.h.

bool velodyne_driver::Input::gps_time_
protected

Definition at line 93 of file input.h.

uint16_t velodyne_driver::Input::port_
protected

Definition at line 91 of file input.h.

ros::NodeHandle velodyne_driver::Input::private_nh_
protected

Definition at line 90 of file input.h.


The documentation for this class was generated from the following files:


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Sun Sep 6 2020 03:25:28