19 #define _USE_MATH_DEFINES
43 #define DEG2RAD M_PI/180.0
100 rosPC_data.
fields.resize(3);
101 rosPC_data.
fields[0].name =
"x";
102 rosPC_data.
fields[0].offset = 0;
103 rosPC_data.
fields[0].datatype = 7;
104 rosPC_data.
fields[0].count = 1;
106 rosPC_data.
fields[1].name =
"y";
107 rosPC_data.
fields[1].offset = 4;
108 rosPC_data.
fields[1].datatype = 7;
109 rosPC_data.
fields[1].count = 1;
111 rosPC_data.
fields[2].name =
"z";
112 rosPC_data.
fields[2].offset = 8;
113 rosPC_data.
fields[2].datatype = 7;
114 rosPC_data.
fields[2].count = 1;
116 #if defined(YARP_BIG_ENDIAN)
118 #elif defined(YARP_LITTLE_ENDIAN)
121 #error "Cannot detect endianness"
138 unsigned char* rpointer = rosPC_data.
data.data();
143 for (; elem<pc.
size()*3*4; elem++)
148 if (elem%12==0) { ypointer+=4; yelem+=4;}
161 m_info =
"LaserFromPointCloud device";
167 m_min_distance = 0.1;
168 m_max_distance = 5.0;
169 m_floor_height = 0.1;
170 m_pointcloud_max_distance = 10.0;
171 m_ceiling_height = 2;
172 m_publish_ros_pc =
false;
176 m_laser_data.resize(m_sensorsNum, 0.0);
183 m_transform_mtrx.resize(4,4);
184 m_transform_mtrx.eye();
187 m_ground_frame_id =
"/ground_frame";
188 m_camera_frame_id =
"/depth_camera_frame";
190 if (config.
check(
"publish_ROS_pointcloud"))
192 m_publish_ros_pc=
true;
196 bool bpcr = config.
check(
"POINTCLOUD_QUALITY");
200 if (pointcloud_quality_config.
check(
"x_step")) { m_pc_stepx = pointcloud_quality_config.
find(
"x_step").
asFloat64(); }
201 if (pointcloud_quality_config.
check(
"y_step")) { m_pc_stepy = pointcloud_quality_config.
find(
"y_step").
asFloat64(); }
205 bool bpc = config.
check(
"Z_CLIPPING_PLANES");
209 if (pointcloud_clip_config.
check(
"floor_height")) {m_floor_height = pointcloud_clip_config.
find(
"floor_height").
asFloat64();}
210 if (pointcloud_clip_config.
check(
"ceiling_height")) {m_ceiling_height=pointcloud_clip_config.
find(
"ceiling_height").
asFloat64();}
211 if (pointcloud_clip_config.
check(
"max_distance")) { m_pointcloud_max_distance = pointcloud_clip_config.
find(
"max_distance").
asFloat64(); }
212 if (pointcloud_clip_config.
check(
"ground_frame_id")) {m_ground_frame_id = pointcloud_clip_config.
find(
"ground_frame_id").
asString();}
213 if (pointcloud_clip_config.
check(
"camera_frame_id")) {m_camera_frame_id = pointcloud_clip_config.
find(
"camera_frame_id").
asString();}
215 yCInfo(
LASER_FROM_POINTCLOUD) <<
"Z clipping planes (floor,ceiling) have been set to ("<< m_floor_height <<
","<< m_ceiling_height <<
")";
217 if (this->parseConfiguration(config) ==
false)
225 if(!config.
check(
"TRANSFORM_CLIENT"))
231 tcprop.
put(
"device",
"transformClient");
233 m_tc_driver.open(tcprop);
234 if (!m_tc_driver.isValid())
239 m_tc_driver.view(m_iTc);
250 if(!config.
check(
"RGBD_SENSOR_CLIENT"))
256 prop.
put(
"device",
"RGBDSensorClient");
259 m_rgbd_driver.open(prop);
260 if (!m_rgbd_driver.isValid())
265 m_rgbd_driver.view(m_iRGBD);
274 m_depth_width = m_iRGBD->getRgbWidth();
275 m_depth_height = m_iRGBD->getRgbHeight();
276 bool propintr = m_iRGBD->getDepthIntrinsicParam(m_propIntrinsics);
279 m_intrinsics.fromProperty(m_propIntrinsics);
281 PeriodicThread::start();
285 if (m_publish_ros_pc)
295 PeriodicThread::stop();
297 if(m_rgbd_driver.isValid())
298 m_rgbd_driver.close();
300 if(m_tc_driver.isValid())
309 std::lock_guard<std::mutex> guard(m_mutex);
310 m_min_distance = min;
311 m_max_distance = max;
318 std::lock_guard<std::mutex> guard(m_mutex);
325 std::lock_guard<std::mutex> guard(m_mutex);
332 std::lock_guard<std::mutex> guard(m_mutex);
350 for (
size_t i=0; i<pc.
size(); i++)
352 auto v1 = pc(i).toVector4();
369 bool depth_ok = m_iRGBD->getDepthImage(m_depth_image);
370 if (depth_ok ==
false)
376 if (m_depth_image.getRawImage()==
nullptr)
382 if (m_depth_image.width() != m_depth_width ||
383 m_depth_image.height() != m_depth_height)
385 yCDebug(
LASER_FROM_POINTCLOUD)<<
"invalid image size: (" << m_depth_image.width() <<
" " << m_depth_image.height() <<
") vs (" << m_depth_width <<
" " << m_depth_height <<
")" ;
389 const double myinf =std::numeric_limits<double>::infinity();
390 const double mynan =std::nan(
"");
412 bool frame_exists = m_iTc->getTransform(m_camera_frame_id,m_ground_frame_id, m_transform_mtrx);
413 if (frame_exists==
false)
425 left[0] = (0 - m_intrinsics.principalPointX)/m_intrinsics.focalLengthX*1000;
426 left[1] = (0 - m_intrinsics.principalPointY)/m_intrinsics.focalLengthY*1000;
431 right[0] = (m_depth_image.width() - m_intrinsics.principalPointX)/m_intrinsics.focalLengthX*1000;
432 right[1] = (0 - m_intrinsics.principalPointY)/m_intrinsics.focalLengthY*1000;
440 left = m_transform_mtrx * left;
441 right = m_transform_mtrx * right;
445 data_left.
get_polar(left_dist, left_theta);
449 data_right.
get_polar(right_dist, right_theta);
451 bool left_elem_neg = 0;
452 bool right_elem_neg = 0;
454 left_theta=left_theta*180/
M_PI;
455 right_theta=right_theta*180/
M_PI;
462 else if (left_theta>360) left_theta-=360;
463 size_t left_elem= left_theta/m_resolution;
470 else if (right_theta>360) right_theta-=360;
471 size_t right_elem= right_theta/m_resolution;
474 std::lock_guard<std::mutex> guard(m_mutex);
479 for (
auto it= m_laser_data.begin(); it!=m_laser_data.end(); it++)
484 if ((!left_elem_neg) && (right_elem_neg))
486 for (
size_t i=0; i<left_elem; i++)
488 m_laser_data[i] = myinf;
490 for (
size_t i=right_elem; i<m_sensorsNum; i++)
492 m_laser_data[i] = myinf;
497 for (
size_t i=right_elem; i<left_elem; i++)
499 m_laser_data[i] = myinf;
505 for (
size_t i=0; i<pc.
size(); i++)
516 if (vec[2]>m_floor_height && vec[2]<m_ceiling_height &&
517 vec[0]<m_pointcloud_max_distance)
533 theta=theta*180/
M_PI;
534 if (theta<0) theta+=360;
535 else if (theta>360) theta-=360;
536 size_t elem= theta/m_resolution;
537 if (elem>=m_laser_data.size())
547 if (distance<m_laser_data[elem])
549 m_laser_data[elem]=distance;
559 applyLimitsOnLaserData();