代码拉取完成,页面将自动刷新
#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
此处可能存在不合适展示的内容,页面不予展示。您可通过相关编辑功能自查并修改。
如您确认内容无涉及 不当用语 / 纯广告导流 / 暴力 / 低俗色情 / 侵权 / 盗版 / 虚假 / 无价值内容或违法国家有关法律法规的内容,可点击提交进行申诉,我们将尽快为您处理。