Skip to content

Commit 97ad31c

Browse files
committed
Update ceres to 2.2.0
1 parent 946ad26 commit 97ad31c

8 files changed

+74
-51
lines changed

Makefile

+5-5
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
SHELL:=/bin/bash
2-
PREFIX=/usr/local
2+
PREFIX=/opt/yac
33
BUILD_DIR=build
44
NUM_CPU=2
55

@@ -29,16 +29,16 @@ deps: ## Install dependencies
2929
@echo "[Installing Dependencies]"
3030
@make -s -C deps
3131

32-
lib_debug: ${BUILD_DIR} ${PREFIX} ## Build libyac in debug mode
32+
lib_debug: ${BUILD_DIR} ## Build libyac in debug mode
3333
$(call compile_yac,Debug)
3434

35-
lib_relwithdeb: ${BUILD_DIR} ${PREFIX} ## Build libyac in release with debug info
35+
lib_relwithdeb: ${BUILD_DIR} ## Build libyac in release with debug info
3636
$(call compile_yac,RelWithDebInfo)
3737

38-
lib: ${BUILD_DIR} ${PREFIX} ## Build libyac in release mode
38+
lib: ${BUILD_DIR} ## Build libyac in release mode
3939
$(call compile_yac,Release)
4040

41-
install:
41+
install: ${PREFIX}
4242
cd ${BUILD_DIR} && make install
4343

4444
download_test_data: ## Download test data

deps/scripts/install_ceres.bash

+24-23
Original file line numberDiff line numberDiff line change
@@ -5,32 +5,33 @@ source "$BASEDIR/config.bash"
55

66
echo "installing ceres-solver ..."
77

8-
apt_install libunwind-dev
9-
apt_install libgflags-dev
10-
apt_install libgflags-doc
11-
apt_install libgoogle-glog-dev
12-
apt_install libceres-dev
13-
apt_install libceres2
8+
# apt_install libunwind-dev
9+
# apt_install libgflags-dev
10+
# apt_install libgflags-doc
11+
# apt_install libgoogle-glog-dev
12+
# apt_install libceres-dev
13+
# apt_install libceres2
1414

1515
# Dependencies
1616
# apt_install libtbb2-dev
1717

18-
# # Clone
19-
# if [ ! -d $INSTALL_PREFIX/src/ceres-solver ]; then
20-
# cd $INSTALL_PREFIX/src
21-
# git clone --quiet https://github.com/ceres-solver/ceres-solver
22-
# cd ..
23-
# fi
18+
# Clone
19+
if [ ! -d $INSTALL_PREFIX/src/ceres-solver ]; then
20+
cd $INSTALL_PREFIX/src
21+
git clone --quiet https://github.com/ceres-solver/ceres-solver
22+
cd ..
23+
fi
2424

25-
# # Build
26-
# cd $INSTALL_PREFIX/src/ceres-solver
27-
# git checkout ${VERSION} --quiet
25+
# Build
26+
cd $INSTALL_PREFIX/src/ceres-solver
27+
git checkout ${VERSION} --quiet
2828

29-
# mkdir -p build
30-
# cd build
31-
# cmake .. \
32-
# -DCMAKE_BUILD_TYPE=$BUILD_TYPE \
33-
# -DCMAKE_INSTALL_PREFIX=$INSTALL_PREFIX \
34-
# -DCMAKE_PREFIX_PATH=$INSTALL_PREFIX
35-
# make -j4
36-
# make install
29+
mkdir -p build
30+
cd build
31+
cmake .. \
32+
-DCMAKE_BUILD_TYPE=$BUILD_TYPE \
33+
-DCMAKE_INSTALL_PREFIX=$INSTALL_PREFIX \
34+
-DCMAKE_PREFIX_PATH=$INSTALL_PREFIX \
35+
-DBUILD_SHARED_LIBS=ON
36+
make -j4
37+
make install

yac/CMakeLists.txt

+4-6
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,4 @@
1-
CMAKE_MINIMUM_REQUIRED(VERSION 2.8.3)
2-
IF (POLICY CMP0048)
3-
CMAKE_POLICY(SET CMP0048 NEW)
4-
ENDIF (POLICY CMP0048)
1+
CMAKE_MINIMUM_REQUIRED(VERSION 3.0.0)
52
PROJECT(yac)
63

74
# COMPILATION SETTINGS
@@ -23,6 +20,7 @@ IF (USE_ADDRESS_SANITIZER)
2320
ENDIF()
2421

2522
# DEPENDENCIES
23+
LIST(PREPEND CMAKE_MODULE_PATH "/opt/yac/lib/cmake")
2624
LIST(APPEND CMAKE_MODULE_PATH "../cmake")
2725

