Skip to content

Commit

Permalink
Update to manif to use Ceres Manifold instead of LocalParameterization
Browse files Browse the repository at this point in the history
  • Loading branch information
mattalvarado committed Jun 20, 2024
1 parent 03c497d commit 3fd424a
Show file tree
Hide file tree
Showing 7 changed files with 95 additions and 95 deletions.
10 changes: 5 additions & 5 deletions docs/pages/cpp/On-the-use-with-Ceres.md
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ In this example, we compute an average point from 4 points in `SE2`.
// Tell ceres not to take ownership of the raw pointers
ceres::Problem::Options problem_options;
problem_options.cost_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
problem_options.local_parameterization_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
problem_options.manifold_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;

ceres::Problem problem(problem_options);

Expand Down Expand Up @@ -217,12 +217,12 @@ problem.AddResidualBlock( obj_3_pi_over_4.get(),
// We use a second manif helper that creates a ceres local parameterization
// for our optimized state block.

std::shared_ptr<ceres::LocalParameterization>
auto_diff_local_parameterization =
manif::make_local_parametrization_autodiff<SE2d>();
std::shared_ptr<ceres::Manifold>
auto_diff_manifold =
manif::make_manifold_autodiff<SE2d>();

problem.SetParameterization( average_state.data(),
auto_diff_local_parameterization.get() );
auto_diff_manifold.get() );

// Run the solver!
ceres::Solver::Options options;
Expand Down
18 changes: 9 additions & 9 deletions include/manif/ceres/ceres.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include "manif/ceres/constants.h"
#include "manif/ceres/constraint.h"
#include "manif/ceres/local_parametrization.h"
#include "manif/ceres/manifold.h"
#include "manif/ceres/objective.h"
#include "manif/ceres/ceres_utils.h"

Expand All @@ -18,41 +18,41 @@ struct is_ad<ceres::Jet<_Scalar, _N>> : std::integral_constant<bool, true> { };

#ifdef _MANIF_MANIF_SO2_H_
using CeresConstraintSO2 = CeresConstraintFunctor<SO2d>;
using CeresLocalParameterizationSO2 = CeresLocalParameterizationFunctor<SO2d>;
using CeresManifoldSO2 = CeresManifoldFunctor<SO2d>;
using CeresObjectiveSO2 = CeresObjectiveFunctor<SO2d>;
#else
using CeresConstraintSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresLocalParameterizationSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresManifoldSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresObjectiveSO2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
#endif

#ifdef _MANIF_MANIF_SO3_H_
using CeresConstraintSO3 = CeresConstraintFunctor<SO3d>;
using CeresLocalParameterizationSO3 = CeresLocalParameterizationFunctor<SO3d>;
using CeresManifoldSO3 = CeresManifoldFunctor<SO3d>;
using CeresObjectiveSO3 = CeresObjectiveFunctor<SO3d>;
#else
using CeresConstraintSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresLocalParameterizationSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresManifoldSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresObjectiveSO3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
#endif

#ifdef _MANIF_MANIF_SE2_H_
using CeresConstraintSE2 = CeresConstraintFunctor<SE2d>;
using CeresLocalParameterizationSE2 = CeresLocalParameterizationFunctor<SE2d>;
using CeresManifoldSE2 = CeresManifoldFunctor<SE2d>;
using CeresObjectiveSE2 = CeresObjectiveFunctor<SE2d>;
#else
using CeresConstraintSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresLocalParameterizationSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresManifoldSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresObjectiveSE2 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
#endif

#ifdef _MANIF_MANIF_SE3_H_
using CeresConstraintSE3 = CeresConstraintFunctor<SE3d>;
using CeresLocalParameterizationSE3 = CeresLocalParameterizationFunctor<SE3d>;
using CeresManifoldSE3 = CeresManifoldFunctor<SE3d>;
using CeresObjectiveSE3 = CeresObjectiveFunctor<SE3d>;
#else
using CeresConstraintSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresLocalParameterizationSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresManifoldSE3 = internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
using CeresObjectiveSE3= internal::YOU_MUST_INCLUDE_MANIF_BEFORE_CERES_HELPER_HEADERS;
#endif

Expand Down
14 changes: 7 additions & 7 deletions include/manif/ceres/ceres_utils.h
Original file line number Diff line number Diff line change
@@ -1,28 +1,28 @@
#ifndef _MANIF_MANIF_CERES_UTILS_H_
#define _MANIF_MANIF_CERES_UTILS_H_

#include "manif/ceres/local_parametrization.h"
#include "manif/ceres/manifold.h"
#include "manif/ceres/objective.h"
#include "manif/ceres/constraint.h"

#include <ceres/autodiff_local_parameterization.h>
#include <ceres/autodiff_manifold.h>
#include <ceres/autodiff_cost_function.h>

