Convert Velodyne raw input to laserscans format. More...
#include <data.h>

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_t > | scans_ |
Private Attributes | |
| scanCallback | cb_ |
| scan data callback | |
| scans_callback_t | scansCB_ |
Convert Velodyne raw input to laserscans format.
Definition at line 320 of file data.h.
| velodyne::DataScans::DataScans | ( | std::string | ofile = "", |
|
| std::string | anglesFile = "" | |||
| ) | [inline] |
| void velodyne::DataScans::packet2scans | ( | const raw_packet_t * | raw, | |
| laserscan_t * | scans | |||
| ) | [protected] |
| 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.
Reimplemented from velodyne::Data.
Reimplemented in velodyne::DataXYZ.
| 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.
| 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.
| 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 |
| virtual void velodyne::DataScans::subscribeScans | ( | scans_callback_t | scansCB | ) | [inline, virtual] |
Subscribe to laser scans.
scanCallback velodyne::DataScans::cb_ [private] |
std::vector<laserscan_t> velodyne::DataScans::scans_ [protected] |