test foncteur pour callback
This commit is contained in:
parent
a054967b19
commit
891c6471ac
1 changed files with 22 additions and 16 deletions
|
@ -2,26 +2,32 @@
|
||||||
#include <pcl_ros/point_cloud.h>
|
#include <pcl_ros/point_cloud.h>
|
||||||
#include <pcl/point_types.h>
|
#include <pcl/point_types.h>
|
||||||
|
|
||||||
class Filtre {
|
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
|
||||||
private:
|
|
||||||
typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
|
|
||||||
ros::NodeHandle node;
|
|
||||||
ros::Subscriber sub;
|
|
||||||
void callback(PointCloud&);
|
|
||||||
public:
|
|
||||||
Filtre()
|
|
||||||
{
|
|
||||||
ros::init(argc, argv, "filtre");
|
|
||||||
callback(PointCloud& msg)
|
|
||||||
{
|
|
||||||
|
|
||||||
|
class Callback
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
operator()(const PointCloud::Ptr& msg)
|
||||||
|
{
|
||||||
|
pub.publish(*msg);
|
||||||
}
|
}
|
||||||
subscriber = node.subscribe<PointCloud>("input", 1, callback);
|
|
||||||
ros::spin();
|
Callback(ros::NodeHandle& node)
|
||||||
|
{
|
||||||
|
pub = node.advertise<PointCloud>("output", 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
ros::Publisher pub;
|
||||||
};
|
};
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
int
|
||||||
|
main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
Filtre f();
|
ros::init(argc, argv, "filtre");
|
||||||
|
ros::NodeHandle node;
|
||||||
|
Callback callback(node);
|
||||||
|
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, callback);
|
||||||
|
ros::spin();
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in a new issue