Skip to content

Commit

Permalink
Update to support Ceres versions >= 2.1.0
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 committed Jul 18, 2024
1 parent bd43ceb commit 24f7cbf
Show file tree
Hide file tree
Showing 3 changed files with 34 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#include <industrial_calibration/optimizations/ceres_math_utilities.h>

#include <ceres/jet.h>
#include <ceres/version.h>
#define CERES_VERSION_LT_2_1 (CERES_VERSION_MAJOR < 2 || (CERES_VERSION_MAJOR == 2 && CERES_VERSION_MINOR < 1))
#include <map>

namespace industrial_calibration
Expand Down Expand Up @@ -280,7 +282,11 @@ class DualDHChainMeasurementCost : public DualDHChainCost
T rot_diff = Eigen::Quaternion<T>(camera_to_target_measured_.cast<T>().linear())
.angularDistance(Eigen::Quaternion<T>(camera_to_target.linear()));

#if CERES_VERSION_LT_2_1
residual[3] = ceres::IsNaN(rot_diff) ? T(0.0) : T(orientation_weight_) * rot_diff;
#else
residual[3] = ceres::isnan(rot_diff) ? T(0.0) : T(orientation_weight_) * rot_diff;
#endif

return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,14 @@
#include <industrial_calibration/core/exceptions.h>

#include <ceres/problem.h>
#include <ceres/version.h>

#define CERES_VERSION_LT_2_1 (CERES_VERSION_MAJOR < 2 || (CERES_VERSION_MAJOR == 2 && CERES_VERSION_MINOR < 1))
#if CERES_VERSION_LT_2_1
#include <ceres/local_parameterization.h>
#else
#include <ceres/manifold.h>
#endif
#include <Eigen/Core>

// Ceres Solver - A fast non-linear least squares minimizer
Expand Down Expand Up @@ -127,8 +134,13 @@ void addSubsetParameterization(ceres::Problem& problem, const std::map<const dou
}
else
{
#if CERES_VERSION_LT_2_1
ceres::LocalParameterization* lp = new ceres::SubsetParameterization(block_size, mask);
problem.SetParameterization(p, lp);
#else
ceres::Manifold* m = new ceres::SubsetManifold(block_size, mask);
problem.SetManifold(p, m);
#endif
}
}
}
Expand Down
16 changes: 16 additions & 0 deletions test/local_parameterization_utest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,11 @@ TEST(LocalParameterizationTests, SubsetParameterization)
EXPECT_NO_THROW(addSubsetParameterization(problem, mask));

// Expect there to be no parameterization, but the entire block should be constant
#if CERES_VERSION_LT_2_1
EXPECT_EQ(problem.GetParameterization(params.data()), nullptr);
#else
EXPECT_EQ(problem.GetManifold(params.data()), nullptr);
#endif
EXPECT_TRUE(problem.IsParameterBlockConstant(params.data()));
}

Expand All @@ -51,15 +55,23 @@ TEST(LocalParameterizationTests, SubsetParameterization)
int bad_idx = params.size() * 2;
mask[params.data()].insert(mask[params.data()].begin(), { bad_idx, 0, 1, 2 });
EXPECT_THROW(addSubsetParameterization(problem, mask), OptimizationException);
#if CERES_VERSION_LT_2_1
EXPECT_EQ(problem.GetParameterization(params.data()), nullptr);
#else
EXPECT_EQ(problem.GetManifold(params.data()), nullptr);
#endif
}

// Empty mask
{
std::map<const double*, std::vector<int>> mask;
EXPECT_NO_THROW(addSubsetParameterization(problem, mask));
// An empty mask should not have added any local parameterization
#if CERES_VERSION_LT_2_1
EXPECT_EQ(problem.GetParameterization(params.data()), nullptr);
#else
EXPECT_EQ(problem.GetManifold(params.data()), nullptr);
#endif
}

// Hold the zero-th row constant
Expand All @@ -73,7 +85,11 @@ TEST(LocalParameterizationTests, SubsetParameterization)
mask[params.data()].push_back(i * params.rows());
}
EXPECT_NO_THROW(addSubsetParameterization(problem, mask));
#if CERES_VERSION_LT_2_1
EXPECT_NE(problem.GetParameterization(params.data()), nullptr);
#else
EXPECT_NE(problem.GetManifold(params.data()), nullptr);
#endif
}

// Solve the optimization
Expand Down

0 comments on commit 24f7cbf

Please sign in to comment.