Skip to content

Commit 522a2ec

Browse files
Support gcc12 and ceres 2.1.0 (#341)
Add support for the Manifold class when using Ceres Solver version 2.1.0 and above --------- Co-authored-by: Jake McLaughlin <[email protected]>
1 parent 415971a commit 522a2ec

File tree

45 files changed

+1643
-813
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+1643
-813
lines changed

fuse_constraints/CMakeLists.txt

Lines changed: 44 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,47 @@ catkin_package(
3535
###########
3636
## Build ##
3737
###########
38-
add_compile_options(-Wall -Werror)
38+
39+
# Disable warnings about array bounds with -Wno-array-bounds until gcc 12 fixes this bug:
40+
# https://gcc.gnu.org/bugzilla/show_bug.cgi?id=106247
41+
#
42+
# Also reported in Eigen, and confirmed to be due to gcc 12:
43+
# https://gitlab.com/libeigen/eigen/-/issues/2506
44+
#
45+
# In file included from include/immintrin.h:43,
46+
# from include/eigen3/Eigen/src/Core/util/ConfigureVectorization.h:361,
47+
# from include/eigen3/Eigen/Core:22,
48+
# from include/fuse_core/fuse_macros.h:63,
49+
# from include/fuse_core/loss.h:37,
50+
# from include/fuse_core/constraint.h:37,
51+
# from src/fuse/fuse_constraints/include/fuse_constraints/relative_orientation_3d_stamped_constraint.h:37,
52+
# from src/fuse/fuse_constraints/src/relative_orientation_3d_stamped_constraint.cpp:34:
53+
# In function ‘__m256d _mm256_loadu_pd(const double*)’,
54+
# inlined from ‘Packet Eigen::internal::ploadu(const typename unpacket_traits<T>::type*) [with Packet = __vector(4) double]’ at include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h:582:129,
55+
# inlined from ‘Packet Eigen::internal::ploadt(const typename unpacket_traits<T>::type*) [with Packet = __vector(4) double; int Alignment = 0]’ at include/eigen3/Eigen/src/Core/GenericPacketMath.h:969:26,
56+
# inlined from ‘PacketType Eigen::internal::evaluator<Eigen::PlainObjectBase<Derived> >::packet(Eigen::Index) const [with int LoadMode = 0; PacketType = __vector(4) double; Derived = Eigen::Matrix<double, 3, 1>]’ at include/eigen3/Eigen/src/Core/CoreEvaluators.h:245:40,
57+
# inlined from ‘void Eigen::internal::generic_dense_assignment_kernel<DstEvaluatorTypeT, SrcEvaluatorTypeT, Functor, Version>::assignPacket(Eigen::Index) [with int StoreMode = 32; int LoadMode = 0; PacketType = __vector(4) double; DstEvaluatorTypeT = Eigen::internal::evaluator<Eigen::Map<Eigen::Matrix<double, -1, 1> > >; SrcEvaluatorTypeT = Eigen::internal::evaluator<Eigen::Matrix<double, 3, 1> >; Functor = Eigen::internal::assign_op<double, double>; int Version = 0]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:681:114,
58+
# inlined from ‘static void Eigen::internal::dense_assignment_loop<Kernel, 3, 0>::run(Kernel&) [with Kernel = Eigen::internal::generic_dense_assignment_kernel<Eigen::internal::evaluator<Eigen::Map<Eigen::Matrix<double, -1, 1> > >, Eigen::internal::evaluator<Eigen::Matrix<double, 3, 1> >, Eigen::internal::assign_op<double, double>, 0>]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:437:75,
59+
# inlined from ‘void Eigen::internal::call_dense_assignment_loop(DstXprType&, const SrcXprType&, const Functor&) [with DstXprType = Eigen::Map<Eigen::Matrix<double, -1, 1> >; SrcXprType = Eigen::Matrix<double, 3, 1>; Functor = assign_op<double, double>]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:785:37,
60+
# inlined from ‘static void Eigen::internal::Assignment<DstXprType, SrcXprType, Functor, Eigen::internal::Dense2Dense, Weak>::run(DstXprType&, const SrcXprType&, const Functor&) [with DstXprType = Eigen::Map<Eigen::Matrix<double, -1, 1> >; SrcXprType = Eigen::Matrix<double, 3, 1>; Functor = Eigen::internal::assign_op<double, double>; Weak = void]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:954:31,
61+
# inlined from ‘void Eigen::internal::call_assignment_no_alias(Dst&, const Src&, const Func&) [with Dst = Eigen::Map<Eigen::Matrix<double, -1, 1> >; Src = Eigen::Matrix<double, 3, 1>; Func = assign_op<double, double>]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:890:49,
62+
# inlined from ‘void Eigen::internal::call_assignment(Dst&, const Src&, const Func&, typename enable_if<evaluator_assume_aliasing<Src>::value, void*>::type) [with Dst = Eigen::Map<Eigen::Matrix<double, -1, 1> >; Src = Eigen::Product<Eigen::Matrix<double, 3, 3, 1>, Eigen::Map<Eigen::Matrix<double, -1, 1> >, 0>; Func = assign_op<double, double>]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:851:27,
63+
# inlined from ‘void Eigen::internal::call_assignment(Dst&, const Src&) [with Dst = Eigen::Map<Eigen::Matrix<double, -1, 1> >; Src = Eigen::Product<Eigen::Matrix<double, 3, 3, 1>, Eigen::Map<Eigen::Matrix<double, -1, 1> >, 0>]’ at include/eigen3/Eigen/src/Core/AssignEvaluator.h:836:18,
64+
# inlined from ‘Derived& Eigen::MatrixBase<Derived>::operator=(const Eigen::DenseBase<OtherDerived>&) [with OtherDerived = Eigen::Product<Eigen::Matrix<double, 3, 3, 1>, Eigen::Map<Eigen::Matrix<double, -1, 1> >, 0>; Derived = Eigen::Map<Eigen::Matrix<double, -1, 1> >]’ at include/eigen3/Eigen/src/Core/Assign.h:66:28,
65+
# inlined from ‘void Eigen::EigenBase<Derived>::applyThisOnTheLeft(Dest&) const [with Dest = Eigen::Map<Eigen::Matrix<double, -1, 1> >; Derived = Eigen::Matrix<double, 3, 3, 1>]’ at include/eigen3/Eigen/src/Core/EigenBase.h:114:9:
66+
# include/avxintrin.h:893:24: error: array subscript ‘__m256d_u[0]’ is partly outside array bounds of ‘Eigen::internal::plain_matrix_type<Eigen::Product<Eigen::Matrix<double, 3, 3, 1>, Eigen::Map<Eigen::Matrix<double, -1, 1> >, 0>, Eigen::Dense>::type [1]’ {aka ‘Eigen::Matrix<double, 3, 1> [1]’} [-Werror=array-bounds]
67+
# 893 | return *(__m256d_u *)__P;
68+
# | ^~~
69+
# In file included from include/eigen3/Eigen/Core:278:
70+
# include/eigen3/Eigen/src/Core/AssignEvaluator.h: In member function ‘void Eigen::EigenBase<Derived>::applyThisOnTheLeft(Dest&) const [with Dest = Eigen::Map<Eigen::Matrix<double, -1, 1> >; Derived = Eigen::Matrix<double, 3, 3, 1>]’:
71+
# include/eigen3/Eigen/src/Core/AssignEvaluator.h:850:41: note: at offset [0, 16] into object ‘tmp’ of size 24
72+
# 850 | typename plain_matrix_type<Src>::type tmp(src);
73+
# | ^~~
74+
if (CMAKE_CXX_COMPILER_ID STREQUAL "GNU" AND CMAKE_CXX_COMPILER_VERSION VERSION_GREATER_EQUAL 12.0)
75+
add_compile_options(-Wall -Werror -Wno-array-bounds)
76+
else()
77+
add_compile_options(-Wall -Werror)
78+
endif()
3979

4080
# fuse_constraints library
4181
add_library(${PROJECT_NAME}
@@ -66,6 +106,9 @@ add_dependencies(${PROJECT_NAME}
66106
target_include_directories(${PROJECT_NAME}
67107
PUBLIC
68108
include
109+
)
110+
target_include_directories(${PROJECT_NAME}
111+
SYSTEM PUBLIC
69112
${catkin_INCLUDE_DIRS}
70113
${CERES_INCLUDE_DIRS}
71114
${EIGEN3_INCLUDE_DIRS}

fuse_constraints/include/fuse_constraints/marginal_constraint.h

Lines changed: 59 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,9 @@
3636

3737
#include <fuse_core/constraint.h>
3838
#include <fuse_core/eigen.h>
39-
#include <fuse_core/local_parameterization.h>
4039
#include <fuse_core/fuse_macros.h>
40+
#include <fuse_core/local_parameterization.h>
41+
#include <fuse_core/manifold.h>
4142
#include <fuse_core/serialization.h>
4243
#include <fuse_core/variable.h>
4344

@@ -57,10 +58,8 @@
5758
#include <string>
5859
#include <vector>
5960

60-
6161
namespace fuse_constraints
6262
{
63-
6463
/**
6564
* @brief A constraint that represents remaining marginal information on a set of variables
6665
*
@@ -93,7 +92,7 @@ class MarginalConstraint : public fuse_core::Constraint
9392
* @param[in] last_A Iterator pointing to one past the last A matrix
9493
* @param[in] b The b vector of the marginal cost (of the form A*(x - x_bar) + b)
9594
*/
96-
template<typename VariableIterator, typename MatrixIterator>
95+
template <typename VariableIterator, typename MatrixIterator>
9796
MarginalConstraint(
9897
const std::string& source,
9998
VariableIterator first_variable,
@@ -122,13 +121,20 @@ class MarginalConstraint : public fuse_core::Constraint
122121
*/
123122
const std::vector<fuse_core::VectorXd>& x_bar() const { return x_bar_; }
124123

124+
#if !CERES_SUPPORTS_MANIFOLDS
125125
/**
126126
* @brief Read-only access to the variable local parameterizations
127127
*/
128128
const std::vector<fuse_core::LocalParameterization::SharedPtr>& localParameterizations() const
129129
{
130130
return local_parameterizations_;
131131
}
132+
#else
133+
/**
134+
* @brief Read-only access to the variable local parameterizations
135+
*/
136+
const std::vector<fuse_core::Manifold::SharedPtr>& manifolds() const { return manifolds_; }
137+
#endif
132138

133139
/**
134140
* @brief Print a human-readable description of the constraint to the provided stream.
@@ -151,7 +157,11 @@ class MarginalConstraint : public fuse_core::Constraint
151157
protected:
152158
std::vector<fuse_core::MatrixXd> A_; //!< The A matrices of the marginal constraint
153159
fuse_core::VectorXd b_; //!< The b vector of the marginal constraint
154-
std::vector<fuse_core::LocalParameterization::SharedPtr> local_parameterizations_; //!< The local parameterizations
160+
#if !CERES_SUPPORTS_MANIFOLDS
161+
std::vector<fuse_core::LocalParameterization::SharedPtr> local_parameterizations_; //!< Parameterizations
162+
#else
163+
std::vector<fuse_core::Manifold::SharedPtr> manifolds_; //!< Manifolds
164+
#endif
155165
std::vector<fuse_core::VectorXd> x_bar_; //!< The linearization point of each involved variable
156166

157167
private:
@@ -164,20 +174,23 @@ class MarginalConstraint : public fuse_core::Constraint
164174
* @param[in/out] archive - The archive object that holds the serialized class members
165175
* @param[in] version - The version of the archive being read/written. Generally unused.
166176
*/
167-
template<class Archive>
177+
template <class Archive>
168178
void serialize(Archive& archive, const unsigned int /* version */)
169179
{
170-
archive & boost::serialization::base_object<fuse_core::Constraint>(*this);
171-
archive & A_;
172-
archive & b_;
173-
archive & local_parameterizations_;
174-
archive & x_bar_;
180+
archive& boost::serialization::base_object<fuse_core::Constraint>(*this);
181+
archive& A_;
182+
archive& b_;
183+
#if !CERES_SUPPORTS_MANIFOLDS
184+
archive& local_parameterizations_;
185+
#else
186+
archive& manifolds_;
187+
#endif
188+
archive& x_bar_;
175189
}
176190
};
177191

178192
namespace detail
179193
{
180-
181194
/**
182195
* @brief Return the UUID of the provided variable
183196
*/
@@ -194,6 +207,7 @@ inline const fuse_core::VectorXd getCurrentValue(const fuse_core::Variable& vari
194207
return Eigen::Map<const fuse_core::VectorXd>(variable.data(), variable.size());
195208
}
196209

210+
#if !CERES_SUPPORTS_MANIFOLDS
197211
/**
198212
* @brief Return the local parameterization of the provided variable
199213
*/
@@ -202,31 +216,52 @@ inline fuse_core::LocalParameterization::SharedPtr const getLocalParameterizatio
202216
return fuse_core::LocalParameterization::SharedPtr(variable.localParameterization());
203217
}
204218

219+
#else
220+
/**
221+
* @brief Return the manifold of the provided variable
222+
*/
223+
inline fuse_core::Manifold::SharedPtr const getManifold(const fuse_core::Variable& variable)
224+
{
225+
return fuse_core::Manifold::SharedPtr(variable.manifold());
226+
}
227+
#endif
228+
205229
} // namespace detail
206230

207-
template<typename VariableIterator, typename MatrixIterator>
231+
template <typename VariableIterator, typename MatrixIterator>
208232
MarginalConstraint::MarginalConstraint(
209233
const std::string& source,
210234
VariableIterator first_variable,
211235
VariableIterator last_variable,
212236
MatrixIterator first_A,
213237
MatrixIterator last_A,
214238
const fuse_core::VectorXd& b) :
215-
Constraint(source,
216-
boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getUuid),
217-
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getUuid)),
218-
A_(first_A, last_A),
219-
b_(b),
220-
local_parameterizations_(boost::make_transform_iterator(first_variable,
221-
&fuse_constraints::detail::getLocalParameterization),
222-
boost::make_transform_iterator(last_variable,
223-
&fuse_constraints::detail::getLocalParameterization)),
224-
x_bar_(boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getCurrentValue),
225-
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getCurrentValue))
239+
Constraint(
240+
source,
241+
boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getUuid),
242+
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getUuid)),
243+
A_(first_A, last_A),
244+
b_(b),
245+
#if !CERES_SUPPORTS_MANIFOLDS
246+
local_parameterizations_(
247+
boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getLocalParameterization),
248+
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getLocalParameterization)),
249+
#else
250+
manifolds_(
251+
boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getManifold),
252+
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getManifold)),
253+
#endif
254+
x_bar_(
255+
boost::make_transform_iterator(first_variable, &fuse_constraints::detail::getCurrentValue),
256+
boost::make_transform_iterator(last_variable, &fuse_constraints::detail::getCurrentValue))
226257
{
227258
assert(!A_.empty());
228259
assert(A_.size() == x_bar_.size());
260+
#if !CERES_SUPPORTS_MANIFOLDS
229261
assert(A_.size() == local_parameterizations_.size());
262+
#else
263+
assert(A_.size() == manifolds_.size());
264+
#endif
230265
assert(b_.rows() > 0);
231266
assert(std::all_of(A_.begin(), A_.end(), [this](const auto& A){ return A.rows() == this->b_.rows(); })); // NOLINT
232267
assert(std::all_of(boost::make_zip_iterator(boost::make_tuple(A_.begin(), first_variable)),

fuse_constraints/include/fuse_constraints/marginal_cost_function.h

Lines changed: 23 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -36,15 +36,14 @@
3636

3737
#include <fuse_core/eigen.h>
3838
#include <fuse_core/local_parameterization.h>
39+
#include <fuse_core/manifold.h>
3940

4041
#include <ceres/cost_function.h>
4142

4243
#include <vector>
4344

44-
4545
namespace fuse_constraints
4646
{
47-
4847
/**
4948
* @brief Implements a cost function designed for precomputed marginal distributions
5049
*
@@ -56,14 +55,15 @@ namespace fuse_constraints
5655
*
5756
* where, the A matrices and the b vector are fixed, x_bar is the linearization point used when calculating the A
5857
* matrices and b vector, and the minus operator in (x - x_bar) is provided by the variable's local parameterization.
59-
*
58+
*
6059
* The A matrices can have any number of rows, but they must all be the same. The number of columns of each A matrix
6160
* must match the associated variable's local parameterization size, and the number of rows of each x_bar must match
6261
* the associated variable's global size. The cost function will have the same number of residuals as the rows of A.
6362
*/
6463
class MarginalCostFunction : public ceres::CostFunction
6564
{
6665
public:
66+
#if !CERES_SUPPORTS_MANIFOLDS
6767
/**
6868
* @brief Construct a cost function instance
6969
*
@@ -77,6 +77,21 @@ class MarginalCostFunction : public ceres::CostFunction
7777
const fuse_core::VectorXd& b,
7878
const std::vector<fuse_core::VectorXd>& x_bar,
7979
const std::vector<fuse_core::LocalParameterization::SharedPtr>& local_parameterizations);
80+
#else
81+
/**
82+
* @brief Construct a cost function instance
83+
*
84+
* @param[in] A The A matrix of the marginal cost (of the form A*(x - x_bar) + b)
85+
* @param[in] b The b vector of the marginal cost (of the form A*(x - x_bar) + b)
86+
* @param[in] x_bar The linearization point of the involved variables
87+
* @param[in] manifolds The manifold associated with the variable
88+
*/
89+
MarginalCostFunction(
90+
const std::vector<fuse_core::MatrixXd>& A,
91+
const fuse_core::VectorXd& b,
92+
const std::vector<fuse_core::VectorXd>& x_bar,
93+
const std::vector<fuse_core::Manifold::SharedPtr>& manifolds);
94+
#endif
8095

8196
/**
8297
* @brief Destructor
@@ -87,15 +102,16 @@ class MarginalCostFunction : public ceres::CostFunction
87102
* @brief Compute the cost values/residuals, and optionally the Jacobians, using the provided variable/parameter
88103
* values
89104
*/
90-
bool Evaluate(
91-
double const* const* parameters,
92-
double* residuals,
93-
double** jacobians) const override;
105+
bool Evaluate(double const* const* parameters, double* residuals, double** jacobians) const override;
94106

95107
private:
96108
const std::vector<fuse_core::MatrixXd>& A_; //!< The A matrices of the marginal cost
97109
const fuse_core::VectorXd& b_; //!< The b vector of the marginal cost
110+
#if !CERES_SUPPORTS_MANIFOLDS
98111
const std::vector<fuse_core::LocalParameterization::SharedPtr>& local_parameterizations_; //!< Parameterizations
112+
#else
113+
const std::vector<fuse_core::Manifold::SharedPtr>& manifolds_; //!< Manifolds
114+
#endif
99115
const std::vector<fuse_core::VectorXd>& x_bar_; //!< The linearization point of each variable
100116
};
101117

fuse_constraints/include/fuse_constraints/marginalize_variables.h

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,8 @@
3838
#include <fuse_constraints/uuid_ordering.h>
3939
#include <fuse_core/constraint.h>
4040
#include <fuse_core/eigen.h>
41-
#include <fuse_core/graph.h>
42-
#include <fuse_core/local_parameterization.h>
4341
#include <fuse_core/fuse_macros.h>
42+
#include <fuse_core/graph.h>
4443
#include <fuse_core/transaction.h>
4544
#include <fuse_core/variable.h>
4645

@@ -54,10 +53,8 @@
5453
#include <string>
5554
#include <vector>
5655

57-
5856
namespace fuse_constraints
5957
{
60-
6158
/**
6259
* @brief Compute an efficient elimination order for the marginalized variables
6360
*
@@ -129,7 +126,6 @@ fuse_core::Transaction marginalizeVariables(
129126

130127
namespace detail
131128
{
132-
133129
/**
134130
* @brief Structure holding linearized Jacobian blocks
135131
*

fuse_constraints/src/marginal_constraint.cpp

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -37,15 +37,13 @@
3737
#include <fuse_core/constraint.h>
3838
#include <pluginlib/class_list_macros.hpp>
3939

40-
#include <boost/serialization/export.hpp>
4140
#include <Eigen/Core>
41+
#include <boost/serialization/export.hpp>
4242

4343
#include <ostream>
4444

45-
4645
namespace fuse_constraints
4746
{
48-
4947
void MarginalConstraint::print(std::ostream& stream) const
5048
{
5149
stream << type() << "\n"
@@ -59,8 +57,10 @@ void MarginalConstraint::print(std::ostream& stream) const
5957
Eigen::IOFormat indent(4, 0, ", ", "\n", " [", "]");
6058
for (size_t i = 0; i < A().size(); ++i)
6159
{
62-
stream << " A[" << i << "]:\n" << A()[i].format(indent) << "\n"
63-
<< " x_bar[" << i << "]:\n" << x_bar()[i].format(indent) << "\n";
60+
stream << " A[" << i << "]:\n"
61+
<< A()[i].format(indent) << "\n"
62+
<< " x_bar[" << i << "]:\n"
63+
<< x_bar()[i].format(indent) << "\n";
6464
}
6565
stream << " b:\n" << b().format(indent) << "\n";
6666

@@ -73,7 +73,11 @@ void MarginalConstraint::print(std::ostream& stream) const
7373

7474
ceres::CostFunction* MarginalConstraint::costFunction() const
7575
{
76+
#if !CERES_SUPPORTS_MANIFOLDS
7677
return new MarginalCostFunction(A_, b_, x_bar_, local_parameterizations_);
78+
#else
79+
return new MarginalCostFunction(A_, b_, x_bar_, manifolds_);
80+
#endif
7781
}
7882

7983
} // namespace fuse_constraints

0 commit comments

Comments
 (0)