Skip to content

Commit

Permalink
Improve naming of localization and triangulation utilities (#97)
Browse files Browse the repository at this point in the history
  • Loading branch information
B1ueber2y authored Nov 21, 2024
1 parent 1496673 commit f988271
Show file tree
Hide file tree
Showing 33 changed files with 153 additions and 142 deletions.
2 changes: 1 addition & 1 deletion limap/_limap/bindings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void bind_features(py::module &);
namespace limap {

PYBIND11_MODULE(_limap, m) {
m.doc() = "Multi-view Line Triangulation and Refinement";
m.doc() = "A toolbox for mapping and localization with line features";
#ifdef VERSION_INFO
m.attr("__version__") = py::str(VERSION_INFO);
#else
Expand Down
4 changes: 2 additions & 2 deletions limap/estimators/absolute_pose/hybrid_pose_estimator.cc
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
#include "estimators/absolute_pose/hybrid_pose_estimator.h"
#include "estimators/absolute_pose/pl_absolute_pose_hybrid_ransac.h"
#include "estimators/absolute_pose/pl_absolute_pose_ransac.h"
#include "optimize/line_localization/cost_functions.h"
#include "optimize/hybrid_localization/cost_functions.h"

namespace limap {

namespace estimators {

namespace absolute_pose {

namespace lineloc = optimize::line_localization;
namespace hybridloc = optimize::hybrid_localization;

std::pair<CameraPose, ransac_lib::HybridRansacStatistics>
EstimateAbsolutePose_PointLine_Hybrid(
Expand Down
4 changes: 2 additions & 2 deletions limap/estimators/absolute_pose/hybrid_pose_estimator.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@
#include "base/linetrack.h"
#include "estimators/absolute_pose/joint_pose_estimator.h"
#include "estimators/extended_hybrid_ransac.h"
#include "optimize/line_localization/lineloc.h"
#include "optimize/hybrid_localization/hybrid_localization.h"
#include "util/types.h"

#include <RansacLib/ransac.h>

namespace limap {

using namespace optimize::line_localization;
using namespace optimize::hybrid_localization;

namespace estimators {

Expand Down
14 changes: 7 additions & 7 deletions limap/estimators/absolute_pose/joint_pose_estimator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "ceresbase/line_projection.h"
#include "ceresbase/point_projection.h"
#include "estimators/absolute_pose/pl_absolute_pose_ransac.h"
#include "optimize/line_localization/cost_functions.h"
#include "optimize/hybrid_localization/cost_functions.h"

#include <PoseLib/camera_pose.h>
#include <PoseLib/solvers/p1p2ll.h>
Expand All @@ -18,7 +18,7 @@ namespace estimators {

namespace absolute_pose {

namespace lineloc = optimize::line_localization;
namespace hybridloc = optimize::hybrid_localization;

std::pair<CameraPose, ransac_lib::RansacStatistics>
EstimateAbsolutePose_PointLine(const std::vector<Line3d> &l3ds,
Expand Down Expand Up @@ -60,7 +60,7 @@ JointPoseEstimator::JointPoseEstimator(
const std::vector<Line3d> &l3ds, const std::vector<int> &l3d_ids,
const std::vector<Line2d> &l2ds, const std::vector<V3D> &p3ds,
const std::vector<V2D> &p2ds, const Camera &cam,
const lineloc::LineLocConfig &cfg, const double cheirality_min_depth,
const hybridloc::LineLocConfig &cfg, const double cheirality_min_depth,
const double cheirality_overlap_pixels)
: loc_config_(cfg), cheirality_min_depth_(cheirality_min_depth),
cheirality_overlap_pixels_(cheirality_overlap_pixels) {
Expand Down Expand Up @@ -182,8 +182,8 @@ double JointPoseEstimator::EvaluateModelOnPoint(const CameraPose &pose,
bool cheirality = cheirality_test_point(p3ds_->at(i), pose);
if (!cheirality)
return std::numeric_limits<double>::max();
lineloc::ReprojectionPointFunctor(p3ds_->at(i), p2ds_->at(i),
loc_config_.points_3d_dist)(
hybridloc::ReprojectionPointFunctor(p3ds_->at(i), p2ds_->at(i),
loc_config_.points_3d_dist)(
cam_.Params().data(), pose.qvec.data(), pose.tvec.data(), res);
return V2D(res[0], res[1]).squaredNorm();
} else {
Expand All @@ -193,8 +193,8 @@ double JointPoseEstimator::EvaluateModelOnPoint(const CameraPose &pose,
bool cheirality = cheirality_test_line(l2ds_->at(i), l3d, pose);
if (!cheirality)
return std::numeric_limits<double>::max();
lineloc::ReprojectionLineFunctor(loc_config_.cost_function, ENoneWeight,
l3d, l2ds_->at(i))(
hybridloc::ReprojectionLineFunctor(loc_config_.cost_function, ENoneWeight,
l3d, l2ds_->at(i))(
cam_.Params().data(), pose.qvec.data(), pose.tvec.data(), res);
if (getResidualNum(loc_config_.cost_function) == 2) {
return V2D(res[0], res[1]).squaredNorm();
Expand Down
4 changes: 2 additions & 2 deletions limap/estimators/absolute_pose/joint_pose_estimator.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,14 +4,14 @@
#include "_limap/helpers.h"
#include "base/camera.h"
#include "base/linetrack.h"
#include "optimize/line_localization/lineloc.h"
#include "optimize/hybrid_localization/hybrid_localization.h"
#include "util/types.h"

#include <RansacLib/ransac.h>

namespace limap {

using namespace optimize::line_localization;
using namespace optimize::hybrid_localization;

namespace estimators {

Expand Down
2 changes: 1 addition & 1 deletion limap/optimize/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ set(FOLDER_NAME "optimize")
add_subdirectory(line_refinement)
add_subdirectory(hybrid_bundle_adjustment)
add_subdirectory(global_pl_association)
add_subdirectory(line_localization)
add_subdirectory(hybrid_localization)

LIMAP_ADD_SOURCES(
bindings.cc
Expand Down
2 changes: 1 addition & 1 deletion limap/optimize/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
solve_line_bundle_adjustment,
solve_point_bundle_adjustment,
)
from .line_localization import (
from .hybrid_localization import (
get_lineloc_cost_func,
get_lineloc_weight_func,
solve_jointloc,
Expand Down
6 changes: 3 additions & 3 deletions limap/optimize/bindings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

#include "optimize/global_pl_association/bindings.cc"
#include "optimize/hybrid_bundle_adjustment/bindings.cc"
#include "optimize/line_localization/bindings.cc"
#include "optimize/hybrid_localization/bindings.cc"
#include "optimize/line_refinement/bindings.cc"

namespace py = pybind11;
Expand All @@ -19,13 +19,13 @@ namespace limap {
void bind_line_refinement(py::module &m);
void bind_hybrid_bundle_adjustment(py::module &m);
void bind_global_pl_association(py::module &m);
void bind_line_localization(py::module &m);
void bind_hybrid_localization(py::module &m);

void bind_optimize(py::module &m) {
bind_line_refinement(m);
bind_hybrid_bundle_adjustment(m);
bind_global_pl_association(m);
bind_line_localization(m);
bind_hybrid_localization(m);
}

} // namespace limap
9 changes: 9 additions & 0 deletions limap/optimize/hybrid_localization/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
set(FOLDER_NAME "hybrid_localization")

LIMAP_ADD_SOURCES(
bindings.cc
cost_functions.h
hybrid_localization.h hybrid_localization.cc
hybrid_localization_config.h
)

Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,15 @@
#include <Eigen/Core>
#include <vector>

#include "optimize/line_localization/lineloc.h"
#include "optimize/line_localization/lineloc_config.h"
#include "optimize/hybrid_localization/hybrid_localization.h"
#include "optimize/hybrid_localization/hybrid_localization_config.h"

namespace py = pybind11;

namespace limap {

void bind_lineloc_engine(py::module &m) {
using namespace optimize::line_localization;
using namespace optimize::hybrid_localization;

using LocEngine = LineLocEngine;
using JointEngine = JointLocEngine;
Expand Down Expand Up @@ -63,8 +63,8 @@ void bind_lineloc_engine(py::module &m) {
.def("GetFinalCost", &JointEngine::GetFinalCost);
}

void bind_line_localization(py::module &m) {
using namespace optimize::line_localization;
void bind_hybrid_localization(py::module &m) {
using namespace optimize::hybrid_localization;

py::enum_<LineLocCostFunction>(m, "LineLocCostFunction")
.value("E2DMidpointDist2", LineLocCostFunction::E2DMidpointDist2)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef LIMAP_OPTIMIZE_LINE_LOCALIZATION_COST_FUNCTIONS_H_
#define LIMAP_OPTIMIZE_LINE_LOCALIZATION_COST_FUNCTIONS_H_
#ifndef LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_COST_FUNCTIONS_H_
#define LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_COST_FUNCTIONS_H_

#include "_limap/helpers.h"
#include <pybind11/numpy.h>
Expand All @@ -14,15 +14,15 @@
#include "ceresbase/point_projection.h"
#include <ceres/ceres.h>

#include "optimize/line_localization/lineloc_config.h"
#include "optimize/hybrid_localization/hybrid_localization_config.h"

namespace py = pybind11;

namespace limap {

namespace optimize {

namespace line_localization {
namespace hybrid_localization {

////////////////////////////////////////////////////////////
// 2D Weights and Line Dists
Expand Down Expand Up @@ -347,7 +347,7 @@ struct ReprojectionPointFunctor {
bool use_3d_dist_;
};

} // namespace line_localization
} // namespace hybrid_localization

} // namespace optimize

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "optimize/line_localization/lineloc.h"
#include "optimize/hybrid_localization/hybrid_localization.h"
#include "ceresbase/parameterization.h"
#include "optimize/line_localization/cost_functions.h"
#include "optimize/hybrid_localization/cost_functions.h"

#include <colmap/optim/bundle_adjustment.h>
#include <colmap/util/logging.h>
Expand All @@ -11,7 +11,7 @@ namespace limap {

namespace optimize {

namespace line_localization {
namespace hybrid_localization {

void LineLocEngine::ParameterizeCamera() {
double *kvec_data = cam.Params().data();
Expand Down Expand Up @@ -134,7 +134,7 @@ void JointLocEngine::AddResiduals() {
}
}

} // namespace line_localization
} // namespace hybrid_localization

} // namespace optimize

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef LIMAP_OPTIMIZE_LINE_LOCALIZATION_LINELOC_H_
#define LIMAP_OPTIMIZE_LINE_LOCALIZATION_LINELOC_H_
#ifndef LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_HYBRID_LOCALIZATION_H_
#define LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_HYBRID_LOCALIZATION_H_

#include "_limap/helpers.h"
#include <pybind11/numpy.h>
Expand All @@ -8,7 +8,7 @@
#include "util/types.h"

#include "base/linebase.h"
#include "optimize/line_localization/lineloc_config.h"
#include "optimize/hybrid_localization/hybrid_localization_config.h"
#include <ceres/ceres.h>

namespace py = pybind11;
Expand All @@ -17,7 +17,7 @@ namespace limap {

namespace optimize {

namespace line_localization {
namespace hybrid_localization {

class LineLocEngine {
protected:
Expand Down Expand Up @@ -126,7 +126,7 @@ class JointLocEngine : public LineLocEngine {
}
};

} // namespace line_localization
} // namespace hybrid_localization

} // namespace optimize

Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef LIMAP_OPTIMIZE_LINE_LOCALIZATION_LINELOC_CONFIG_H_
#define LIMAP_OPTIMIZE_LINE_LOCALIZATION_LINELOC_CONFIG_H_
#ifndef LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_HYBRID_LOCALIZATION_CONFIG_H_
#define LIMAP_OPTIMIZE_HYBRID_LOCALIZATION_HYBRID_LOCALIZATION_CONFIG_H_

#include "_limap/helpers.h"
#include <pybind11/numpy.h>
Expand All @@ -14,7 +14,7 @@ namespace limap {

namespace optimize {

namespace line_localization {
namespace hybrid_localization {

enum LineLocCostFunction {
E2DMidpointDist2,
Expand Down Expand Up @@ -78,7 +78,7 @@ class LineLocConfig {
std::shared_ptr<ceres::LossFunction> loss_function;
};

} // namespace line_localization
} // namespace hybrid_localization

} // namespace optimize

Expand Down
File renamed without changes.
9 changes: 0 additions & 9 deletions limap/optimize/line_localization/CMakeLists.txt

This file was deleted.

12 changes: 6 additions & 6 deletions limap/runners/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,17 @@
undistort_images,
)
from .functions_structures import compute_2d_bipartites_from_colmap
from .hybrid_localization import (
get_hloc_keypoints,
get_hloc_keypoints_from_log,
hybrid_localization,
)
from .line_fitnmerge import (
fit_3d_segs,
fit_3d_segs_with_points3d,
line_fitnmerge,
line_fitting_with_points3d,
)
from .line_localization import (
get_hloc_keypoints,
get_hloc_keypoints_from_log,
line_localization,
)
from .line_triangulation import line_triangulation

__all__ = [
Expand All @@ -34,6 +34,6 @@
"line_fitting_with_points3d",
"get_hloc_keypoints",
"get_hloc_keypoints_from_log",
"line_localization",
"hybrid_localization",
"line_triangulation",
]
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import limap.line2d
import limap.runners as runners
import limap.util.io as limapio
from limap.optimize.line_localization.functions import (
from limap.optimize.hybrid_localization.functions import (
filter_line_2to2_epipolarIoU,
get_reprojection_dist_func,
match_line_2to2_epipolarIoU,
Expand Down Expand Up @@ -91,7 +91,7 @@ def get_hloc_keypoints_from_log(
return p2ds, p3ds, inliers


def line_localization(
def hybrid_localization(
cfg,
imagecols_db,
imagecols_query,
Expand Down
Loading

0 comments on commit f988271

Please sign in to comment.