Public Member Functions | Private Attributes | List of all members
velodyne_driver::InputSocket Class Reference

Live Velodyne input from socket. More...

#include <input.h>

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

Public Member Functions

virtual int getPacket (velodyne_msgs::VelodynePacket *pkt, const double time_offset)
 Get one velodyne packet. More...
 
 InputSocket (ros::NodeHandle private_nh, uint16_t port=DATA_PORT_NUMBER)
 constructor More...
 
void setDeviceIP (const std::string &ip)
 
virtual ~InputSocket ()
 destructor More...
 
- Public Member Functions inherited from velodyne_driver::Input
 Input (ros::NodeHandle private_nh, uint16_t port)
 constructor More...
 
virtual ~Input ()
 

Private Attributes

in_addr devip_
 
int sockfd_
 

Additional Inherited Members

- Protected Attributes inherited from velodyne_driver::Input
std::string devip_str_
 
bool gps_time_
 
uint16_t port_
 
ros::NodeHandle private_nh_
 

Detailed Description

Live Velodyne input from socket.

Definition at line 97 of file input.h.

Constructor & Destructor Documentation

velodyne_driver::InputSocket::InputSocket ( ros::NodeHandle  private_nh,
uint16_t  port = DATA_PORT_NUMBER 
)

constructor

Parameters
private_nhROS private handle for calling node.
portUDP port number

Definition at line 93 of file input.cc.

velodyne_driver::InputSocket::~InputSocket ( void  )
virtual

destructor

Definition at line 133 of file input.cc.

Member Function Documentation

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

Get one velodyne packet.

Implements velodyne_driver::Input.

Definition at line 139 of file input.cc.

void velodyne_driver::InputSocket::setDeviceIP ( const std::string &  ip)

Member Data Documentation

in_addr velodyne_driver::InputSocket::devip_
private

Definition at line 110 of file input.h.

int velodyne_driver::InputSocket::sockfd_
private

Definition at line 109 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