ts_pointcloud_ros.h
Go to the documentation of this file.
1 #ifndef TS_POINTCLOUD_ROS_H
2 #define TS_POINTCLOUD_ROS_H
3 
4 #include <ros/package.h>
5 #include <ros/ros.h>
7 #include <visualization_msgs/Marker.h>
8 
11 
12 namespace toposens_pointcloud
13 {
14 static const std::string kPointCloudTopic = "ts_cloud";
15 
40 {
41 public:
48 
53 
54 private:
64  void cloudCallback(const toposens_msgs::TsScan::ConstPtr &msg);
65 
76  void doTransform(geometry_msgs::TransformStamped transform, pcl::PointXYZINormal &pt,
77  std_msgs::Header h);
78 
86  void publishNormals(XYZINCloud::ConstPtr tc);
87 
88  std::string scans_topic_;
89  std::string target_frame_;
96  int marker_id_ = 0;
101  boost::thread *log_thread_;
104  std::unique_ptr<Mapping> pointTransform_;
105  visualization_msgs::Marker marker;
106 };
107 
108 } // namespace toposens_pointcloud
109 
110 #endif
ROS interface for transforming the pointclouds.
visualization_msgs::Marker marker
void doTransform(geometry_msgs::TransformStamped transform, pcl::PointXYZINormal &pt, std_msgs::Header h)
tf2_ros::TransformListener * tf2_listener_
void publishNormals(XYZINCloud::ConstPtr tc)
std::unique_ptr< Mapping > pointTransform_
static const std::string kPointCloudTopic
void cloudCallback(const toposens_msgs::TsScan::ConstPtr &msg)
TSPointCloudROS(ros::NodeHandle nh, ros::NodeHandle private_nh)


toposens_pointcloud
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Inshal Uddin
autogenerated on Sun Feb 14 2021 03:20:25