velodyne::DataXYZ Class Reference

Convert Velodyne raw input to XYZ format. More...

#include <data.h>

Inheritance diagram for velodyne::DataXYZ:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DataXYZ (std::string ofile="", std::string anglesFile="")
virtual int print (void)
 print laser scans in XYZ format
virtual void processRaw (const raw_packet_t *raw, size_t npackets)
 Process raw Velodyne packets for an entire revolution.
ros::Subscriber subscribe (ros::NodeHandle node, const std::string &topic, uint32_t queue_size, const xyzCallback callback, const ros::TransportHints &transport_hints=ros::TransportHints())
 Subscribe to XYZ laser scans.
virtual void subscribeXYZ (xyz_callback_t xyzCB)
 Subscribe to XYZ laser scans.

Protected Member Functions

void scan2xyz (const laserscan_t *scan, laserscan_xyz_t *point)

Protected Attributes

std::vector< laserscan_xyz_txyzScans_

Private Attributes

xyzCallback cb_
 XYZ data callback.
xyz_callback_t xyzCB_

Detailed Description

Convert Velodyne raw input to XYZ format.

Definition at line 407 of file data.h.


Constructor & Destructor Documentation

velodyne::DataXYZ::DataXYZ ( std::string  ofile = "",
std::string  anglesFile = "" 
) [inline]

Definition at line 410 of file data.h.


Member Function Documentation

int velodyne::DataXYZ::print ( void   )  [virtual]

print laser scans in XYZ format

Returns:
0, if successful; errno value, for failure
Todo:
allow exact number of packets argument

Reimplemented from velodyne::DataScans.

Definition at line 352 of file data.cc.

void velodyne::DataXYZ::processRaw ( const raw_packet_t raw,
size_t  npackets 
) [virtual]

Process raw Velodyne packets for an entire revolution.

Reimplemented from velodyne::DataScans.

Definition at line 320 of file data.cc.

void velodyne::DataXYZ::scan2xyz ( const laserscan_t scan,
laserscan_xyz_t point 
) [inline, protected]

Definition at line 306 of file data.cc.

ros::Subscriber velodyne::DataXYZ::subscribe ( ros::NodeHandle  node,
const std::string &  topic,
uint32_t  queue_size,
const xyzCallback  callback,
const ros::TransportHints &  transport_hints = ros::TransportHints() 
) [inline]

Subscribe to XYZ laser scans.

Parameters:
node the ros::NodeHandle to use to subscribe.
base_topic the topic to subscribe to.
queue_size the subscription queue size
callback function or method to receive XYZ data
transport_hints optional transport hints for this subscription

Definition at line 431 of file data.h.

virtual void velodyne::DataXYZ::subscribeXYZ ( xyz_callback_t  xyzCB  )  [inline, virtual]

Subscribe to XYZ laser scans.

Deprecated:
must separately subscribe to the topic

Definition at line 450 of file data.h.


Member Data Documentation

XYZ data callback.

Reimplemented from velodyne::DataScans.

Definition at line 464 of file data.h.

Definition at line 463 of file data.h.

Definition at line 460 of file data.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:58 2013