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

how to use concatenatePointCloud

asked 2016-09-12 11:04:07 -0500

marilia15 gravatar image

updated 2016-09-12 11:04:43 -0500

I am publishing /tf with a tf_broadcaster node. Also I am publishing <velodyne_msgs velodynescan=""> with velodyne_driver node.

Then the velodyne_pointcloud Transform nodelet is suscribed to both previous topics, applies the tf to the velodyneScan data and and publishes a PointCloud2 message.

I want to concatenate these PointCloud2 messages, trying to get a denser pointcloud in just one message.

I guess I have to use pcl::concatenatePointCloud but I am not sure how to use it.

Shall I create a node subscribing to PointCloud2 message and in the callback something like below?:

accumulatedPointCloud= pcl::concatenatePointCloud (oldPointCloud, newPointCloud )
publish(accumulatedPointCloud)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-09-19 03:37:22 -0500

marilia15 gravatar image

I am not sure if it is the optimized way to do that, but my proved solution is:

static sensor_msgs::PointCloud2 PCacumulada;  

static pcl::PCLPointCloud2 pclPCacumulada;


void chatterCallback( sensor_msgs::PointCloud2 PCmsg)
{
    pcl::PCLPointCloud2 pclmsg;
        pcl_conversions::toPCL(PCmsg,pclmsg);
    pcl::concatenatePointCloud (pclPCacumulada, pclmsg, pclPCacumulada);
    pcl_conversions::fromPCL(pclPCacumulada, PCacumulada);  
}

int main (int argc, char ** argv)
{
    ros::init(argc,argv,"nodeProcesador"); 
    ros::NodeHandle ns; 
    ros::NodeHandle np; 
    ros::Subscriber subscriptor = ns.subscribe("velodyne_points",10, chatterCallback);
    ros::Publisher publicador= ns.advertise<sensor_msgs::PointCloud2>("velodyne_points2",10);
    ros::Rate loop_rate(10); /
    ros::spinOnce();
    while(ros::ok())
    {       
        publicador.publish(PCacumulada);
        ros::spinOnce();
        loop_rate.sleep();
    }
    ROS_INFO("Fin suscriptor");
    return 0;
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-09-12 11:04:07 -0500

Seen: 2,555 times

Last updated: Sep 19 '16