Live O3M151 input from socket. More...
#include <input.h>

Public Member Functions | |
| virtual int | getPacket (pcl::PointCloud< pcl::PointXYZI > &pc) |
| Read one O3M151 packet. More... | |
| InputSocket (ros::NodeHandle private_nh, uint16_t udp_port=UDP_PORT_NUMBER) | |
| constructor More... | |
| ~InputSocket () | |
| destructor More... | |
Public Member Functions inherited from o3m151_driver::Input | |
| Input () | |
Private Attributes | |
| int | sockfd_ |
Additional Inherited Members | |
Protected Member Functions inherited from o3m151_driver::Input | |
| int | process (int8_t *udpPacketBuf, const ssize_t rc, pcl::PointCloud< pcl::PointXYZI > &pc) |
| void | processChannel8 (int8_t *buf, uint32_t size, pcl::PointCloud< pcl::PointXYZI > &pc) |
| int | processPacket (int8_t *currentPacketData, uint32_t currentPacketSize, int8_t *channelBuffer, uint32_t channelBufferSize, uint32_t *pos) |
| double | slope (const std::vector< double > &x, const std::vector< double > &y) |
Protected Attributes inherited from o3m151_driver::Input | |
| uint32_t | channel_buf_size_ |
| int8_t * | channelBuf |
| uint32_t | pos_in_channel_ |
| uint32_t | previous_packet_counter_ |
| bool | previous_packet_counter_valid_ |
| bool | startOfChannelFound_ |
| o3m151_driver::InputSocket::InputSocket | ( | ros::NodeHandle | private_nh, |
| uint16_t | udp_port = UDP_PORT_NUMBER |
||
| ) |
| o3m151_driver::InputSocket::~InputSocket | ( | void | ) |
|
virtual |
Read one O3M151 packet.
| pkt | points to O3M151Packet message |
Implements o3m151_driver::Input.