corelib
include
rtabmap
core
clams
frame_projector.h
Go to the documentation of this file.
1
/*
2
Copyright (c) 2013, Alex Teichman and Stephen Miller (Stanford University)
3
All rights reserved.
4
5
Redistribution and use in source and binary forms, with or without
6
modification, are permitted provided that the following conditions are met:
7
* Redistributions of source code must retain the above copyright
8
notice, this list of conditions and the following disclaimer.
9
* Redistributions in binary form must reproduce the above copyright
10
notice, this list of conditions and the following disclaimer in the
11
documentation and/or other materials provided with the distribution.
12
* Neither the name of the <organization> nor the
13
names of its contributors may be used to endorse or promote products
14
derived from this software without specific prior written permission.
15
16
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19
DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
20
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
27
RTAB-Map integration: Mathieu Labbe
28
*/
29
30
#ifndef FRAME_PROJECTOR_H
31
#define FRAME_PROJECTOR_H
32
33
#include <pcl/point_cloud.h>
34
#include <pcl/point_types.h>
35
#include <opencv2/core/core.hpp>
36
#include <
rtabmap/core/CameraModel.h
>
37
38
#define MAX_MULT 1.3
39
#define MIN_MULT 0.7
40
41
namespace
clams
42
{
43
47
class
ProjectivePoint
48
{
49
public
:
50
ProjectivePoint
() :
51
u_
(0),
52
v_
(0),
53
z_
(0.0
f
) {}
54
55
int
u_
;
56
int
v_
;
57
float
z_
;
// in meters
58
};
59
62
class
RTABMAP_CORE_EXPORT
FrameProjector
63
{
64
public
:
65
// For storing z values in meters. This is not Euclidean distance.
66
typedef
std::vector< std::vector< std::vector<double> > >
RangeIndex
;
67
68
FrameProjector
(
const
rtabmap::CameraModel
&
model
);
69
70
RangeIndex
cloudToRangeIndex(
const
pcl::PointCloud<pcl::PointXYZ>::Ptr & pcd)
const
;
74
cv::Mat estimateMapDepth(
75
const
pcl::PointCloud<pcl::PointXYZ>::Ptr & map,
76
const
rtabmap::Transform
& transform,
77
const
cv::Mat & measurement,
78
double
coneRadius = 0.02,
79
double
coneStdevThresh = 0.03)
const
;
80
81
pcl::PointXYZ
project
(
const
ProjectivePoint
& ppt)
const
;
82
ProjectivePoint
reproject(
const
pcl::PointXYZ& pt)
const
;
83
84
protected
:
85
bool
coneFit(
const
cv::Size& imageSize,
const
RangeIndex
& rindex,
86
int
uc,
int
vc,
double
radius,
double
measurement_depth,
87
double
* mean,
double
*
stdev
)
const
;
88
89
private
:
90
rtabmap::CameraModel
model_
;
91
};
92
93
}
// namespace clams
94
95
#endif // FRAME_PROJECTOR_H
clams::ProjectivePoint::u_
int u_
Definition:
frame_projector.h:55
rtabmap::CameraModel
Definition:
CameraModel.h:38
clams::FrameProjector::model_
rtabmap::CameraModel model_
Definition:
frame_projector.h:90
glm::project
GLM_FUNC_DECL detail::tvec3< T, P > project(detail::tvec3< T, P > const &obj, detail::tmat4x4< T, P > const &model, detail::tmat4x4< T, P > const &proj, detail::tvec4< U, P > const &viewport)
clams::FrameProjector::RangeIndex
std::vector< std::vector< std::vector< double > > > RangeIndex
Definition:
frame_projector.h:66
clams::ProjectivePoint::z_
float z_
Definition:
frame_projector.h:57
clams::ProjectivePoint::v_
int v_
Definition:
frame_projector.h:56
clams
Definition:
discrete_depth_distortion_model.h:41
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
eigen_extensions::stdev
double stdev(const Eigen::VectorXd &vec)
Definition:
eigen_extensions.h:22
clams::FrameProjector
Definition:
frame_projector.h:62
rtabmap::Transform
Definition:
Transform.h:41
CameraModel.h
clams::ProjectivePoint
Definition:
frame_projector.h:47
clams::ProjectivePoint::ProjectivePoint
ProjectivePoint()
Definition:
frame_projector.h:50
trace.model
model
Definition:
trace.py:4
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:10