velodyne::Data Class Reference
Base Velodyne data class -- not used directly.
More...
#include <data.h>
List of all members.
Detailed Description
Base Velodyne data class -- not used directly.
Definition at line 138 of file data.h.
Constructor & Destructor Documentation
velodyne::Data::Data |
( |
std::string |
ofile = "" , |
|
|
std::string |
anglesFile = "" | |
|
) |
| | [inline] |
virtual velodyne::Data::~Data |
( |
|
) |
[inline, virtual] |
Member Function Documentation
void velodyne::Data::getMsgHeaderFields |
( |
ros::Time & |
stamp, |
|
|
std::string & |
frame_id | |
|
) |
| | const [inline] |
Get time stamp and frame from latest ROS message header.
This will always reflect the current message while any callback function is running.
Definition at line 180 of file data.h.
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 46 of file data.cc.
virtual int velodyne::Data::print |
( |
void |
|
) |
[inline, virtual] |
void velodyne::Data::processRaw |
( |
const raw_packet_t * |
raw, |
|
|
size_t |
npackets | |
|
) |
| | [virtual] |
handle raw scan ROS topic message
This is the main entry point for handling ROS messages from the /velodyne/rawscan topic, published by the velodyne_read (device driver) node. This is not a virtual function; derived classes may replace processRaw(), instead.
Typically, velodyne_read publishes all the data for a single rotation of the device in each message.
Subscribe via the method-oriented ROS interface, like this:
velodyne::Data *data = new velodyne::Data();
ros::Subscriber velodyne_scan =
node.subscribe("velodyne/rawscan", 1,
&velodyne::Data::processRawScan, data,
ros::TransportHints().tcpNoDelay(true));
Definition at line 67 of file data.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 86 of file data.cc.
virtual void velodyne::Data::shutdown |
( |
void |
|
) |
[inline, virtual] |
Shut down data processing.
Definition at line 254 of file data.h.
Subscribe to raw packets for a each revolution.
Definition at line 261 of file data.h.
Member Data Documentation
correction angles file name
Definition at line 271 of file data.h.
correction angles indexed by laser within bank
- Todo:
- combine them into a single array, lower followed by upper
Definition at line 285 of file data.h.
output file name for print()
configuration parameters
Definition at line 270 of file data.h.
output file descriptor
runtime state
Definition at line 274 of file data.h.
raw data callback
Definition at line 275 of file data.h.
latest raw scan message received
Definition at line 279 of file data.h.
The documentation for this class was generated from the following files: