Skip to content

Commit e3a9e4d

Browse files
committed
add plane prior
1 parent e7f8d71 commit e3a9e4d

File tree

5 files changed

+184
-2
lines changed

5 files changed

+184
-2
lines changed

.clang-format

+117
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,117 @@
1+
---
2+
Language: Cpp
3+
# BasedOnStyle: Google
4+
AccessModifierOffset: -2
5+
AlignAfterOpenBracket: Align
6+
AlignConsecutiveAssignments: false
7+
AlignConsecutiveDeclarations: false
8+
AlignEscapedNewlines: Left
9+
AlignOperands: true
10+
AlignTrailingComments: true
11+
AllowAllParametersOfDeclarationOnNextLine: true
12+
AllowShortBlocksOnASingleLine: false
13+
AllowShortCaseLabelsOnASingleLine: false
14+
AllowShortFunctionsOnASingleLine: Empty
15+
AllowShortIfStatementsOnASingleLine: true
16+
AllowShortLoopsOnASingleLine: true
17+
AlwaysBreakAfterDefinitionReturnType: None
18+
AlwaysBreakAfterReturnType: None
19+
AlwaysBreakBeforeMultilineStrings: true
20+
AlwaysBreakTemplateDeclarations: true
21+
BinPackArguments: true
22+
BinPackParameters: false
23+
BraceWrapping:
24+
AfterClass: false
25+
AfterControlStatement: false
26+
AfterEnum: false
27+
AfterFunction: false
28+
AfterNamespace: false
29+
AfterObjCDeclaration: false
30+
AfterStruct: false
31+
AfterUnion: false
32+
AfterExternBlock: false
33+
BeforeCatch: false
34+
BeforeElse: false
35+
IndentBraces: false
36+
SplitEmptyFunction: true
37+
SplitEmptyRecord: true
38+
SplitEmptyNamespace: true
39+
BreakBeforeBinaryOperators: None
40+
BreakBeforeBraces: Attach
41+
BreakBeforeInheritanceComma: false
42+
BreakBeforeTernaryOperators: true
43+
BreakConstructorInitializersBeforeComma: false
44+
BreakConstructorInitializers: BeforeColon
45+
BreakAfterJavaFieldAnnotations: false
46+
BreakStringLiterals: false
47+
ColumnLimit: 256
48+
CommentPragmas: '^ IWYU pragma:'
49+
CompactNamespaces: false
50+
ConstructorInitializerAllOnOneLineOrOnePerLine: true
51+
ConstructorInitializerIndentWidth: 4
52+
ContinuationIndentWidth: 4
53+
Cpp11BracedListStyle: true
54+
DerivePointerAlignment: true
55+
DisableFormat: false
56+
ExperimentalAutoDetectBinPacking: false
57+
FixNamespaceComments: true
58+
ForEachMacros:
59+
- foreach
60+
- Q_FOREACH
61+
- BOOST_FOREACH
62+
IncludeBlocks: Preserve
63+
IncludeCategories:
64+
- Regex: '^<ext/.*\.h>'
65+
Priority: 2
66+
- Regex: '^<.*\.h>'
67+
Priority: 1
68+
- Regex: '^<.*'
69+
Priority: 2
70+
- Regex: '.*'
71+
Priority: 3
72+
IncludeIsMainRegex: '([-_](test|unittest))?$'
73+
IndentCaseLabels: true
74+
IndentPPDirectives: None
75+
IndentWidth: 2
76+
IndentWrappedFunctionNames: false
77+
JavaScriptQuotes: Leave
78+
JavaScriptWrapImports: true
79+
KeepEmptyLinesAtTheStartOfBlocks: false
80+
MacroBlockBegin: ''
81+
MacroBlockEnd: ''
82+
MaxEmptyLinesToKeep: 1
83+
NamespaceIndentation: None
84+
ObjCBlockIndentWidth: 2
85+
ObjCSpaceAfterProperty: false
86+
ObjCSpaceBeforeProtocolList: false
87+
PenaltyBreakAssignment: 2
88+
PenaltyBreakBeforeFirstCallParameter: 1
89+
PenaltyBreakComment: 300
90+
PenaltyBreakFirstLessLess: 120
91+
PenaltyBreakString: 1000
92+
PenaltyExcessCharacter: 0
93+
PenaltyReturnTypeOnItsOwnLine: 200
94+
PointerAlignment: Left
95+
RawStringFormats:
96+
- Delimiter: pb
97+
Language: TextProto
98+
BasedOnStyle: google
99+
ReflowComments: true
100+
SortIncludes: false
101+
SortUsingDeclarations: false
102+
SpaceAfterCStyleCast: false
103+
SpaceAfterTemplateKeyword: false
104+
SpaceBeforeAssignmentOperators: true
105+
SpaceBeforeParens: Never
106+
SpaceInEmptyParentheses: false
107+
SpacesBeforeTrailingComments: 2
108+
SpacesInAngles: false
109+
SpacesInContainerLiterals: true
110+
SpacesInCStyleCastParentheses: false
111+
SpacesInParentheses: false
112+
SpacesInSquareBrackets: false
113+
Standard: Auto
114+
TabWidth: 8
115+
UseTab: Never
116+
...
117+

include/g2o/edge_plane_prior.hpp

