Fixed the Eigen::Map compilation error
parent
0857c1069c
commit
cb7fb21add
|
@ -363,9 +363,11 @@ struct traits_x<float> : public internal::ScalarTraits<float> {};
|
||||||
// traits for any double Eigen matrix
|
// traits for any double Eigen matrix
|
||||||
template<int M, int N, int Options, int MaxRows, int MaxCols>
|
template<int M, int N, int Options, int MaxRows, int MaxCols>
|
||||||
struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
|
struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
|
||||||
|
BOOST_STATIC_ASSERT_MSG(M != Eigen::Dynamic && N != Eigen::Dynamic,
|
||||||
|
"This traits class only supports fixed-size matrices.");
|
||||||
// Typedefs required by all manifold types.
|
// Typedefs required by all manifold types.
|
||||||
typedef vector_space_tag structure_category;
|
typedef vector_space_tag structure_category;
|
||||||
enum { dimension = (M == Eigen::Dynamic ? Eigen::Dynamic : (N == Eigen::Dynamic ? Eigen::Dynamic : M * N)) };
|
enum { dimension = M * N };
|
||||||
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
|
typedef Eigen::Matrix<double, dimension, 1> TangentVector;
|
||||||
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
|
typedef OptionalJacobian<dimension, dimension> ChartJacobian;
|
||||||
typedef Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> ManifoldType;
|
typedef Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> ManifoldType;
|
||||||
|
@ -405,8 +407,7 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
|
||||||
ChartJacobian Hv = boost::none) {
|
ChartJacobian Hv = boost::none) {
|
||||||
if (Horigin) *Horigin = Eye(origin);
|
if (Horigin) *Horigin = Eye(origin);
|
||||||
if (Hv) *Hv = Eye(origin);
|
if (Hv) *Hv = Eye(origin);
|
||||||
return origin +
|
return origin + Eigen::Map<const Eigen::Matrix<double, M, N> >(v.data(), origin.rows(), origin.cols());
|
||||||
Eigen::Map<Eigen::Matrix<double, M, N> >(v.data(), origin.rows(), origin.cols());
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static ManifoldType Compose(const ManifoldType& m1,
|
static ManifoldType Compose(const ManifoldType& m1,
|
||||||
|
@ -444,7 +445,7 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
|
||||||
if (Hm) *Hm = Eye(m);
|
if (Hm) *Hm = Eye(m);
|
||||||
TangentVector result(GetDimension(m));
|
TangentVector result(GetDimension(m));
|
||||||
Eigen::Map<Eigen::Matrix<double, M, N> >(
|
Eigen::Map<Eigen::Matrix<double, M, N> >(
|
||||||
result.data(), m.rows(), m.cols()) = m;
|
result.data()) = m;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -453,7 +454,7 @@ struct traits_x< Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > {
|
||||||
ManifoldType m; m.setZero();
|
ManifoldType m; m.setZero();
|
||||||
if (Hv) *Hv = Eye(m);
|
if (Hv) *Hv = Eye(m);
|
||||||
return m +
|
return m +
|
||||||
Eigen::Map<Eigen::Matrix<double, M, N> >(v.data(), m.rows(), m.cols());
|
Eigen::Map<Eigen::Matrix<double, M, N> >(v.data());
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -70,7 +70,7 @@ Vector numericalGradient(boost::function<double(const X&)> h, const X& x,
|
||||||
double factor = 1.0 / (2.0 * delta);
|
double factor = 1.0 / (2.0 * delta);
|
||||||
|
|
||||||
BOOST_STATIC_ASSERT_MSG(
|
BOOST_STATIC_ASSERT_MSG(
|
||||||
(boost::is_base_of<manifold_tag, typename traits_x<X>::structure_category_tag>::value),
|
(boost::is_base_of<manifold_tag, typename traits_x<X>::structure_category>::value),
|
||||||
"Template argument X must be a manifold type.");
|
"Template argument X must be a manifold type.");
|
||||||
static const int N = traits_x<X>::dimension;
|
static const int N = traits_x<X>::dimension;
|
||||||
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type.");
|
BOOST_STATIC_ASSERT_MSG(N>0, "Template argument X must be fixed-size type.");
|
||||||
|
@ -300,10 +300,11 @@ inline Matrix numericalHessian(boost::function<double(const X&)> f, const X& x,
|
||||||
double delta = 1e-5) {
|
double delta = 1e-5) {
|
||||||
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X>::structure_category>::value),
|
BOOST_STATIC_ASSERT_MSG( (boost::is_base_of<gtsam::manifold_tag, typename traits_x<X>::structure_category>::value),
|
||||||
"Template argument X must be a manifold type.");
|
"Template argument X must be a manifold type.");
|
||||||
|
typedef Eigen::Matrix<double, traits_x<X>::dimension, 1> VectorD;
|
||||||
typedef boost::function<double(const X&)> F;
|
typedef boost::function<double(const X&)> F;
|
||||||
typedef boost::function<Vector(F, const X&, double)> G;
|
typedef boost::function<VectorD(F, const X&, double)> G;
|
||||||
G ng = static_cast<G>(numericalGradient<X> );
|
G ng = static_cast<G>(numericalGradient<X> );
|
||||||
return numericalDerivative11<Vector, X>(boost::bind(ng, f, _1, delta), x,
|
return numericalDerivative11<VectorD, X>(boost::bind(ng, f, _1, delta), x,
|
||||||
delta);
|
delta);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue