YARP
Yet Another Robot Platform
PointCloudUtils.h
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-License-Identifier: BSD-3-Clause
4  */
5 
6 #ifndef YARP_SIG_POINTCLOUDUTILS_H
7 #define YARP_SIG_POINTCLOUDUTILS_H
8 
9 #include <yarp/sig/Image.h>
11 #include <yarp/sig/PointCloud.h>
12 
13 namespace yarp {
14 namespace sig{
20 namespace utils
21 {
22 
23 enum class OrganizationType{
24  Organized,
26 };
27 
28 struct PCL_ROI
29 {
30  size_t min_x {0};
31  size_t max_x {0};
32  size_t min_y {0};
33  size_t max_y {0};
34 };
35 
45  const yarp::sig::IntrinsicParams& intrinsic);
46 
59  const yarp::sig::IntrinsicParams& intrinsic,
60  const yarp::sig::utils::PCL_ROI& roi,
61  size_t step_x,
62  size_t step_y);
63 
74 template<typename T1, typename T2>
76  const yarp::sig::ImageOf<T2>& color,
77  const yarp::sig::IntrinsicParams& intrinsic,
79 } // namespace utils
80 } // namespace sig
81 } // namespace yarp
82 
84 
85 #endif // YARP_SIG_POINTCLOUDUTILS_H
The PointCloud class.
Definition: PointCloud.h:24
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.
yarp::sig::PointCloud< T1 > depthRgbToPC(const yarp::sig::ImageOf< yarp::sig::PixelFloat > &depth, const yarp::sig::ImageOf< T2 > &color, const yarp::sig::IntrinsicParams &intrinsic, const yarp::sig::utils::OrganizationType organizationType=yarp::sig::utils::OrganizationType::Organized)
depthRgbToPC, compute the colored PointCloud given depth image, color image and the intrinsic paramet...
The main, catch-all namespace for YARP.
Definition: dirs.h:16
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).
#define YARP_sig_API
Definition: api.h:18