Public Member Functions | Private Attributes
velodyne_driver::VelodyneDriver Class Reference

#include <driver.h>

List of all members.

Public Member Functions

bool poll (void)
 VelodyneDriver (ros::NodeHandle node, ros::NodeHandle private_nh)
 ~VelodyneDriver ()

Private Attributes

struct {
   std::string   frame_id
 tf frame ID
   std::string   model
 device model name
   int   npackets
 number of packets to collect
   double   rpm
 device rotation rate (RPMs)
config_
double diag_max_freq_
double diag_min_freq_
boost::shared_ptr
< diagnostic_updater::TopicDiagnostic
diag_topic_
diagnostic_updater::Updater diagnostics_
boost::shared_ptr< Inputinput_
ros::Publisher output_

Detailed Description

Definition at line 28 of file driver.h.


Constructor & Destructor Documentation

Definition at line 27 of file driver.cc.

Definition at line 34 of file driver.h.


Member Function Documentation

poll the device

Returns:
true unless end of file reached

Definition at line 115 of file driver.cc.


Member Data Documentation

struct { ... } velodyne_driver::VelodyneDriver::config_ [private]

Definition at line 55 of file driver.h.

Definition at line 54 of file driver.h.

Definition at line 56 of file driver.h.

diagnostics updater

Definition at line 53 of file driver.h.

tf frame ID

Definition at line 43 of file driver.h.

boost::shared_ptr<Input> velodyne_driver::VelodyneDriver::input_ [private]

Definition at line 49 of file driver.h.

device model name

Definition at line 44 of file driver.h.

number of packets to collect

Definition at line 45 of file driver.h.

Definition at line 50 of file driver.h.

device rotation rate (RPMs)

Definition at line 46 of file driver.h.


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


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Thu Aug 27 2015 15:37:02