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

Conversion of pointCloud using pcl::fromROSMsg makes process much slower.

asked 2016-03-25 06:16:49 -0500

PKumars gravatar image

Dear All, I'm using ROS indigo and Kinect sensor for getting XYZ position. I'm using Conversion of pointCloud using pcl::fromROSMsg. But the problem is it makes process much slower.

I'm subscribing to /camera/depth_registered_points and /camera/depth/points. I'm synchronizing them with approximate synchronize.

Here goes a snippet of my code. main function

int main(int argc, char** argv) { ros::init(argc, argv, "vision_node");

ros::NodeHandle nh;

// topic subscription
message_filters::Subscriber<Image> RGB_sub(nh, "/camera/rgb/image_color", 1);
message_filters::Subscriber<sensor_msgs::PointCloud2> PointCloud_sub(nh, "/camera/depth_registered/points", 1);
// synchronization policy
typedef sync_policies::ApproximateTime<Image, sensor_msgs::PointCloud2> MySyncPolicy;

// ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), RGB_sub, PointCloud_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));

pubData = nh.advertise<std_msgs::Float32MultiArray>("pubData", 10);

ros::spin();
return 0;

}

callback function

void callback(const ImageConstPtr& image_rgb, const sensor_msgs::PointCloud2::ConstPtr& pCloud) { pcl::StopWatch watch;

// Solve all of perception here...
cv::Mat image_color = cv_bridge::toCvCopy(image_rgb)->image;

// new cloud formation 
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);

// new pcl::cloud from  sensormsg::cloud
pcl::fromROSMsg (*pCloud, *cloud);

}

it will be a great help if anyone can point out error or guide me in making process faster. because it makes my processing much slower. 30Hz to 10-12Hz.

Thanks

Regards, Prasanna

edit retag flag offensive close merge delete

Comments

I have this same problem, have you figured out a solution?

Thanks, Vincent

vkee gravatar image vkee  ( 2016-10-17 12:41:20 -0500 )edit

do you want synchronization? If not then this not a problem and you can run at 30Hz. let me know about it. I want to know the exact thing that you want to do and not just testing and hit-and-trial kind of thing. I hope you understood. Reply soon and I'll try to find a solution..

PKumars gravatar image PKumars  ( 2016-10-17 13:07:41 -0500 )edit

I don't need synchronization. I am just trying to pass around point clouds in ROS.

vkee gravatar image vkee  ( 2016-10-17 13:34:43 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-10-18 06:56:06 -0500

PKumars gravatar image

updated 2016-10-18 08:55:38 -0500

Thomas D gravatar image

Here is a sample that can solve your problem. This is a snippet and it should work properly with normal rate of 30Hz. If this is not solving then let me know about the exact problem.

//// c++ headers
#include <iostream>
// ROS headers
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
// point cloud definition
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
// namspace
using namespace std;
using namespace sensor_msgs;


void callback(const sensor_msgs::PointCloud2ConstPtr& pCloud)
{
// new cloud formation 
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg (*pCloud, *cloud);

// cloud is the one you are interested about.
}


int main(int argc, char** argv)
{
ros::init(argc, argv, "test_node");

ros::NodeHandle nh;
ros::Rate rate(30); // frequency of operation

// subscribe
ros::Subscriber sub = nh.subscribe ("/camera/depth/points", 1, callback);


ros::spin();
return 0;
}

Regards, Prasanna

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-03-25 06:16:49 -0500

Seen: 8,315 times

Last updated: Oct 18 '16