g2o
Loading...
Searching...
No Matches
g2o
types
slam3d
edge_se3_pointxyz_depth.h
Go to the documentation of this file.
1
// g2o - General Graph Optimization
2
// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
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
7
// met:
8
//
9
// * Redistributions of source code must retain the above copyright notice,
10
// this list of conditions and the following disclaimer.
11
// * Redistributions in binary form must reproduce the above copyright
12
// notice, this list of conditions and the following disclaimer in the
13
// documentation and/or other materials provided with the distribution.
14
//
15
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16
// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17
// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18
// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19
// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21
// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22
// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23
// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24
// 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
#ifndef G2O_EDGE_PROJECT_DEPTH_H_
28
#define G2O_EDGE_PROJECT_DEPTH_H_
29
30
#include "
g2o/core/base_binary_edge.h
"
31
#include "
g2o_types_slam3d_api.h
"
32
#include "
parameter_camera.h
"
33
#include "
vertex_pointxyz.h
"
34
#include "
vertex_se3.h
"
35
36
namespace
g2o
{
37
42
class
G2O_TYPES_SLAM3D_API
EdgeSE3PointXYZDepth
43
:
public
BaseBinaryEdge
<3, Vector3, VertexSE3, VertexPointXYZ> {
44
public
:
45
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46
EdgeSE3PointXYZDepth
();
47
virtual
bool
read(std::istream& is);
48
virtual
bool
write(std::ostream& os)
const
;
49
50
// return the error estimate as a 3-vector
51
void
computeError();
52
// jacobian
53
virtual
void
linearizeOplus();
54
55
virtual
bool
setMeasurementData
(
const
double
* d) {
56
Eigen::Map<const Vector3> v(d);
57
_measurement = v;
58
return
true
;
59
}
60
61
virtual
bool
getMeasurementData
(
double
* d)
const
{
62
Eigen::Map<Vector3> v(d);
63
v = _measurement;
64
return
true
;
65
}
66
67
virtual
int
measurementDimension
()
const
{
return
3; }
68
69
virtual
bool
setMeasurementFromState();
70
71
virtual
double
initialEstimatePossible
(
72
const
OptimizableGraph::VertexSet
& from,
OptimizableGraph::Vertex
* to) {
73
(void)to;
74
return
(from.count(_vertices[0]) == 1 ? 1.0 : -1.0);
75
}
76
77
virtual
void
initialEstimate(
const
OptimizableGraph::VertexSet
& from,
78
OptimizableGraph::Vertex
* to);
79
80
private
:
81
Eigen::Matrix<double, 3, 9, Eigen::ColMajor>
J
;
// jacobian before projection
82
83
virtual
bool
resolveCaches();
84
ParameterCamera
*
params
;
85
CacheCamera
*
cache
;
86
};
87
88
}
// namespace g2o
89
#endif
base_binary_edge.h
g2o::BaseBinaryEdge
Definition
base_binary_edge.h:37
g2o::CacheCamera
Definition
parameter_camera.h:58
g2o::EdgeSE3PointXYZDepth
Definition
edge_se3_pointxyz_depth.h:43
g2o::EdgeSE3PointXYZDepth::J
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
Definition
edge_se3_pointxyz_depth.h:81
g2o::EdgeSE3PointXYZDepth::params
ParameterCamera * params
Definition
edge_se3_pointxyz_depth.h:84
g2o::EdgeSE3PointXYZDepth::setMeasurementData
virtual bool setMeasurementData(const double *d)
Definition
edge_se3_pointxyz_depth.h:55
g2o::EdgeSE3PointXYZDepth::initialEstimatePossible
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Definition
edge_se3_pointxyz_depth.h:71
g2o::EdgeSE3PointXYZDepth::getMeasurementData
virtual bool getMeasurementData(double *d) const
Definition
edge_se3_pointxyz_depth.h:61
g2o::EdgeSE3PointXYZDepth::measurementDimension
virtual int measurementDimension() const
Definition
edge_se3_pointxyz_depth.h:67
g2o::EdgeSE3PointXYZDepth::cache
CacheCamera * cache
Definition
edge_se3_pointxyz_depth.h:85
g2o::HyperGraph::VertexSet
std::set< Vertex * > VertexSet
Definition
hyper_graph.h:142
g2o::OptimizableGraph::Vertex
A general case Vertex for optimization.
Definition
optimizable_graph.h:108
g2o::ParameterCamera
parameters for a camera
Definition
parameter_camera.h:38
g2o_types_slam3d_api.h
G2O_TYPES_SLAM3D_API
#define G2O_TYPES_SLAM3D_API
Definition
g2o_types_slam3d_api.h:55
g2o
Definition
dl_wrapper.cpp:55
parameter_camera.h
vertex_pointxyz.h
vertex_se3.h
Generated on Tue Nov 11 2025 05:18:45 for g2o by
1.9.8