YARP
Yet Another Robot Platform
PointCloudUtils.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 #ifndef YARP_SIG_POINTCLOUDUTILS_H
10 #define YARP_SIG_POINTCLOUDUTILS_H
11 
12 #include <yarp/sig/Image.h>
14 #include <yarp/sig/PointCloud.h>
15 
16 namespace yarp {
17 namespace sig{
23 namespace utils
24 {
25 
26 struct PCL_ROI
27 {
28  size_t min_x {0};
29  size_t max_x {0};
30  size_t min_y {0};
31  size_t max_y {0};
32 };
33 
43  const yarp::sig::IntrinsicParams& intrinsic);
44 
57  const yarp::sig::IntrinsicParams& intrinsic,
58  const yarp::sig::utils::PCL_ROI& roi,
59  size_t step_x,
60  size_t step_y);
61 
72 template<typename T1, typename T2>
74  const yarp::sig::ImageOf<T2>& color,
75  const yarp::sig::IntrinsicParams& intrinsic);
76 } // namespace utils
77 } // namespace sig
78 } // namespace yarp
79 
81 
82 #endif // YARP_SIG_POINTCLOUDUTILS_H
IntrinsicParams.h
PointCloud.h
yarp::sig::utils::PCL_ROI::min_y
size_t min_y
Definition: PointCloudUtils.h:30
yarp::sig::utils::PCL_ROI
Definition: PointCloudUtils.h:27
yarp::sig::utils::PCL_ROI::max_x
size_t max_x
Definition: PointCloudUtils.h:29
yarp::sig::utils::PCL_ROI::max_y
size_t max_y
Definition: PointCloudUtils.h:31
yarp::sig::ImageOf< yarp::sig::PixelFloat >
yarp::sig::PointCloud
The PointCloud class.
Definition: PointCloud.h:27
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
PointCloudUtils-inl.h
yarp::sig::utils::PCL_ROI::min_x
size_t min_x
Definition: PointCloudUtils.h:28
YARP_sig_API
#define YARP_sig_API
Definition: api.h:19
Image.h
yarp::sig::utils::depthRgbToPC
yarp::sig::PointCloud< T1 > depthRgbToPC(const yarp::sig::ImageOf< yarp::sig::PixelFloat > &depth, const yarp::sig::ImageOf< T2 > &color, const yarp::sig::IntrinsicParams &intrinsic)
depthRgbToPC, compute the colored PointCloud given depth image, color image and the intrinsic paramet...
Definition: PointCloudUtils-inl.h:68
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::sig::IntrinsicParams
The IntrinsicParams struct to handle the intrinsic parameter of cameras(RGB and RGBD either).
Definition: IntrinsicParams.h:44