-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsubscriber_filter_republisher.cpp
64 lines (49 loc) · 1.87 KB
/
subscriber_filter_republisher.cpp
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
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
// Include the ROS library
//#include <ros/ros.h>
// Include pcl
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>
// Include PointCloud2 message
#include <sensor_msgs/PointCloud2.h>
// Topics (still to be modified correctly)
static const std::string IMAGE_TOPIC = "/camera/depth/points";
static const std::string PUBLISH_TOPIC = "/pcl/points";
// ROS Publisher
ros::Publisher pub;
void cloud_cb(const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
{
// Container for original & filtered data
pcl::PCLPointCloud2* cloud = new pcl::PCLPointCloud2;
pcl::PCLPointCloud2ConstPtr cloudPtr(cloud);
pcl::PCLPointCloud2 cloud_filtered;
// Convert to PCL data type
pcl_conversions::toPCL(*cloud_msg, *cloud);
// Perform the actual filtering
pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
sor.setInputCloud (cloudPtr);
sor.setLeafSize (0.1, 0.1, 0.1);
sor.filter (cloud_filtered);
// Convert to ROS data type
sensor_msgs::PointCloud2 output;
pcl_conversions::moveFromPCL(cloud_filtered, output);
// Publish the data
pub.publish (output);
}
int main (int argc, char** argv)
{
// Initialize the ROS Node ""
ros::init (argc, argv, "subscriber_filter_republisher");
ros::NodeHandle nh;
// Print "Hello" message with node name to the terminal and ROS log file
ROS_INFO_STREAM("Hello from ROS Node: " << ros::this_node::getName());
// Create a ROS Subscriber to IMAGE_TOPIC with a queue_size of 1 and a callback function to cloud_cb
ros::Subscriber sub = nh.subscribe(IMAGE_TOPIC, 1, cloud_cb);
// Create a ROS publisher to PUBLISH_TOPIC with a queue_size of 1
pub = nh.advertise<sensor_msgs::PointCloud2>(PUBLISH_TOPIC, 1);
// Spin
ros::spin();
// Success
return 0;
}