Velodyne::Data Class Reference

Base Velodyne data class -- not used directly. More...

#include <data_base.h>

Inheritance diagram for Velodyne::Data:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 Data (std::string ofile="", std::string anglesFile="")
virtual int getParams (void)
 Get ROS parameters.
virtual int print (void)=0
 Print data to human-readable file.
virtual void processPacket (const velodyne_msgs::VelodynePacket *pkt, const std::string &frame_id)=0
 Process a Velodyne packet.
void processScan (const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
 handle ROS topic message
virtual int setup (void)
 Set up for data processing.
virtual void shutdown (void)
 Shut down data processing.
virtual ~Data ()

Protected Attributes

std::string anglesFile_
 correction angles file name
correction_angles lower_ [SCANS_PER_BLOCK]
std::string ofile_
 output file name for print()
FILE * ofp_
 output file descriptor
velodyne_msgs::VelodyneScan::ConstPtr rawScan_
bool uninitialized_
 false after successful setup()
correction_angles upper_ [SCANS_PER_BLOCK]

Detailed Description

Base Velodyne data class -- not used directly.

Definition at line 117 of file data_base.h.


Constructor & Destructor Documentation

Velodyne::Data::Data ( std::string  ofile = "",
std::string  anglesFile = "" 
)

Definition at line 42 of file data_base.cc.

virtual Velodyne::Data::~Data (  )  [inline, virtual]

Definition at line 122 of file data_base.h.


Member Function Documentation

int Velodyne::Data::getParams ( void   )  [virtual]

Get ROS parameters.

ROS parameter settings override constructor options

Returns:
0, if successful; errno value, for failure

get ROS parameters

ROS parameter settings override constructor options

Returns:
0, if successful; errno value, for failure

Definition at line 62 of file data_base.cc.

virtual int Velodyne::Data::print ( void   )  [pure virtual]

Print data to human-readable file.

Returns:
0, if successful; errno value, for failure

Implemented in Velodyne::DataScans, and Velodyne::DataXYZ.

virtual void Velodyne::Data::processPacket ( const velodyne_msgs::VelodynePacket *  pkt,
const std::string &  frame_id 
) [pure virtual]

Process a Velodyne packet.

Parameters:
pkt -> VelodynePacket message

Implemented in Velodyne::DataScans, and Velodyne::DataXYZ.

void Velodyne::Data::processScan ( const velodyne_msgs::VelodyneScan::ConstPtr &  scanMsg  ) 

handle ROS topic message

This is the main entry point for handling ROS messages from the "velodyne/packets" topic, published by the driver nodelet. This is not a virtual function; derived classes may replace processPacket(), instead.

By default, the driver publishes packets for a complete rotation of the device in each message, but that is not guaranteed.

handle raw scan ROS topic message

Definition at line 83 of file data_base.cc.

int Velodyne::Data::setup ( void   )  [virtual]

Set up for data processing.

Perform initializations needed before data processing can begin:

  • open output file (if any)
  • read device-specific correction angles
Returns:
0 if successful; errno value for failure

Set up for on-line operation.

Definition at line 100 of file data_base.cc.

virtual void Velodyne::Data::shutdown ( void   )  [inline, virtual]

Shut down data processing.

Definition at line 174 of file data_base.h.


Member Data Documentation

std::string Velodyne::Data::anglesFile_ [protected]

correction angles file name

Definition at line 184 of file data_base.h.

correction angles indexed by laser within bank

Todo:
combine them into a single array, lower followed by upper

Definition at line 197 of file data_base.h.

std::string Velodyne::Data::ofile_ [protected]

output file name for print()

configuration parameters

Definition at line 183 of file data_base.h.

FILE* Velodyne::Data::ofp_ [protected]

output file descriptor

runtime state

Definition at line 187 of file data_base.h.

velodyne_msgs::VelodyneScan::ConstPtr Velodyne::Data::rawScan_ [protected]

latest raw scan message received

Definition at line 191 of file data_base.h.

false after successful setup()

Definition at line 188 of file data_base.h.

Definition at line 198 of file data_base.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Defines


velodyne_common
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Fri Jan 11 10:05:57 2013