g2o原生位姿图#
Copy
#include<iostream>
#include<fstream>
#include<string>
#include <g2o/types/slam3d/types_slam3d.h>
#include<g2o/core/block_solver.h>
#include<g2o/core/optimization_algorithm_levenberg.h>
#include<g2o/solvers/eigen/linear_solver_eigen.h>
using namespace std;
int main(int argc,char **argv){
if (argc != 2) {
cout << "Usage: pose_graph_g2o_SE3 sphere.g2o" << endl;
return 1;
}
ifstream fin(argv[1]);
if (!fin) {
cout << "file " << argv[1] << " does not exist." << endl;
return 1;
}
typedef g2o::BlockSolver<g2o::BlockSolverTraits<6, 6>> BlockSolverType;
typedef g2o::LinearSolverEigen<BlockSolverType::PoseMatrixType>LinearSolverType;
auto solver=new g2o::OptimizationAlgorithmLevenberg(g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm(solver);
optimizer.setVerbose(true);
int vertexCnt=0,edgeCnt=0;
while(!fin.eof()){
string name;
fin>>name;
if(name=="VERTEX_SE3:QUAT"){
g2o::VertexSE3*v=new g2o::VertexSE3();
int index=0;
fin>>index;
v->setId(index);
v->read(fin);
optimizer.addVertex(v);
vertexCnt++;
if(index==0)
v->setFixed(true);
}else if(name=="EDGE_SE3:QUAT"){
g2o::EdgeSE3 *e=new g2o::EdgeSE3();
int idx1,idx2;
fin >> idx1 >> idx2;
e->setId(edgeCnt++);
e->setVertex(0, optimizer.vertices()[idx1]);
e->setVertex(1, optimizer.vertices()[idx2]);
e->read(fin);
optimizer.addEdge(e);
}
if (!fin.good()) break;
}
cout << "read total " << vertexCnt << " vertices, " << edgeCnt << " edges." << endl;
cout << "optimizing ..." << endl;
optimizer.initializeOptimization();
optimizer.optimize(30);
cout << "saving optimization results ..." << endl;
optimizer.save("result.g2o");
return 0;
}
李代数上的位姿图优化#
Copy
#include<iostream>
#include<fstream>
#include<string>
#include<Eigen/Core>
#include<g2o/core/base_vertex.h>
#include<g2o/core/base_binary_edge.h>
#include<g2o/core/block_solver.h>
#include<g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/eigen/linear_solver_eigen.h>
#include<sophus/se3.hpp>
using namespace std;
using namespace Eigen;
using Sophus::SE3d;
using Sophus::SO3d;
typedef Matrix<double,6,6> Matrix6d;
Matrix6d JRInv(const SE3d &e){
Matrix6d J;
J.block(0,0,3,3)=SO3d::hat(e.so3().log());
J.block(0,3,3,3)=SO3d::hat(e.translation());
J.block(3,0,3,3)=Matrix3d::Zero(3,3);
J.block(3,3,3,3)=SO3d::hat(e.so3().log());
J=Matrix6d::Identity();
return J;
}
typedef Matrix<double,6,1> Vector6d;
class VertexSE3LieAlgebra:public g2o::BaseVertex<6,SE3d>{
public :
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual bool read(istream &is) override{
double data[7];
for(int i=0;i<7;i++)
is>>data[i];
setEstimate(
SE3d(Quaterniond(data[6],data[3],data[4],data[5]),Vector3d(data[0],data[1],data[2])
));
}
virtual bool write(ostream &os)const override{
os<<id()<<" ";
Quaterniond q=_estimate.unit_quaternion();
os<<_estimate.translation().transpose()<<" ";
os<<q.coeffs()[0]<<" "<<q.coeffs()[1]<<" "<<q.coeffs()[2]<<" "<<q.coeffs()[3]<<endl;
return true;
}
virtual void setToOriginImpl()override{
_estimate=SE3d();
}
virtual void oplusImpl(const double *update)override{
Vector6d upd;
upd<<update[0],update[1],update[2],update[3],update[4],update[5];
_estimate=SE3d::exp(upd)*_estimate;
}
};
class EdgeSE3LieAlgebra:public g2o::BaseBinaryEdge<6,SE3d,VertexSE3LieAlgebra,VertexSE3LieAlgebra>{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual bool read(istream &is)override{
double data[7];
for(int i=0;i<7;i++)
is>>data[i];
Quaterniond q(data[6],data[3],data[4],data[5]);
q.normalize();
setMeasurement(SE3d(q,Vector3d(data[0],data[1],data[2])));
for(int i=0;i<information().rows()&&is.good();i++)
for(int j=i;j<information().cols()&&is.good();j++){
is>>information()(i,j);
if(i!=j)
information()(j,i)=information()(i,j);
}
return true;
}
virtual bool write(ostream &os)const override{
VertexSE3LieAlgebra *v1=static_cast<VertexSE3LieAlgebra *>(_vertices[0]);
VertexSE3LieAlgebra *v2=static_cast<VertexSE3LieAlgebra *>(_vertices[1]);
os<<v1->id()<<" "<<v2->id()<<" ";
SE3d m=_measurement;
Eigen::Quaterniond q=m.unit_quaternion();
os<<m.translation().transpose()<<" ";
os << q.coeffs()[0] << " " << q.coeffs()[1] << " " << q.coeffs()[2] << " " << q.coeffs()[3] << " ";
for (int i = 0; i < information().rows(); i++)
for (int j = i; j < information().cols(); j++) {
os << information()(i, j) << " ";
}
os << endl;
return true;
}
virtual void computeError()override{
SE3d v1=(static_cast<VertexSE3LieAlgebra *>(_vertices[0]))->estimate();
SE3d v2=(static_cast<VertexSE3LieAlgebra*>(_vertices[1]))->estimate();
_error=(_measurement.inverse()*v1.inverse()*v2).log();
}
virtual void linearizeOplus() override{
SE3d v1=(static_cast<VertexSE3LieAlgebra*>(_vertices[0]))->estimate();
SE3d v2=(static_cast<VertexSE3LieAlgebra*>(_vertices[1]))->estimate();
Matrix6d J=JRInv(SE3d::exp(_error));
_jacobianOplusXi=-J*v2.inverse().Adj();
_jacobianOplusXj=J*v2.inverse().Adj();
}
};
int main(int argc, char **argv) {
if (argc != 2) {
cout << "Usage: pose_graph_g2o_SE3_lie sphere.g2o" << endl;
return 1;
}
ifstream fin(argv[1]);
if (!fin) {
cout << "file " << argv[1] << " does not exist." << endl;
return 1;
}
typedef g2o::BlockSolver<g2o::BlockSolverTraits<6, 6>> BlockSolverType;
typedef g2o::LinearSolverEigen<BlockSolverType::PoseMatrixType> LinearSolverType;
auto solver = new g2o::OptimizationAlgorithmLevenberg(
g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm(solver);
optimizer.setVerbose(true);
int vertexCnt = 0, edgeCnt = 0;
vector<VertexSE3LieAlgebra *> vectices;
vector<EdgeSE3LieAlgebra *> edges;
while (!fin.eof()) {
string name;
fin >> name;
if (name == "VERTEX_SE3:QUAT") {
VertexSE3LieAlgebra *v = new VertexSE3LieAlgebra();
int index = 0;
fin >> index;
v->setId(index);
v->read(fin);
optimizer.addVertex(v);
vertexCnt++;
vectices.push_back(v);
if (index == 0)
v->setFixed(true);
} else if (name == "EDGE_SE3:QUAT") {
EdgeSE3LieAlgebra *e = new EdgeSE3LieAlgebra();
int idx1, idx2;
fin >> idx1 >> idx2;
e->setId(edgeCnt++);
e->setVertex(0, optimizer.vertices()[idx1]);
e->setVertex(1, optimizer.vertices()[idx2]);
e->read(fin);
optimizer.addEdge(e);
edges.push_back(e);
}
if (!fin.good()) break;
}
cout << "read total " << vertexCnt << " vertices, " << edgeCnt << " edges." << endl;
cout << "optimizing ..." << endl;
optimizer.initializeOptimization();
optimizer.optimize(30);
cout << "saving optimization results ..." << endl;
ofstream fout("result_lie.g2o");
for (VertexSE3LieAlgebra *v:vectices) {
fout << "VERTEX_SE3:QUAT ";
v->write(fout);
}
for (EdgeSE3LieAlgebra *e:edges) {
fout << "EDGE_SE3:QUAT ";
e->write(fout);
}
fout.close();
return 0;
}
CMakeLists.txt#
Copy
cmake_minimum_required(VERSION 2.8)
project(pose_graph)
set(CMAKE_BUILD_TYPE "Release")
list(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
list(APPEND CMAKE_MODULE_PATH /home/xxx/MyLibs/g2o-master/cmake_modules)
set(G2O_ROOT /usr/local/include/g2o)
set(G2O_LIBS /usr/local/include/g2o)
# Eigen
include_directories("/usr/include/eigen3")
# sophus
find_package(Sophus REQUIRED)
include_directories(${Sophus_INCLUDE_DIRS})
# g2o
find_package(G2O REQUIRED)
include_directories(${G2O_INCLUDE_DIRS})
add_executable(pose_graph_g2o_SE3 pose_graph_g2o_SE3.cpp)
target_link_libraries(pose_graph_g2o_SE3
g2o_core g2o_stuff g2o_types_slam3d ${CHOLMOD_LIBRARIES}
)
add_executable(pose_graph_g2o_lie pose_graph_g2o_lie_algebra.cpp)
target_link_libraries(pose_graph_g2o_lie
g2o_core g2o_stuff
${CHOLMOD_LIBRARIES}
${Sophus_LIBRARIES} fmt
)
【推荐】国内首个AI IDE,深度理解中文开发场景,立即下载体验Trae
【推荐】编程新体验,更懂你的AI,立即体验豆包MarsCode编程助手
【推荐】抖音旗下AI助手豆包,你的智能百科全书,全免费不限次数
【推荐】轻量又高性能的 SSH 工具 IShell:AI 加持,快人一步
· 无需6万激活码!GitHub神秘组织3小时极速复刻Manus,手把手教你使用OpenManus搭建本
· Manus爆火,是硬核还是营销?
· 终于写完轮子一部分:tcp代理 了,记录一下
· 别再用vector<bool>了!Google高级工程师:这可能是STL最大的设计失误
· 单元测试从入门到精通
2021-10-11 GAMES101 Rasteriztion