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