24 #include <std_msgs/Empty.h>
25 #include <sensor_msgs/PointCloud2.h>
35 SelectPointCloudPublishAction::SelectPointCloudPublishAction( QWidget* parent )
52 int num_children = model_->
rowCount();
53 if( num_children > 0 )
56 sensor_msgs::PointCloud2 pc2;
58 pc2.header.frame_id =
"camera_depth_optical_frame";
60 pc2.width = num_children;
63 pc2.fields[0].name =
"x";
64 pc2.fields[1].name =
"y";
65 pc2.fields[2].name =
"z";
66 pc2.fields[3].name =
"rgb";
67 pc2.fields[0].offset = 0;
68 pc2.fields[1].offset = 4;
69 pc2.fields[2].offset = 8;
70 pc2.fields[3].offset = 12;
71 pc2.fields[0].count = pc2.fields[1].count = pc2.fields[2].count = pc2.fields[3].count = 1;
72 pc2.fields[0].datatype = pc2.fields[1].datatype = pc2.fields[2].datatype = pc2.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
74 pc2.data.resize(num_children * 4 *
sizeof(
float));
75 for(
int i = 0; i < num_children; i++ )
77 QModelIndex child_index = model_->
index( i, 0, QModelIndex());
81 Ogre::Vector3 point_vec = vec_data->
getVector();
85 if (color_data !=
NULL && color_data->
getColor().isValid()) {
86 Ogre::ColourValue point_color = color_data->
getOgreColor();
87 rgb_int = (int)point_color.r << 16 | (
int)point_color.g << 8 | (int)point_color.b << 0;
89 float x = point_vec.x,
y = point_vec.y,
z = point_vec.z;
91 float rgb_float = *
reinterpret_cast<float*
>(&rgb_int);
92 memcpy(&pc2.data[i*4*
sizeof(
float)], &
x,
sizeof(
float));
93 memcpy(&pc2.data[(i*4+1)*
sizeof(
float)], &
y,
sizeof(
float));
94 memcpy(&pc2.data[(i*4+2)*
sizeof(
float)], &
z,
sizeof(
float));
95 memcpy(&pc2.data[(i*4+3)*
sizeof(
float)], &rgb_float,
sizeof(
float));
99 pc2.row_step = pc2.point_step * pc2.width;
100 pc2.is_dense =
false;