velodyne::DataScans Class Reference

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

#include <data.h>

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

List of all members.

Public Member Functions

 DataScans (std::string ofile="", std::string anglesFile="")
virtual int print (void)
 print laser scan data
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 scanCallback callback, const ros::TransportHints &transport_hints=ros::TransportHints())
 Subscribe to laser scans.
virtual void subscribeScans (scans_callback_t scansCB)
 Subscribe to laser scans.

Protected Member Functions

void packet2scans (const raw_packet_t *raw, laserscan_t *scans)
 convert raw packet to laserscan format

Protected Attributes

std::vector< laserscan_tscans_

Private Attributes

scanCallback cb_
 scan data callback
scans_callback_t scansCB_

Detailed Description

Convert Velodyne raw input to laserscans format.

Definition at line 320 of file data.h.


Constructor & Destructor Documentation

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

Definition at line 323 of file data.h.


Member Function Documentation

void velodyne::DataScans::packet2scans ( const raw_packet_t raw,
laserscan_t scans 
) [protected]

convert raw packet to laserscan format

Todo:
test against pdump2 with delayed normalize_angle()

Definition at line 183 of file data.cc.

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

print laser scan data

This is not exactly the same format used by pcapconvert -t3, but it's similar.

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

Reimplemented from velodyne::Data.

Reimplemented in velodyne::DataXYZ.

Definition at line 270 of file data.cc.

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

Process raw Velodyne packets for an entire revolution.

Reimplemented from velodyne::Data.

Reimplemented in velodyne::DataXYZ.

Definition at line 236 of file data.cc.

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

Subscribe to 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 scan data
transport_hints optional transport hints for this subscription

Definition at line 344 of file data.h.

virtual void velodyne::DataScans::subscribeScans ( scans_callback_t  scansCB  )  [inline, virtual]

Subscribe to laser scans.

Deprecated:
must separately subscribe to the topic

Definition at line 363 of file data.h.


Member Data Documentation

scan data callback

Reimplemented in velodyne::DataXYZ.

Definition at line 377 of file data.h.

std::vector<laserscan_t> velodyne::DataScans::scans_ [protected]

Definition at line 373 of file data.h.

Definition at line 376 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:57 2013