#include <LaserPublisher.h>
| Public Member Functions | |
| 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 Member Functions | |
| void | publishLaserScan () | 
| void | publishPointCloud () | 
| void | readingsCB () | 
| Protected Attributes | |
| bool | broadcast_tf | 
| std::string | globaltfname | 
| ArLaser * | laser | 
| ArFunctorC< LaserPublisher > | laserReadingsCB | 
| sensor_msgs::LaserScan | laserscan | 
| ros::Publisher | laserscan_pub | 
| tf::Transform | lasertf | 
| ros::NodeHandle & | node | 
| std::string | parenttfname | 
| sensor_msgs::PointCloud | pointcloud | 
| ros::Publisher | pointcloud_pub | 
| std::string | tfname | 
| tf::TransformBroadcaster | transform_broadcaster | 
Definition at line 12 of file LaserPublisher.h.
| LaserPublisher::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" | ||
| ) | 
Definition at line 19 of file LaserPublisher.cpp.
Definition at line 77 of file LaserPublisher.cpp.
| void LaserPublisher::publishLaserScan | ( | ) |  [protected] | 
Definition at line 98 of file LaserPublisher.cpp.
| void LaserPublisher::publishPointCloud | ( | ) |  [protected] | 
Definition at line 141 of file LaserPublisher.cpp.
| void LaserPublisher::readingsCB | ( | ) |  [protected] | 
Definition at line 85 of file LaserPublisher.cpp.
| bool LaserPublisher::broadcast_tf  [protected] | 
Definition at line 33 of file LaserPublisher.h.
| std::string LaserPublisher::globaltfname  [protected] | 
Definition at line 30 of file LaserPublisher.h.
| ArLaser* LaserPublisher::laser  [protected] | 
Definition at line 24 of file LaserPublisher.h.
| ArFunctorC<LaserPublisher> LaserPublisher::laserReadingsCB  [protected] | 
Definition at line 22 of file LaserPublisher.h.
| sensor_msgs::LaserScan LaserPublisher::laserscan  [protected] | 
Definition at line 26 of file LaserPublisher.h.
| ros::Publisher LaserPublisher::laserscan_pub  [protected] | 
Definition at line 25 of file LaserPublisher.h.
| tf::Transform LaserPublisher::lasertf  [protected] | 
Definition at line 31 of file LaserPublisher.h.
| ros::NodeHandle& LaserPublisher::node  [protected] | 
Definition at line 23 of file LaserPublisher.h.
| std::string LaserPublisher::parenttfname  [protected] | 
Definition at line 29 of file LaserPublisher.h.
| sensor_msgs::PointCloud LaserPublisher::pointcloud  [protected] | 
Definition at line 27 of file LaserPublisher.h.
| ros::Publisher LaserPublisher::pointcloud_pub  [protected] | 
Definition at line 25 of file LaserPublisher.h.
| std::string LaserPublisher::tfname  [protected] | 
Definition at line 28 of file LaserPublisher.h.
Definition at line 32 of file LaserPublisher.h.