Hot do I obtain PointCloud2 data?
Hello all,
So I am trying obtain a PointCloud2 (from the Kinect) but I am very confused now. I am using C++ with the Freenect driver but I think it's very similar to the OpenNI driver.
Let's get started. First I run the
roscore
command, followed by
roslaunch freenect_launch freenect.launch
to activate the Kinect.
The I wrote code that will subscribe to the "/camera/depth_registered/points" topic and write the data to a text file. The message type that this topic sends is sensor_msgs/PointCloud2.
Here is my code:
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "sensor_msgs/PointCloud2.h"
#include <iostream>
#include <fstream>
using namespace std;
ofstream myfile;
void pointCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
{
myfile.open("ROS/catkin_ws/src/read_kinect_01/txt_files/saves.txt");
//myfile <<"Data is: " << msg->data; //This does not work
myfile << "Data is:" << msg->height; //This works :)
myfile.close();
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "front_end");
ros::NodeHandle n;
string topic = n.resolveName("/camera/depth_registered/points");
uint32_t queue_size = 1;
//ros::Subscriber sub = n.subscribe("/camera/depth_registered/points", 1000, pointCallback); //Second solution
ros::Subscriber sub = n.subscribe<sensor_msgs::PointCloud2> (topic, queue_size, pointCallback);
ros::spin();
return 0;
}
I am able to save all different information that this messages provides except the "data" one.
Then I read some information on PointCloud2 data type from HERE. Also read the namespace of sensor_msgs but still can't understand how it works.
What I want to do is get the XYZRGB point from the kinect and then process the RGB data, followed by using the XYZ data afterwards. All of this in the C++ code.
How do I gain access to the XYZRGB point? I am really confused :/
Please update with the actual error you get when you try to use this code. Is it a compile-time or run-time issue? What's the exact error text?