2826
IF (NOT DEFINED USE_OPENMP)
@@ -39,7 +37,8 @@ IF(USE_OPENMP)
3937
ENDIF(OPENMP_FOUND)
4038
ENDIF(USE_OPENMP)
4139

42-
FIND_PACKAGE(Ceres REQUIRED)
40+
SET(Ceres_DIR "/opt/yac/lib/cmake/Ceres")
41+
FIND_PACKAGE(Ceres REQUIRED REQUIRED PATHS "/opt/yac")
4342
FIND_PACKAGE(OpenCV REQUIRED)
4443
FIND_PACKAGE(Eigen3 REQUIRED)
4544
FIND_PACKAGE(TBB REQUIRED)
@@ -51,7 +50,6 @@ INCLUDE_DIRECTORIES(${SUITESPARSEQR_INCLUDE_DIR})
5150
INCLUDE_DIRECTORIES(${SUITESPARSE_CONFIG_INCLUDE_DIR})
5251
INCLUDE_DIRECTORIES("/opt/yac/include")
5352
LINK_DIRECTORIES("/opt/yac/lib")
54-
LINK_DIRECTORIES("/usr/local/lib")
5553
SET(DEPS
5654
yaml-cpp
5755
glog

yac/lib/calib_nbt.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -681,8 +681,8 @@ int nbt_eval(const lissajous_traj_t &traj,
681681
calib_nbt.problem->AddParameterBlock(calib_nbt.fiducial->param.data(),
682682
FIDUCIAL_PARAMS_SIZE);
683683
if (calib_nbt.fiducial->param.size() == 7) {
684-
calib_nbt.problem->SetParameterization(calib_nbt.fiducial->param.data(),
685-
&calib_nbt.pose_plus);
684+
calib_nbt.problem->SetManifold(calib_nbt.fiducial->param.data(),
685+
&calib_nbt.pose_plus);
686686
}
687687

688688
for (const auto &ts : timeline.timestamps) {

yac/lib/calib_vi.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ calib_vi_view_t::calib_vi_view_t(const bool live_mode_,
2626
problem{problem_}, vision_loss{vision_loss_}, imu_loss{imu_loss_} {
2727
// Add pose to problem
2828
problem->AddParameterBlock(pose.param.data(), 7);
29-
problem->SetParameterization(pose.param.data(), pose_plus);
29+
problem->SetManifold(pose.param.data(), pose_plus);
3030

3131
// Add speed and biases to problem
3232
problem->AddParameterBlock(sb.param.data(), 9);
@@ -260,7 +260,7 @@ calib_vi_view_t::marginalize(marg_residual_t *marg_residual) {
260260
calib_vi_t::calib_vi_t(const calib_target_t &calib_target_)
261261
: calib_target{calib_target_} {
262262
// Ceres-Problem
263-
prob_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
263+
prob_options.manifold_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
264264
prob_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
265265
prob_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
266266
prob_options.enable_fast_removal = true;
@@ -284,7 +284,7 @@ calib_vi_t::calib_vi_t(const calib_target_t &calib_target_)
284284
calib_vi_t::calib_vi_t(const std::string &config_file_)
285285
: config_file{config_file_} {
286286
// Ceres-Problem
287-
prob_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
287+
prob_options.manifold_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
288288
prob_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
289289
prob_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
290290
prob_options.enable_fast_removal = true;
@@ -377,7 +377,7 @@ calib_vi_t::calib_vi_t(const std::string &config_file_)
377377
fiducial = std::make_shared<fiducial_t>(T_WF);
378378
problem->AddParameterBlock(fiducial->param.data(), FIDUCIAL_PARAMS_SIZE);
379379
if (fiducial->param.size() == 7) {
380-
problem->SetParameterization(fiducial->param.data(), &pose_plus);
380+
problem->SetManifold(fiducial->param.data(), &pose_plus);
381381
}
382382
}
383383

@@ -413,7 +413,7 @@ void calib_vi_t::add_imu(const imu_params_t &imu_params_,
413413
// Imu extrinsics
414414
imu_exts = std::make_shared<extrinsics_t>(T_BS);
415415
problem->AddParameterBlock(imu_exts->param.data(), 7);
416-
problem->SetParameterization(imu_exts->param.data(), &pose_plus);
416+
problem->SetManifold(imu_exts->param.data(), &pose_plus);
417417
if (fix_extrinsics) {
418418
problem->SetParameterBlockConstant(imu_exts->param.data());
419419
imu_exts->fixed = true;
@@ -466,7 +466,7 @@ void calib_vi_t::add_camera(const int cam_idx,
466466
// Camera extrinsics
467467
cam_exts[cam_idx] = std::make_shared<extrinsics_t>(T_BCi);
468468
problem->AddParameterBlock(cam_exts[cam_idx]->param.data(), 7);
469-
problem->SetParameterization(cam_exts[cam_idx]->param.data(), &pose_plus);
469+
problem->SetManifold(cam_exts[cam_idx]->param.data(), &pose_plus);
470470
if (fix_extrinsics) {
471471
problem->SetParameterBlockConstant(cam_exts[cam_idx]->param.data());
472472
cam_exts[cam_idx]->fixed = true;
@@ -676,7 +676,7 @@ void calib_vi_t::initialize(const CamIdx2Grids &grids, imu_data_t &imu_buf) {
676676
fiducial = std::make_shared<fiducial_t>(T_WF);
677677
problem->AddParameterBlock(fiducial->param.data(), FIDUCIAL_PARAMS_SIZE);
678678
if (fiducial->param.size() == 7) {
679-
problem->SetParameterization(fiducial->param.data(), &pose_plus);
679+
problem->SetManifold(fiducial->param.data(), &pose_plus);
680680
}
681681
} else {
682682
const mat4_t T_C0S = get_imu_extrinsics();

yac/lib/solver.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -964,7 +964,7 @@ void yac_solver_t::solve(const int max_iter,
964964
// CERES-SOLVER //////////////////////////////////////////////////////////////
965965

966966
ceres_solver_t::ceres_solver_t() {
967-
prob_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
967+
prob_options.manifold_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
968968
prob_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
969969
prob_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
970970
prob_options.enable_fast_removal = true;
@@ -1005,7 +1005,7 @@ void ceres_solver_t::add_param(param_t *param) {
10051005
return false;
10061006
};
10071007
if (is_pose(param)) {
1008-
problem->SetParameterization(param->data(), &pose_plus);
1008+
problem->SetManifold(param->data(), &pose_plus);
10091009
}
10101010
}
10111011

yac/lib/util/ceres_utils.cpp

+22-2
Original file line numberDiff line numberDiff line change
@@ -127,8 +127,8 @@ bool PoseLocalParameterization::Plus(const double *x,
127127
return true;
128128
}
129129

130-
bool PoseLocalParameterization::ComputeJacobian(const double *x,
131-
double *jacobian) const {
130+
bool PoseLocalParameterization::PlusJacobian(const double *x,
131+
double *jacobian) const {
132132
// Jacobian of Plus(x, delta) w.r.t delta at delta = 0.
133133
Eigen::Map<Eigen::Matrix<double, 7, 6, Eigen::RowMajor>> Jp(jacobian);
134134
UNUSED(x);
@@ -151,4 +151,24 @@ bool PoseLocalParameterization::ComputeJacobian(const double *x,
151151
return true;
152152
}
153153

154+
bool PoseLocalParameterization::Minus(const double *x,
155+
const double *delta,
156+
double *x_plus_delta) const {
157+
UNUSED(x);
158+
UNUSED(delta);
159+
UNUSED(x_plus_delta);
160+
return false;
161+
}
162+
163+
bool PoseLocalParameterization::MinusJacobian(const double *x,
164+
double *jacobian) const {
165+
UNUSED(x);
166+
UNUSED(jacobian);
167+
return false;
168+
}
169+
170+
int PoseLocalParameterization::AmbientSize() const { return 7; }
171+
172+
int PoseLocalParameterization::TangentSize() const { return 6; }
173+
154174
} // namespace yac

yac/lib/util/ceres_utils.hpp

+8-4
Original file line numberDiff line numberDiff line change
@@ -31,16 +31,20 @@ bool evaluate_residual_block(const ceres::Problem &problem,
3131
vec2_t &r);
3232

3333
// Pose local parameterization
34-
class PoseLocalParameterization : public ceres::LocalParameterization {
34+
class PoseLocalParameterization : public ceres::Manifold {
3535
public:
3636
PoseLocalParameterization();
3737
virtual ~PoseLocalParameterization();
3838
virtual bool Plus(const double *x,
3939
const double *delta,
4040
double *x_plus_delta) const;
41-
virtual bool ComputeJacobian(const double *x, double *jacobian) const;
42-
virtual int GlobalSize() const { return 7; }
43-
virtual int LocalSize() const { return 6; }
41+
virtual bool PlusJacobian(const double *x, double *jacobian) const;
42+
virtual bool Minus(const double *x,
43+
const double *delta,
44+
double *x_plus_delta) const;
45+
virtual bool MinusJacobian(const double *x, double *jacobian) const;
46+
virtual int AmbientSize() const;
47+
virtual int TangentSize() const;
4448
};
4549

4650
} // namespace yac

0 commit comments

Comments
 (0)