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

Live O3M151 input from socket. More...

#include <input.h>

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

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_
 

Detailed Description

Live O3M151 input from socket.

Definition at line 85 of file input.h.

Constructor & Destructor Documentation

o3m151_driver::InputSocket::InputSocket ( ros::NodeHandle  private_nh,
uint16_t  udp_port = UDP_PORT_NUMBER 
)

constructor

Parameters
private_nhprivate node handle for driver
udp_portUDP port number to connect

Definition at line 301 of file input.cc.

o3m151_driver::InputSocket::~InputSocket ( void  )

destructor

Definition at line 337 of file input.cc.

Member Function Documentation

int o3m151_driver::InputSocket::getPacket ( pcl::PointCloud< pcl::PointXYZI > &  pc)
virtual

Read one O3M151 packet.

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

Implements o3m151_driver::Input.

Definition at line 342 of file input.cc.

Member Data Documentation

int o3m151_driver::InputSocket::sockfd_
private

Definition at line 95 of file input.h.


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


o3m151_driver
Author(s): Vincent Rousseau
autogenerated on Mon Jun 10 2019 14:07:55