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. | |
| InputSocket (ros::NodeHandle private_nh, uint16_t port=DATA_PORT_NUMBER) | |
| constructor | |
| void | setDeviceIP (const std::string &ip) |
| virtual | ~InputSocket () |
| destructor | |
Private Attributes | |
| in_addr | devip_ |
| int | sockfd_ |
| velodyne_driver::InputSocket::InputSocket | ( | ros::NodeHandle | private_nh, |
| uint16_t | port = DATA_PORT_NUMBER |
||
| ) |
| velodyne_driver::InputSocket::~InputSocket | ( | void | ) | [virtual] |
| int velodyne_driver::InputSocket::getPacket | ( | velodyne_msgs::VelodynePacket * | pkt, |
| const double | time_offset | ||
| ) | [virtual] |
Get one velodyne packet.
Implements velodyne_driver::Input.
| void velodyne_driver::InputSocket::setDeviceIP | ( | const std::string & | ip | ) |
in_addr velodyne_driver::InputSocket::devip_ [private] |
int velodyne_driver::InputSocket::sockfd_ [private] |