namespace manif {

/**
* @brief Helper function to create a Ceres autodiff local parameterization wrapper.
* @see CeresLocalParameterizationFunctor
* @see CeresManifoldFunctor
*/
template <typename _LieGroup>
std::shared_ptr<
ceres::AutoDiffLocalParameterization<CeresLocalParameterizationFunctor<_LieGroup>,
ceres::AutoDiffManifold<CeresManifoldFunctor<_LieGroup>,
_LieGroup::RepSize, _LieGroup::DoF>>
make_local_parameterization_autodiff()
make_manifold_autodiff()
{
return std::make_shared<
ceres::AutoDiffLocalParameterization<
CeresLocalParameterizationFunctor<_LieGroup>, _LieGroup::RepSize, _LieGroup::DoF>>();
ceres::AutoDiffManifold<
CeresManifoldFunctor<_LieGroup>, _LieGroup::RepSize, _LieGroup::DoF>>();
}

/**
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef _MANIF_MANIF_CERES_LOCAL_PARAMETRIZATION_H_
#define _MANIF_MANIF_CERES_LOCAL_PARAMETRIZATION_H_
#ifndef _MANIF_MANIF_CERES_MANIFOLD_H_
#define _MANIF_MANIF_CERES_MANIFOLD_H_

#include <Eigen/Core>

Expand All @@ -9,7 +9,7 @@ namespace manif {
* @brief A wrapper for Ceres autodiff local parameterization.
*/
template <typename _LieGroup>
class CeresLocalParameterizationFunctor
class CeresManifoldFunctor
{
using LieGroup = _LieGroup;
using Tangent = typename _LieGroup::Tangent;
Expand All @@ -22,8 +22,8 @@ class CeresLocalParameterizationFunctor

public:

CeresLocalParameterizationFunctor() = default;
virtual ~CeresLocalParameterizationFunctor() = default;
CeresManifoldFunctor() = default;
virtual ~CeresManifoldFunctor() = default;

template<typename T>
bool operator()(const T* state_raw,
Expand All @@ -43,4 +43,4 @@ class CeresLocalParameterizationFunctor

} /* namespace manif */

#endif /* _MANIF_MANIF_CERES_LOCAL_PARAMETRIZATION_H_ */
#endif /* _MANIF_MANIF_CERES_MANIFOLD_H_ */
42 changes: 21 additions & 21 deletions test/ceres/ceres_test_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -378,17 +378,17 @@ class JacobianCeresTester
using Jacobian = typename LieGroup::Jacobian;

using ManifObjective = CeresObjectiveFunctor<LieGroup>;
using ManifLocalParameterization = CeresLocalParameterizationFunctor<LieGroup>;
using ManifManifold = CeresManifoldFunctor<LieGroup>;

using LocalParamJacobian =
using ManifoldJacobian =
Eigen::Matrix<typename LieGroup::Scalar,
LieGroup::RepSize,
LieGroup::DoF,
(LieGroup::DoF>1)?
Eigen::RowMajor:
Eigen::ColMajor>;

using LocalParameterizationPtr = std::shared_ptr<ceres::LocalParameterization>;
using ManifoldPtr = std::shared_ptr<ceres::Manifold>;

using Inverse = CeresInverseFunctor<LieGroup>;
using Rplus = CeresRplusFunctor<LieGroup>;
Expand Down Expand Up @@ -450,7 +450,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().inverse(), state_out);

local_parameterization->ComputeJacobian(state_raw, adJ_locpar.data());
manifold->ComputeJacobian(state_raw, adJ_locpar.data());

// Compute the local_de-parameterization (?) Jac
parameters = new double*[2];
Expand Down Expand Up @@ -488,7 +488,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().log(J_out_s), delta_out);

local_parameterization->ComputeJacobian(state_raw, adJ_locpar.data());
manifold->ComputeJacobian(state_raw, adJ_locpar.data());

adJ_out_s = ad_r_J_out_spd * adJ_locpar;

Expand All @@ -513,7 +513,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().rplus(getDelta(), J_out_s, J_out_so), state_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

Expand All @@ -532,7 +532,7 @@ class JacobianCeresTester

EXPECT_EIGEN_NEAR(J_out_s, adJ_out_s, tol);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -562,7 +562,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().lplus(getDelta(), J_out_s, J_out_so), state_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

Expand All @@ -581,7 +581,7 @@ class JacobianCeresTester

EXPECT_EIGEN_NEAR(J_out_s, adJ_out_s, tol);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -614,13 +614,13 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().rminus(getStateOther()), delta_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

adJ_out_s = adJ_out_R * lhs_adJ_locpar;

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -656,13 +656,13 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().lminus(getStateOther()), delta_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

adJ_out_s = adJ_out_R * lhs_adJ_locpar;

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -694,7 +694,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().compose(getStateOther(), J_out_s, J_out_so), state_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

Expand All @@ -713,7 +713,7 @@ class JacobianCeresTester

EXPECT_EIGEN_NEAR(J_out_s, adJ_out_s, tol);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -742,7 +742,7 @@ class JacobianCeresTester

EXPECT_MANIF_NEAR(getState().between(getStateOther(), J_out_s, J_out_so), state_out);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

Expand All @@ -761,7 +761,7 @@ class JacobianCeresTester

EXPECT_EIGEN_NEAR(J_out_s, adJ_out_s, tol);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_other_raw, rhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -801,7 +801,7 @@ class JacobianCeresTester
Eigen::Matrix<double, LieGroup::Dim, LieGroup::Dim> J_vout_v;
EXPECT_EIGEN_NEAR(getState().act(vin, J_vout_s, J_vout_v), vout, tol);

local_parameterization->ComputeJacobian(
manifold->ComputeJacobian(
state_raw, lhs_adJ_locpar.data()
);

Expand Down Expand Up @@ -829,8 +829,8 @@ class JacobianCeresTester

double **jacobians;

LocalParameterizationPtr local_parameterization =
make_local_parameterization_autodiff<LieGroup>();
ManifoldPtr manifold =
make_manifold_autodiff<LieGroup>();

LieGroup state_out;

Expand All @@ -839,7 +839,7 @@ class JacobianCeresTester
Jacobian J_out_s, J_out_so,
adJ_out_s, adJ_out_so;

LocalParamJacobian adJ_locpar, lhs_adJ_locpar, rhs_adJ_locpar;
ManifoldJacobian adJ_locpar, lhs_adJ_locpar, rhs_adJ_locpar;
};

} // namespace manif
Expand Down
Loading

0 comments on commit 3fd424a

Please sign in to comment.