YARP
Yet Another Robot Platform
laserFromPointCloud.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #define _USE_MATH_DEFINES
20 
21 #include "laserFromPointCloud.h"
22 
23 #include <yarp/os/Time.h>
24 #include <yarp/os/Log.h>
25 #include <yarp/os/LogStream.h>
26 #include <yarp/os/ResourceFinder.h>
27 #include <yarp/math/Math.h>
28 
30 #include <yarp/os/Node.h>
31 #include <yarp/os/Publisher.h>
32 
33 #include <cmath>
34 #include <cstring>
35 #include <cstdlib>
36 #include <iostream>
37 #include <limits>
38 #include <mutex>
39 
40 using namespace std;
41 
42 #ifndef DEG2RAD
43 #define DEG2RAD M_PI/180.0
44 #endif
45 
46 YARP_LOG_COMPONENT(LASER_FROM_POINTCLOUD, "yarp.devices.laserFromPointCloud")
47 
48 /*
49 
50 yarpdev --device Rangefinder2DWrapper --subdevice laserFromPointCloud \
51  --ROS::useROS true --ROS::ROS_nodeName /cer-laserFront \
52  --ROS::ROS_topicName /laserDepth --ROS::frame_id /mobile_base_lidar_F \
53  --SENSOR \
54  --RGBD_SENSOR_CLIENT::localImagePort /clientRgbPort:i \
55  --RGBD_SENSOR_CLIENT::localDepthPort /clientDepthPort:i \
56  --RGBD_SENSOR_CLIENT::localRpcPort /clientRpcPort \
57  --RGBD_SENSOR_CLIENT::remoteImagePort /SIM_CER_ROBOT/depthCamera/rgbImage:o \
58  --RGBD_SENSOR_CLIENT::remoteDepthPort /SIM_CER_ROBOT/depthCamera/depthImage:o \
59  --RGBD_SENSOR_CLIENT::remoteRpcPort /SIM_CER_ROBOT/depthCamera/rpc:i \
60  --TRANSFORM_CLIENT::local /laserFromDepth/tfClient \
61  --TRANSFORM_CLIENT::remote /transformServer \
62  --Z_CLIPPING_PLANES::floor_height 0.15 \
63  --Z_CLIPPING_PLANES::ceiling_height 3.0 \
64  --Z_CLIPPING_PLANES::camera_frame_id depth_center \
65  --Z_CLIPPING_PLANES::ground_frame_id ground_link \
66  --publish_ROS_pointcloud \
67  --period 10 \
68  --name /outlaser:o
69 */
70 
72 yarp::os::Node * rosNode=nullptr;
73 
75 {
76  // rosNode = new yarp::os::Node("laserFromPointCloud");
77 
79  if (pointCloud_outTopic->topic("/ros_pc")==false)
80  {
81  yCError(LASER_FROM_POINTCLOUD) << "opening topic";
82  }
83  else
84  {
85  yCInfo(LASER_FROM_POINTCLOUD) << "topic successful";
86  }
87 }
88 
90 {
91  //yCDebug(LASER_FROM_POINTCLOUD) << "sizeof:" << sizeof(yarp::sig::DataXYZ);
92 
94  static int counter=0;
95  rosPC_data.header.stamp.nsec=0;
96  rosPC_data.header.stamp.sec=0;
97  rosPC_data.header.seq=counter++;
98  rosPC_data.header.frame_id = frame_id;
99 
100  rosPC_data.fields.resize(3);
101  rosPC_data.fields[0].name = "x";
102  rosPC_data.fields[0].offset = 0; // offset in bytes from start of each point
103  rosPC_data.fields[0].datatype = 7; // 7 = FLOAT32
104  rosPC_data.fields[0].count = 1; // how many FLOAT32 used for 'x'
105 
106  rosPC_data.fields[1].name = "y";
107  rosPC_data.fields[1].offset = 4; // offset in bytes from start of each point
108  rosPC_data.fields[1].datatype = 7; // 7 = FLOAT32
109  rosPC_data.fields[1].count = 1; // how many FLOAT32 used for 'y'
110 
111  rosPC_data.fields[2].name = "z";
112  rosPC_data.fields[2].offset = 8; // offset in bytes from start of each point
113  rosPC_data.fields[2].datatype = 7; // 7 = FLOAT32
114  rosPC_data.fields[2].count = 1; // how many FLOAT32 used for 'z'
115 
116 #if defined(YARP_BIG_ENDIAN)
117  rosPC_data.is_bigendian = true;
118 #elif defined(YARP_LITTLE_ENDIAN)
119  rosPC_data.is_bigendian = false;
120 #else
121  #error "Cannot detect endianness"
122 #endif
123 
124 #if 0
125  rosPC_data.height=1;
126  rosPC_data.width=pc.size();
127 #else
128  rosPC_data.height=pc.height();
129  rosPC_data.width=pc.width();
130 #endif
131 
132  rosPC_data.point_step = 3*4; //x, y, z
133  rosPC_data.row_step = rosPC_data.point_step*rosPC_data.width; //12 *number of points bytes
134  rosPC_data.is_dense = true; // what this field actually means?? When is it false??
135  rosPC_data.data.resize(rosPC_data.row_step*rosPC_data.height);
136 
137  const char* ypointer = pc.getRawData()+12;
138  unsigned char* rpointer = rosPC_data.data.data();
139 
140  //yCDebug(LASER_FROM_POINTCLOUD)<< pc.size() << pc.size()*4*4 << pc.dataSizeBytes() << rosPC_data.data.size();
141  size_t elem =0;
142  size_t yelem=0;
143  for (; elem<pc.size()*3*4; elem++)
144  {
145  *rpointer=*ypointer;
146  rpointer++;
147  ypointer++; yelem++;
148  if (elem%12==0) { ypointer+=4; yelem+=4;}
149  // yCDebug(LASER_FROM_POINTCLOUD << "%d" <<ypointer;
150  }
151  //yCDebug(LASER_FROM_POINTCLOUD)<<elem <<yelem;
152 
153  if (pointCloud_outTopic) pointCloud_outTopic->write(rosPC_data);
154 }
155 
156 //-------------------------------------------------------------------------------------
157 
159 {
160  Property subConfig;
161  m_info = "LaserFromPointCloud device";
162 
163 #ifdef LASER_DEBUG
164  yCDebug(LASER_FROM_POINTCLOUD) << "%s\n", config.toString().c_str();
165 #endif
166 
167  m_min_distance = 0.1; //m
168  m_max_distance = 5.0; //m
169  m_floor_height = 0.1; //m
170  m_pointcloud_max_distance = 10.0; //m
171  m_ceiling_height = 2; //m
172  m_publish_ros_pc = false;
173 
174  m_sensorsNum = 360;
175  m_resolution = 1;
176  m_laser_data.resize(m_sensorsNum, 0.0);
177  m_max_angle = 360;
178  m_min_angle = 0;
179 
180  m_pc_stepx=2;
181  m_pc_stepy=2;
182 
183  m_transform_mtrx.resize(4,4);
184  m_transform_mtrx.eye();
185 
186 
187  m_ground_frame_id = "/ground_frame";
188  m_camera_frame_id = "/depth_camera_frame";
189 
190  if (config.check("publish_ROS_pointcloud"))
191  {
192  m_publish_ros_pc=true;
193  yCDebug(LASER_FROM_POINTCLOUD) << "User requested to publish ROS pointcloud (debug mode)";
194  }
195 
196  bool bpcr = config.check("POINTCLOUD_QUALITY");
197  if (bpcr != false)
198  {
199  yarp::os::Searchable& pointcloud_quality_config = config.findGroup("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(); }
202  yCInfo(LASER_FROM_POINTCLOUD) << "Pointcloud decimation step set to:" << m_pc_stepx << m_pc_stepy;
203  }
204 
205  bool bpc = config.check("Z_CLIPPING_PLANES");
206  if (bpc != false)
207  {
208  yarp::os::Searchable& pointcloud_clip_config = config.findGroup("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();}
214  }
215  yCInfo(LASER_FROM_POINTCLOUD) <<"Z clipping planes (floor,ceiling) have been set to ("<< m_floor_height <<","<< m_ceiling_height <<")";
216 
217  if (this->parseConfiguration(config) == false)
218  {
219  yCError(LASER_FROM_POINTCLOUD) << "Error parsing parameters";
220  return false;
221  }
222 
223  //open the tc client
224  Property tcprop;
225  if(!config.check("TRANSFORM_CLIENT"))
226  {
227  yCError(LASER_FROM_POINTCLOUD) << "missing TRANSFORM_CLIENT section in configuration file!";
228  return false;
229  }
230  tcprop.fromString(config.findGroup("TRANSFORM_CLIENT").toString());
231  tcprop.put("device", "transformClient");
232 
233  m_tc_driver.open(tcprop);
234  if (!m_tc_driver.isValid())
235  {
236  yCError(LASER_FROM_POINTCLOUD) << "Error opening PolyDriver check parameters";
237  return false;
238  }
239  m_tc_driver.view(m_iTc);
240  if (!m_iTc)
241  {
242  yCError(LASER_FROM_POINTCLOUD) << "Error opening iFrameTransform interface. Device not available";
243  return false;
244  }
246 
247 
248  //open the rgbd client
249  Property prop;
250  if(!config.check("RGBD_SENSOR_CLIENT"))
251  {
252  yCError(LASER_FROM_POINTCLOUD) << "missing RGBD_SENSOR_CLIENT section in configuration file!";
253  return false;
254  }
255  prop.fromString(config.findGroup("RGBD_SENSOR_CLIENT").toString());
256  prop.put("device", "RGBDSensorClient");
257  //prop.put("ImageCarrier","mjpeg"); //this is set in the ini file
258  //prop.put("DepthCarrier","udp"); //this is set in the ini file
259  m_rgbd_driver.open(prop);
260  if (!m_rgbd_driver.isValid())
261  {
262  yCError(LASER_FROM_POINTCLOUD) << "Error opening PolyDriver check parameters";
263  return false;
264  }
265  m_rgbd_driver.view(m_iRGBD);
266  if (!m_iRGBD)
267  {
268  yCError(LASER_FROM_POINTCLOUD) << "Error opening iRGBD interface. Device not available";
269  return false;
270  }
272 
273  //get parameters data from the camera
274  m_depth_width = m_iRGBD->getRgbWidth(); //@@@ this is horrible! See yarp issue: https://github.com/robotology/yarp/issues/2290
275  m_depth_height = m_iRGBD->getRgbHeight(); //@@@ this is horrible! See yarp issue: https://github.com/robotology/yarp/issues/2290
276  bool propintr = m_iRGBD->getDepthIntrinsicParam(m_propIntrinsics);
277  YARP_UNUSED(propintr);
278  yCInfo(LASER_FROM_POINTCLOUD) << "Depth Intrinsics:" << m_propIntrinsics.toString();
279  m_intrinsics.fromProperty(m_propIntrinsics);
280 
281  PeriodicThread::start();
282  yCInfo(LASER_FROM_POINTCLOUD) << "Sensor ready";
283 
284  //init ros
285  if (m_publish_ros_pc)
286  {
287  ros_init_pc();
288  }
289 
290  return true;
291 }
292 
294 {
295  PeriodicThread::stop();
296 
297  if(m_rgbd_driver.isValid())
298  m_rgbd_driver.close();
299 
300  if(m_tc_driver.isValid())
301  m_tc_driver.close();
302 
303  yCInfo(LASER_FROM_POINTCLOUD) << "closed";
304  return true;
305 }
306 
307 bool LaserFromPointCloud::setDistanceRange(double min, double max)
308 {
309  std::lock_guard<std::mutex> guard(m_mutex);
310  m_min_distance = min;
311  m_max_distance = max;
312  return true;
313 }
314 
315 
316 bool LaserFromPointCloud::setScanLimits(double min, double max)
317 {
318  std::lock_guard<std::mutex> guard(m_mutex);
319  yCWarning(LASER_FROM_POINTCLOUD,"setScanLimits not yet implemented");
320  return true;
321 }
322 
324 {
325  std::lock_guard<std::mutex> guard(m_mutex);
326  yCWarning(LASER_FROM_POINTCLOUD,"setHorizontalResolution not yet implemented");
327  return true;
328 }
329 
331 {
332  std::lock_guard<std::mutex> guard(m_mutex);
333  yCWarning(LASER_FROM_POINTCLOUD,"setScanRate not yet implemented");
334  return false;
335 }
336 
337 
339 {
340 #ifdef LASER_DEBUG
341  yCDebug(LASER_FROM_POINTCLOUD) << "thread initialising...\n";
342  yCDebug(LASER_FROM_POINTCLOUD) << "... done!\n");
343 #endif
344 
345  return true;
346 }
347 
349 {
350  for (size_t i=0; i<pc.size(); i++)
351  {
352  auto v1 = pc(i).toVector4();
353  auto v2 = m*v1;
354  pc(i).x=v2(0);
355  pc(i).y=v2(1);
356  pc(i).z=v2(2);
357  }
358 }
359 
361 {
362 #ifdef DEBUG_TIMING
363  static double t3 = yarp::os::Time::now();
364  double t1 = yarp::os::Time::now();
365  yCDebug(LASER_FROM_POINTCLOUD) << "thread period:" <<t1- t3;
366  t3 = yarp::os::Time::now();
367 #endif
368 
369  bool depth_ok = m_iRGBD->getDepthImage(m_depth_image);
370  if (depth_ok == false)
371  {
372  yCDebug(LASER_FROM_POINTCLOUD) << "getDepthImage failed";
373  return;
374  }
375 
376  if (m_depth_image.getRawImage()==nullptr)
377  {
378  yCDebug(LASER_FROM_POINTCLOUD)<<"invalid image received";
379  return;
380  }
381 
382  if (m_depth_image.width() != m_depth_width ||
383  m_depth_image.height() != m_depth_height)
384  {
385  yCDebug(LASER_FROM_POINTCLOUD)<<"invalid image size: (" << m_depth_image.width() << " " << m_depth_image.height() << ") vs (" << m_depth_width << " " << m_depth_height << ")" ;
386  return;
387  }
388 
389  const double myinf =std::numeric_limits<double>::infinity();
390  const double mynan =std::nan("");
391 
392  //compute the point cloud
393  yarp::sig::PointCloud<yarp::sig::DataXYZ> pc = yarp::sig::utils::depthToPC(m_depth_image, m_intrinsics,m_pc_roi,m_pc_stepx,m_pc_stepy);
394 
395 
396  //if (m_publish_ros_pc) {ros_compute_and_send_pc(pc,m_camera_frame_id);}//<-------------------------
397 
398 #ifdef TEST_M
399  //yCDebug(LASER_FROM_POINTCLOUD) << "pc size:" << pc.size();
400 #endif
401 
402  //we compute the transformation matrix from the camera to the laser reference frame
403 
404 #ifdef TEST_M
405  yarp::sig::Vector vvv(3);
406  vvv(0)=-1.57;
407  vvv(1)=0;
408  vvv(2)=-1.57;
409  m = yarp::math::rpy2dcm(vvv);
410  m(2,3)=1.2; //z translation
411 #else
412  bool frame_exists = m_iTc->getTransform(m_camera_frame_id,m_ground_frame_id, m_transform_mtrx);
413  if (frame_exists==false)
414  {
415  yCWarning(LASER_FROM_POINTCLOUD) << "Unable to found m matrix";
416  }
417 #endif
418 
419  //we rototranslate the full pointcloud
420  rotate_pc(pc, m_transform_mtrx);
421 
422  if (m_publish_ros_pc) {ros_compute_and_send_pc(pc,m_ground_frame_id);}//<-------------------------
423 
424  yarp::sig::Vector left(4);
425  left[0] = (0 - m_intrinsics.principalPointX)/m_intrinsics.focalLengthX*1000;
426  left[1] = (0 - m_intrinsics.principalPointY)/m_intrinsics.focalLengthY*1000;
427  left[2] = 1000;
428  left[3] = 1;
429 
430  yarp::sig::Vector right(4);
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;
433  right[2] = 1000;
434  right[3] = 1;
435 
436  double left_dist;
437  double left_theta;
438  double right_dist;
439  double right_theta;
440  left = m_transform_mtrx * left;
441  right = m_transform_mtrx * right;
442 
443  LaserMeasurementData data_left;
444  data_left.set_cartesian(left[0],left[1]);
445  data_left.get_polar(left_dist, left_theta);
446 
447  LaserMeasurementData data_right;
448  data_right.set_cartesian(right[0],right[1]);
449  data_right.get_polar(right_dist, right_theta);
450 
451  bool left_elem_neg = 0;
452  bool right_elem_neg = 0;
453 
454  left_theta=left_theta*180/M_PI;
455  right_theta=right_theta*180/M_PI;
456 
457  if (left_theta<0)
458  {
459  left_theta+=360;
460  left_elem_neg = 1;
461  }
462  else if (left_theta>360) left_theta-=360;
463  size_t left_elem= left_theta/m_resolution;
464 
465  if (right_theta<0)
466  {
467  right_theta+=360;
468  right_elem_neg = 1;
469  }
470  else if (right_theta>360) right_theta-=360;
471  size_t right_elem= right_theta/m_resolution;
472 
473  //enter critical section and protect m_laser_data
474  std::lock_guard<std::mutex> guard(m_mutex);
475 #ifdef DEBUG_TIMING
476  double t4 = yarp::os::Time::now();
477 #endif
478  //prepare an empty laserscan vector with the resolution we want
479  for (auto it= m_laser_data.begin(); it!=m_laser_data.end(); it++)
480  {
481  *it= mynan;
482  }
483 
484  if ((!left_elem_neg) && (right_elem_neg))
485  {
486  for (size_t i=0; i<left_elem; i++)
487  {
488  m_laser_data[i] = myinf;
489  }
490  for (size_t i=right_elem; i<m_sensorsNum; i++)
491  {
492  m_laser_data[i] = myinf;
493  }
494  }
495  else
496  {
497  for (size_t i=right_elem; i<left_elem; i++)
498  {
499  m_laser_data[i] = myinf;
500  }
501  }
502 
503 
504 
505  for (size_t i=0; i<pc.size(); i++)
506  {
507 
508 #ifdef TEST_M
509  //yCDebug(LASER_FROM_POINTCLOUD) << pc(i).toString(5,5);
510 #endif
511 
512  //we obtain a point from the point cloud
513  yarp::sig::Vector vec= pc(i).toVector4();
514 
515  //we check if the point is in the volume that we want to consider as possibile obstacle
516  if (vec[2]>m_floor_height && vec[2]<m_ceiling_height &&
517  vec[0]<m_pointcloud_max_distance)
518  {
519 #ifdef TEST_M
520  // yCDebug(LASER_FROM_POINTCLOUD) << "This point is ok:" << i <<"its z is:" << tvec[2];
521 #endif
522  //by removing z, we project the 3d point on the 2D plane on which the laser works.
523  //we use LaserMeasurementData struct to easily obtain a polar representation from a cartesian representation
525  data.set_cartesian(vec[0],vec[1]);
526 
527  //get the polar representation
528  double distance;
529  double theta;
530  data.get_polar(distance, theta);
531 
532  //compute the right element of the vector where to put distance data. This is done by clusterizing angles, depending on the laser resolution.
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())
538  {
539  yCError(LASER_FROM_POINTCLOUD) << "Error in computing elem" << i << ">" << m_laser_data.size();
540  continue;
541  }
542 
543 #ifdef TEST_M
544  // yCDebug(LASER_FROM_POINTCLOUD) <<theta << elem <<distance;
545 #endif
546  //update the vector of measurements, putting the NEAREST obstacle in right element of the vector.
547  if (distance<m_laser_data[elem])
548  {
549  m_laser_data[elem]=distance;
550  }
551  }
552  else
553  {
554 #ifdef TEST_M
555  //yCDebug(LASER_FROM_POINTCLOUD) << "this point is out of considered volume:" <<i << " z:" << vec[2];
556 #endif
557  }
558  }
559  applyLimitsOnLaserData();
560 
561 #ifdef DEBUG_TIMING
562  double t2 = yarp::os::Time::now();
563  yCDebug(LASER_FROM_POINTCLOUD) << "tot run:" << t2 - t1 << "crit run:" << t2-t4;
564 #endif
565 
566  return;
567 }
568 
570 {
571 #ifdef LASER_DEBUG
572  yCDebug(LASER_FROM_POINTCLOUD) << "Thread releasing...";
573  yCDebug(LASER_FROM_POINTCLOUD) << "... done.";
574 #endif
575 
576  return;
577 }
LogStream.h
yarp::dev::LaserMeasurementData
\LaserMeasurementData
Definition: LaserMeasurementData.h:28
PointCloud2.h
yarp::rosmsg::sensor_msgs::PointCloud2::row_step
std::uint32_t row_step
Definition: PointCloud2.h:66
LaserFromPointCloud::setScanRate
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
Definition: laserFromPointCloud.cpp:330
yarp::rosmsg::sensor_msgs::PointCloud2::is_bigendian
bool is_bigendian
Definition: PointCloud2.h:64
yarp::dev::LaserMeasurementData::get_polar
void get_polar(double &rho, double &theta)
Definition: LaserMeasurementData.cpp:34
yarp::os::Bottle::toString
std::string toString() const override
Gives a human-readable textual representation of the bottle.
Definition: Bottle.cpp:214
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::rosmsg::sensor_msgs::PointCloud2
Definition: PointCloud2.h:58
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
M_PI
#define M_PI
Definition: fakeLocalizerDev.cpp:44
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
LaserFromPointCloud::run
void run() override
Loop function.
Definition: laserFromPointCloud.cpp:360
yarp::rosmsg::sensor_msgs::PointCloud2::point_step
std::uint32_t point_step
Definition: PointCloud2.h:65
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
ros_init_pc
void ros_init_pc()
Definition: laserFromPointCloud.cpp:74
yarp::os::Property::fromString
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
Definition: Property.cpp:1046
yarp::sig::PointCloud::size
size_t size() const override
Definition: PointCloud.h:110
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
yarp::rosmsg::std_msgs::Header::frame_id
std::string frame_id
Definition: Header.h:49
ros_compute_and_send_pc
void ros_compute_and_send_pc(const yarp::sig::PointCloud< yarp::sig::DataXYZ > &pc, string frame_id)
Definition: laserFromPointCloud.cpp:89
YARP_UNUSED
#define YARP_UNUSED(var)
Definition: api.h:159
yarp::rosmsg::sensor_msgs::PointCloud2::fields
std::vector< yarp::rosmsg::sensor_msgs::PointField > fields
Definition: PointCloud2.h:63
yarp::os::Publisher
A port specialized for publishing data of a constant type on a topic.
Definition: Publisher.h:26
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::sig::PointCloud::getRawData
const char * getRawData() const override
Get the pointer to the data.
Definition: PointCloud.h:85
LaserFromPointCloud::open
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: laserFromPointCloud.cpp:158
yarp::math::rpy2dcm
yarp::sig::Matrix rpy2dcm(const yarp::sig::Vector &rpy)
Converts roll-pitch-yaw angles in the corresponding dcm (direction cosine matrix) rotation matrix (de...
Definition: math.cpp:818
yarp::sig::PointCloud
The PointCloud class.
Definition: PointCloud.h:27
yarp::sig::VectorOf< double >
Log.h
yarp::rosmsg::std_msgs::Header::seq
std::uint32_t seq
Definition: Header.h:47
yarp::sig::utils::depthToPC
yarp::sig::PointCloud< yarp::sig::DataXYZ > depthToPC(const yarp::sig::ImageOf< yarp::sig::PixelFloat > &depth, const yarp::sig::IntrinsicParams &intrinsic)
depthToPC, compute the PointCloud given depth image and the intrinsic parameters of the camera.
Definition: PointCloudUtils.cpp:19
pointCloud_outTopic
yarp::os::Publisher< yarp::rosmsg::sensor_msgs::PointCloud2 > * pointCloud_outTopic
Definition: laserFromPointCloud.cpp:71
Math.h
rotate_pc
void rotate_pc(yarp::sig::PointCloud< yarp::sig::DataXYZ > &pc, const yarp::sig::Matrix &m)
Definition: laserFromPointCloud.cpp:348
LASER_FROM_POINTCLOUD
const yarp::os::LogComponent & LASER_FROM_POINTCLOUD()
Definition: laserFromPointCloud.cpp:46
yarp::rosmsg::TickTime::sec
std::uint32_t sec
Definition: TickTime.h:32
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
sensor_msgs::PointCloud2
yarp::rosmsg::sensor_msgs::PointCloud2 PointCloud2
Definition: PointCloud2.h:24
yarp::rosmsg::sensor_msgs::PointCloud2::height
std::uint32_t height
Definition: PointCloud2.h:61
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
Node.h
rosNode
yarp::os::Node * rosNode
Definition: laserFromPointCloud.cpp:72
yarp::rosmsg::sensor_msgs::PointCloud2::header
yarp::rosmsg::std_msgs::Header header
Definition: PointCloud2.h:60
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
yarp::os::Node
The Node class.
Definition: Node.h:27
LaserFromPointCloud::setDistanceRange
bool setDistanceRange(double min, double max) override
set the device detection range.
Definition: laserFromPointCloud.cpp:307
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
LaserFromPointCloud::threadInit
bool threadInit() override
Initialization method.
Definition: laserFromPointCloud.cpp:338
yarp::rosmsg::sensor_msgs::PointCloud2::width
std::uint32_t width
Definition: PointCloud2.h:62
yarp::dev::LaserMeasurementData::set_cartesian
void set_cartesian(const double x, const double y)
Definition: LaserMeasurementData.cpp:19
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
Publisher.h
yarp::sig::PointCloudBase::height
virtual size_t height() const
Definition: PointCloudBase.cpp:92
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
LaserFromPointCloud::setScanLimits
bool setScanLimits(double min, double max) override
set the scan angular range.
Definition: laserFromPointCloud.cpp:316
yarp::rosmsg::TickTime::nsec
std::uint32_t nsec
Definition: TickTime.h:33
Time.h
yarp::sig::PointCloudBase::width
virtual size_t width() const
Definition: PointCloudBase.cpp:97
LaserFromPointCloud::setHorizontalResolution
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
Definition: laserFromPointCloud.cpp:323
sensor_msgs
Definition: BatteryState.h:22
laserFromPointCloud.h
yarp::os::Value::asFloat64
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
LaserFromPointCloud::threadRelease
void threadRelease() override
Release method.
Definition: laserFromPointCloud.cpp:569
yarp::rosmsg::std_msgs::Header::stamp
yarp::rosmsg::TickTime stamp
Definition: Header.h:48
yarp::os::Time::delay
void delay(double seconds)
Wait for a certain number of seconds.
Definition: Time.cpp:114
yarp::rosmsg::sensor_msgs::PointCloud2::data
std::vector< std::uint8_t > data
Definition: PointCloud2.h:67
ResourceFinder.h
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
yarp::rosmsg::sensor_msgs::PointCloud2::is_dense
bool is_dense
Definition: PointCloud2.h:68
LaserFromPointCloud::close
bool close() override
Close the DeviceDriver.
Definition: laserFromPointCloud.cpp:293
yarp::sig::Matrix
A class for a Matrix.
Definition: Matrix.h:46