Live Velodyne input from socket. More...
#include <input.h>
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_ |
velodyne_driver::InputSocket::InputSocket | ( | ros::NodeHandle | private_nh, |
uint16_t | port = DATA_PORT_NUMBER |
||
) |
|
virtual |
|
virtual |
Get one velodyne packet.
Implements velodyne_driver::Input.
void velodyne_driver::InputSocket::setDeviceIP | ( | const std::string & | ip | ) |