Conversion of pointCloud using pcl::fromROSMsg makes process much slower.
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
I have this same problem, have you figured out a solution?
Thanks, Vincent
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..
I don't need synchronization. I am just trying to pass around point clouds in ROS.