Apollo  6.0
Open source self driving car software
Public Member Functions | Protected Member Functions | List of all members
apollo::drivers::velodyne::Input Class Referenceabstract

Pure virtual Velodyne input base class. More...

#include <input.h>

Inheritance diagram for apollo::drivers::velodyne::Input:
Inheritance graph
Collaboration diagram for apollo::drivers::velodyne::Input:
Collaboration graph

Public Member Functions

 Input ()
 
virtual ~Input ()
 
virtual int get_firing_data_packet (VelodynePacket *pkt)=0
 Read one Velodyne packet. More...
 
virtual int get_positioning_data_packet (NMEATimePtr nmea_time)=0
 
virtual void init ()
 
virtual void init (const int &port)
 

Protected Member Functions

bool exract_nmea_time_from_packet (NMEATimePtr nmea_time, const uint8_t *bytes)
 

Detailed Description

Pure virtual Velodyne input base class.

Constructor & Destructor Documentation

◆ Input()

apollo::drivers::velodyne::Input::Input ( )
inline

◆ ~Input()

virtual apollo::drivers::velodyne::Input::~Input ( )
inlinevirtual

Member Function Documentation

◆ exract_nmea_time_from_packet()

bool apollo::drivers::velodyne::Input::exract_nmea_time_from_packet ( NMEATimePtr  nmea_time,
const uint8_t *  bytes 
)
protected

◆ get_firing_data_packet()

virtual int apollo::drivers::velodyne::Input::get_firing_data_packet ( VelodynePacket *  pkt)
pure virtual

Read one Velodyne packet.

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

Implemented in apollo::drivers::velodyne::SocketInput.

◆ get_positioning_data_packet()

virtual int apollo::drivers::velodyne::Input::get_positioning_data_packet ( NMEATimePtr  nmea_time)
pure virtual

◆ init() [1/2]

virtual void apollo::drivers::velodyne::Input::init ( )
inlinevirtual

◆ init() [2/2]

virtual void apollo::drivers::velodyne::Input::init ( const int &  port)
inlinevirtual

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