+50
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
#ifndef EDGE_PLANE_PRIOR_HPP
2+
#define EDGE_PLANE_PRIOR_HPP
3+
4+
#include <Eigen/Dense>
5+
#include <g2o/core/base_unary_edge.h>
6+
#include <g2o/types/slam3d_addons/vertex_plane.h>
7+
8+
namespace g2o {
9+
class EdgePlanePriorNormal : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane> {
10+
public:
11+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
12+
EdgePlanePriorNormal() : g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexPlane>() {}
13+
14+
void computeError() override {
15+
const g2o::VertexPlane* v1 = static_cast<const g2o::VertexPlane*>(_vertices[0]);
16+
Eigen::Vector3d normal = v1->estimate().normal();
17+
18+
if(normal.dot(_measurement) < 0.0) {
19+
normal = -normal;
20+
}
21+
22+
_error = normal - _measurement;
23+
}
24+
25+
void setMeasurement(const Eigen::Vector3d& m) override {
26+
_measurement = m;
27+
}
28+
29+
virtual bool read(std::istream& is) override {
30+
Eigen::Vector3d v;
31+
is >> v(0) >> v(1) >> v(2);
32+
setMeasurement(v);
33+
for(int i = 0; i < information().rows(); ++i)
34+
for(int j = i; j < information().cols(); ++j) {
35+
is >> information()(i, j);
36+
if(i != j) information()(j, i) = information()(i, j);
37+
}
38+
return true;
39+
}
40+
virtual bool write(std::ostream& os) const override {
41+
Eigen::Vector3d v = _measurement;
42+
os << v(0) << " " << v(1) << " " << v(2) << " ";
43+
for(int i = 0; i < information().rows(); ++i)
44+
for(int j = i; j < information().cols(); ++j) os << " " << information()(i, j);
45+
return os.good();
46+
}
47+
};
48+
} // namespace g2o
49+
50+
#endif // EDGE_SE3_PRIORXY_HPP

include/hdl_graph_slam/graph_slam.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ namespace g2o {
2020
class EdgePlane;
2121
class EdgePlaneParallel;
2222
class EdgePlanePerpendicular;
23+
class EdgePlanePriorNormal;
2324
class RobustKernelFactory;
2425
}
2526

@@ -91,6 +92,8 @@ class GraphSLAM {
9192
* @param information_matrix
9293
* @return
9394
*/
95+
g2o::EdgePlanePriorNormal* add_plane_normal_prior_edge(g2o::VertexPlane* v, const Eigen::Vector3d& normal, const Eigen::MatrixXd& information_matrix);
96+
9497
g2o::EdgeSE3PriorXY* add_se3_prior_xy_edge(g2o::VertexSE3* v_se3, const Eigen::Vector2d& xy, const Eigen::MatrixXd& information_matrix);
9598

9699
g2o::EdgeSE3PriorXYZ* add_se3_prior_xyz_edge(g2o::VertexSE3* v_se3, const Eigen::Vector3d& xyz, const Eigen::MatrixXd& information_matrix);

src/g2o/robust_kernel_io.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -94,8 +94,8 @@ class KernelData {
9494
bool load_robust_kernels(const std::string& filename, g2o::SparseOptimizer* graph) {
9595
std::ifstream ifs(filename);
9696
if(!ifs) {
97-
std::cerr << "failed to open input stream!!" << std::endl;
98-
return false;
97+
std::cerr << "warning: failed to open input stream!!" << std::endl;
98+
return true;
9999
}
100100

101101
std::vector<KernelData> kernels;

src/hdl_graph_slam/graph_slam.cpp

+12
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <g2o/edge_se3_priorxyz.hpp>
1818
#include <g2o/edge_se3_priorvec.hpp>
1919
#include <g2o/edge_se3_priorquat.hpp>
20+
#include <g2o/edge_plane_prior.hpp>
2021
#include <g2o/edge_plane_parallel.hpp>
2122
#include <g2o/robust_kernel_io.hpp>
2223

@@ -30,6 +31,7 @@ namespace g2o {
3031
G2O_REGISTER_TYPE(EDGE_SE3_PRIORXYZ, EdgeSE3PriorXYZ)
3132
G2O_REGISTER_TYPE(EDGE_SE3_PRIORVEC, EdgeSE3PriorVec)
3233
G2O_REGISTER_TYPE(EDGE_SE3_PRIORQUAT, EdgeSE3PriorQuat)
34+
G2O_REGISTER_TYPE(EDGE_PLANE_PRIOR_NORMAL, EdgePlanePriorNormal)
3335
G2O_REGISTER_TYPE(EDGE_PLANE_PARALLEL, EdgePlaneParallel)
3436
G2O_REGISTER_TYPE(EDGE_PLANE_PAERPENDICULAR, EdgePlanePerpendicular)
3537
}
@@ -132,6 +134,16 @@ g2o::EdgeSE3PointXYZ* GraphSLAM::add_se3_point_xyz_edge(g2o::VertexSE3* v_se3, g
132134
return edge;
133135
}
134136

137+
g2o::EdgePlanePriorNormal* GraphSLAM::add_plane_normal_prior_edge(g2o::VertexPlane* v, const Eigen::Vector3d& normal, const Eigen::MatrixXd& information_matrix) {
138+
g2o::EdgePlanePriorNormal* edge(new g2o::EdgePlanePriorNormal());
139+
edge->setMeasurement(normal);
140+
edge->setInformation(information_matrix);
141+
edge->vertices()[0] = v;
142+
graph->addEdge(edge);
143+
144+
return edge;
145+
}
146+
135147
g2o::EdgeSE3PriorXY* GraphSLAM::add_se3_prior_xy_edge(g2o::VertexSE3* v_se3, const Eigen::Vector2d& xy, const Eigen::MatrixXd& information_matrix) {
136148
g2o::EdgeSE3PriorXY* edge(new g2o::EdgeSE3PriorXY());
137149
edge->setMeasurement(xy);

0 commit comments

Comments
 (0)