Convert Velodyne raw input to laserscans format. More...
#include <data_scans.h>
Public Member Functions | |
DataScans (std::string ofile="", std::string anglesFile="") | |
virtual int | print (void) |
print laser scan data | |
virtual void | processPacket (const velodyne_msgs::VelodynePacket *pkt, const std::string &frame_id) |
Process Velodyne packet. | |
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. | |
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 |
Convert Velodyne raw input to laserscans format.
Definition at line 57 of file data_scans.h.
Velodyne::DataScans::DataScans | ( | std::string | ofile = "" , |
|
std::string | anglesFile = "" | |||
) |
Definition at line 37 of file data_scans.cc.
void Velodyne::DataScans::packet2scans | ( | const raw_packet_t * | raw, | |
laserscan_t * | scans | |||
) | [protected] |
convert raw packet to laserscan format
Definition at line 46 of file data_scans.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.
Implements Velodyne::Data.
Reimplemented in Velodyne::DataXYZ.
Definition at line 122 of file data_scans.cc.
void Velodyne::DataScans::processPacket | ( | const velodyne_msgs::VelodynePacket * | pkt, | |
const std::string & | frame_id | |||
) | [virtual] |
Process Velodyne packet.
Implements Velodyne::Data.
Reimplemented in Velodyne::DataXYZ.
Definition at line 98 of file data_scans.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.
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 74 of file data_scans.h.
scanCallback Velodyne::DataScans::cb_ [private] |
std::vector<laserscan_t> Velodyne::DataScans::scans_ [protected] |
Definition at line 92 of file data_scans.h.