Skip to content

Commit

Permalink
Support latest g2o (#514)
Browse files Browse the repository at this point in the history
* Replace numbet_t with double

* Replace g2o::make_unique with stella_vslam::make_unique
  • Loading branch information
ymd-stella committed Jul 1, 2023
1 parent c129558 commit 655fbae
Show file tree
Hide file tree
Showing 9 changed files with 20 additions and 20 deletions.
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/global_bundle_adjuster.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ void optimize_impl(g2o::SparseOptimizer& optimizer,
// 2. Construct an optimizer

std::unique_ptr<g2o::BlockSolverBase> block_solver;
auto linear_solver = g2o::make_unique<g2o::LinearSolverCSparse<g2o::BlockSolver_6_3::PoseMatrixType>>();
block_solver = g2o::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto linear_solver = stella_vslam::make_unique<g2o::LinearSolverCSparse<g2o::BlockSolver_6_3::PoseMatrixType>>();
block_solver = stella_vslam::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto algorithm = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));

optimizer.setAlgorithm(algorithm);
Expand Down
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/graph_optimizer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ void graph_optimizer::optimize(const std::shared_ptr<data::keyframe>& loop_keyfr
std::unordered_map<unsigned int, unsigned int>& found_lm_to_ref_keyfrm_id) const {
// 1. Construct an optimizer

auto linear_solver = g2o::make_unique<g2o::LinearSolverCSparse<g2o::BlockSolver_7_3::PoseMatrixType>>();
auto block_solver = g2o::make_unique<g2o::BlockSolver_7_3>(std::move(linear_solver));
auto linear_solver = stella_vslam::make_unique<g2o::LinearSolverCSparse<g2o::BlockSolver_7_3::PoseMatrixType>>();
auto block_solver = stella_vslam::make_unique<g2o::BlockSolver_7_3>(std::move(linear_solver));
auto algorithm = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));

g2o::SparseOptimizer optimizer;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class mono_perspective_pose_opt_edge final : public g2o::BaseUnaryEdge<2, Vec2_t
Vec2_t cam_project(const Vec3_t& pos_c) const;

Vec3_t pos_w_;
number_t fx_, fy_, cx_, cy_;
double fx_, fy_, cx_, cy_;
};

inline mono_perspective_pose_opt_edge::mono_perspective_pose_opt_edge()
Expand Down Expand Up @@ -124,7 +124,7 @@ class stereo_perspective_pose_opt_edge : public g2o::BaseUnaryEdge<3, Vec3_t, sh
Vec3_t cam_project(const Vec3_t& pos_c) const;

Vec3_t pos_w_;
number_t fx_, fy_, cx_, cy_, focal_x_baseline_;
double fx_, fy_, cx_, cy_, focal_x_baseline_;
};

inline stereo_perspective_pose_opt_edge::stereo_perspective_pose_opt_edge()
Expand Down
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/internal/se3/shot_vertex.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class shot_vertex final : public g2o::BaseVertex<6, g2o::SE3Quat> {

void setToOriginImpl() override;

void oplusImpl(const number_t* update_) override;
void oplusImpl(const double* update_) override;
};

inline shot_vertex::shot_vertex()
Expand Down Expand Up @@ -52,7 +52,7 @@ inline void shot_vertex::setToOriginImpl() {
_estimate = g2o::SE3Quat();
}

inline void shot_vertex::oplusImpl(const number_t* update_) {
inline void shot_vertex::oplusImpl(const double* update_) {
Eigen::Map<const Vec6_t> update(update_);
setEstimate(g2o::SE3Quat::exp(update) * estimate());
}
Expand Down
6 changes: 3 additions & 3 deletions src/stella_vslam/optimize/internal/sim3/shot_vertex.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class shot_vertex final : public g2o::BaseVertex<7, g2o::Sim3> {

void setToOriginImpl() override;

void oplusImpl(const number_t* update_) override;
void oplusImpl(const double* update_) override;

bool fix_scale_;
};
Expand Down Expand Up @@ -53,8 +53,8 @@ inline void shot_vertex::setToOriginImpl() {
_estimate = g2o::Sim3();
}

inline void shot_vertex::oplusImpl(const number_t* update_) {
Eigen::Map<Vec7_t> update(const_cast<number_t*>(update_));
inline void shot_vertex::oplusImpl(const double* update_) {
Eigen::Map<Vec7_t> update(const_cast<double*>(update_));

if (fix_scale_) {
update(6) = 0;
Expand Down
6 changes: 3 additions & 3 deletions src/stella_vslam/optimize/internal/sim3/transform_vertex.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class transform_vertex final : public g2o::BaseVertex<7, g2o::Sim3> {

void setToOriginImpl() override;

void oplusImpl(const number_t* update_) override;
void oplusImpl(const double* update_) override;

bool fix_scale_;

Expand Down Expand Up @@ -58,8 +58,8 @@ inline void transform_vertex::setToOriginImpl() {
_estimate = g2o::Sim3();
}

inline void transform_vertex::oplusImpl(const number_t* update_) {
Eigen::Map<Vec7_t> update(const_cast<number_t*>(update_));
inline void transform_vertex::oplusImpl(const double* update_) {
Eigen::Map<Vec7_t> update(const_cast<double*>(update_));

if (fix_scale_) {
update(6) = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/local_bundle_adjuster_g2o.cc
Original file line number Diff line number Diff line change
Expand Up @@ -149,8 +149,8 @@ void local_bundle_adjuster_g2o::optimize(data::map_database* map_db,
// 2. Construct an optimizer

std::unique_ptr<g2o::BlockSolverBase> block_solver;
auto linear_solver = g2o::make_unique<g2o::LinearSolverEigen<g2o::BlockSolver_6_3::PoseMatrixType>>();
block_solver = g2o::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto linear_solver = stella_vslam::make_unique<g2o::LinearSolverEigen<g2o::BlockSolver_6_3::PoseMatrixType>>();
block_solver = stella_vslam::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto algorithm = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));

g2o::SparseOptimizer optimizer;
Expand Down
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/pose_optimizer_g2o.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ unsigned int pose_optimizer_g2o::optimize(const Mat44_t& cam_pose_cw, const data
std::vector<bool>& outlier_flags) const {
// 1. Construct an optimizer

auto linear_solver = g2o::make_unique<g2o::LinearSolverEigen<g2o::BlockSolver_6_3::PoseMatrixType>>();
auto block_solver = g2o::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto linear_solver = stella_vslam::make_unique<g2o::LinearSolverEigen<g2o::BlockSolver_6_3::PoseMatrixType>>();
auto block_solver = stella_vslam::make_unique<g2o::BlockSolver_6_3>(std::move(linear_solver));
auto algorithm = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));

g2o::SparseOptimizer optimizer;
Expand Down
4 changes: 2 additions & 2 deletions src/stella_vslam/optimize/transform_optimizer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ unsigned int transform_optimizer::optimize(const std::shared_ptr<data::keyframe>

// 1. Construct an optimizer

auto linear_solver = g2o::make_unique<g2o::LinearSolverEigen<g2o::BlockSolverX::PoseMatrixType>>();
auto block_solver = g2o::make_unique<g2o::BlockSolverX>(std::move(linear_solver));
auto linear_solver = stella_vslam::make_unique<g2o::LinearSolverEigen<g2o::BlockSolverX::PoseMatrixType>>();
auto block_solver = stella_vslam::make_unique<g2o::BlockSolverX>(std::move(linear_solver));
auto algorithm = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));

g2o::SparseOptimizer optimizer;
Expand Down

0 comments on commit 655fbae

Please sign in to comment.