ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

Hey D.

I found this solution to work:

//Variables
tf::TransformListener tf_;
tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

//initialisation
cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

//callback protoype
void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
{
    ROS_INFO("Message received");
    cloud_ = sensor_msg;
    pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
    pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
    ROS_INFO("Message passed");
    //transformed_pcl_cloud_ contains the projected cloud       
}

Hope it helps

Raph

Hey D.

I found this solution to work:work for point clouds. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicated the frame on which I synchronize (map in my case).

//Variables
tf::TransformListener tf_;
tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

//initialisation
cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

//callback protoype
void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
{
    ROS_INFO("Message received");
    cloud_ = sensor_msg;
    pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
    pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
    ROS_INFO("Message passed");
    //transformed_pcl_cloud_ contains the projected cloud       
}

Hope it helps

Raph

Hey D.

I found this solution to work for point clouds. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicated the frame on which I synchronize (map in my case).

class PointReader
{    
    //Variables
 tf::TransformListener tf_;
 tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
 message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

 //initialisation
 cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
 tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
 tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

 //callback protoype
 void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
 {
     ROS_INFO("Message received");
     cloud_ = sensor_msg;
     pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
     pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
     ROS_INFO("Message passed");
     //transformed_pcl_cloud_ contains the projected cloud       
    }
}

Hope it helps

Raph

Hey D.

I found this solution to work for point clouds. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicated indicate the frame on which I synchronize (map in my case).

class PointReader
{    
    //Variables
    tf::TransformListener tf_;
    tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
    message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

    //initialisation
    cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
    tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
    tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

    //callback protoype
    void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
    {
        ROS_INFO("Message received");
        cloud_ = sensor_msg;
        pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
        pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
        ROS_INFO("Message passed");
        //transformed_pcl_cloud_ contains the projected cloud       
    }
}

Hope it helps

Raph

Hey D.

I found this solution to work for point clouds. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicate the frame on which I synchronize (map in my case).

class PointReader
{    
    //Variables
    tf::TransformListener tf_;
    tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
    message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

    //initialisation
    cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
    tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
    tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

    //callback protoype
//callback
    void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
    {
        ROS_INFO("Message received");
        cloud_ = sensor_msg;
        pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
        pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
        ROS_INFO("Message passed");
        //transformed_pcl_cloud_ contains the projected cloud       
    }
}

Hope it helps

Raph

Hey D.Dejan,

I found this solution to work for point clouds. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicate the frame on which I synchronize (map in my case).

class PointReader
{    
    //Variables
    tf::TransformListener tf_;
    tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
    message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

    //initialisation
    cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
    tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
    tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

    //callback
    void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
    {
        ROS_INFO("Message received");
        cloud_ = sensor_msg;
        pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
        pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
        ROS_INFO("Message passed");
        //transformed_pcl_cloud_ contains the projected cloud       
    }
}

Hope it helps

Raph

Hey Dejan,

I found this solution to work for synchronizing point clouds. clouds and tf frames. I didn't try with Images but I don't see why the synchronization mechanism would be different. Note that I need to indicate the frame on which I synchronize (map in my case).

class PointReader
{    
    //Variables
    tf::TransformListener tf_;
    tf::MessageFilter<sensor_msgs::PointCloud2> * tf_filter_;
    message_filters::Subscriber<sensor_msgs::PointCloud2> cloud2_sub_;

    //initialisation
    cloud2_sub_.subscribe(n, "/kinect/rgb/points2", 10);
    tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud2>(cloud2_sub_, tf_, "/map", 10);
    tf_filter_->registerCallback( boost::bind(&PointReader::pointCloudCallback, this, _1) );

    //callback
    void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& sensor_msg)
    {
        ROS_INFO("Message received");
        cloud_ = sensor_msg;
        pcl::fromROSMsg (*cloud_, original_pcl_cloud_);
        pcl::transformPointCloud("/map", original_pcl_cloud_, transformed_pcl_cloud_, tf_);
        ROS_INFO("Message passed");
        //transformed_pcl_cloud_ contains the projected cloud       
    }
}

Hope it helps

Raph