Velodyne::DataXYZ Class Reference

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

#include <data_xyz.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 processPacket (const velodyne_msgs::VelodynePacket *pkt, const std::string &frame_id)
 Process a Velodyne packet message.
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.

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 packet callback.

Detailed Description

Convert Velodyne raw input to XYZ format.

Definition at line 52 of file data_xyz.h.


Constructor & Destructor Documentation

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

Definition at line 34 of file data_xyz.cc.


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 83 of file data_xyz.cc.

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

Process a Velodyne packet message.

Reimplemented from Velodyne::DataScans.

Definition at line 56 of file data_xyz.cc.

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

Definition at line 42 of file data_xyz.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 69 of file data_xyz.h.


Member Data Documentation

XYZ packet callback.

Reimplemented from Velodyne::DataScans.

Definition at line 90 of file data_xyz.h.

Definition at line 87 of file data_xyz.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