00001 #ifndef ROSARIALASERPUBLISHER_H 00002 #define ROSARIALASERPUBLISHER_H 00003 00004 #include <ros/ros.h> 00005 #include <sensor_msgs/LaserScan.h> 00006 #include <sensor_msgs/PointCloud.h> 00007 #include <tf/transform_broadcaster.h> 00008 00009 class ArLaser; 00010 class ArTime; 00011 00012 class LaserPublisher 00013 { 00014 public: 00015 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"); 00016 ~LaserPublisher(); 00017 protected: 00018 void readingsCB(); 00019 void publishLaserScan(); 00020 void publishPointCloud(); 00021 00022 ArFunctorC<LaserPublisher> laserReadingsCB; 00023 ros::NodeHandle& node; 00024 ArLaser *laser; 00025 ros::Publisher laserscan_pub, pointcloud_pub; 00026 sensor_msgs::LaserScan laserscan; 00027 sensor_msgs::PointCloud pointcloud; 00028 std::string tfname; 00029 std::string parenttfname; 00030 std::string globaltfname; 00031 tf::Transform lasertf; 00032 tf::TransformBroadcaster transform_broadcaster; 00033 bool broadcast_tf; 00034 00035 //ArTime *readingsCallbackTime; 00036 }; 00037 00038 #endif