-
Notifications
You must be signed in to change notification settings - Fork 76
/
LaserPublisher.h
38 lines (32 loc) · 1021 Bytes
/
LaserPublisher.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
#ifndef ROSARIALASERPUBLISHER_H
#define ROSARIALASERPUBLISHER_H
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud.h>
#include <tf/transform_broadcaster.h>
class ArLaser;
class ArTime;
class LaserPublisher
{
public:
LaserPublisher(ArLaser* _l, ros::NodeHandle& _n, bool _broadcast_transform = true, const std::string& _tf_frame = "laser", const std::string& _parent_tf_frame = "base_link", const std::string& _global_tf_frame = "odom");
~LaserPublisher();
protected:
void readingsCB();
void publishLaserScan();
void publishPointCloud();
ArFunctorC<LaserPublisher> laserReadingsCB;
ros::NodeHandle& node;
ArLaser *laser;
ros::Publisher laserscan_pub, pointcloud_pub;
sensor_msgs::LaserScan laserscan;
sensor_msgs::PointCloud pointcloud;
std::string tfname;
std::string parenttfname;
std::string globaltfname;
tf::Transform lasertf;
tf::TransformBroadcaster transform_broadcaster;
bool broadcast_tf;
//ArTime *readingsCallbackTime;
};
#endif