Fixed overload resoltion error in template matching by removing overloads in traits
parent
c4457682bc
commit
401ee70364
|
@ -144,9 +144,6 @@ struct LieGroupTraits : Testable<Class> {
|
||||||
/// @{
|
/// @{
|
||||||
typedef multiplicative_group_tag group_flavor;
|
typedef multiplicative_group_tag group_flavor;
|
||||||
static Class Identity() { return Class::identity();}
|
static Class Identity() { return Class::identity();}
|
||||||
static Class Compose(const Class& m1, const Class& m2) { return m1 * m2;}
|
|
||||||
static Class Between(const Class& m1, const Class& m2) { return m1.inverse() * m2;}
|
|
||||||
static Class Inverse(const Class& m) { return m.inverse();}
|
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
/// @name Manifold
|
/// @name Manifold
|
||||||
|
@ -161,21 +158,13 @@ struct LieGroupTraits : Testable<Class> {
|
||||||
|
|
||||||
static int GetDimension(const Class&) {return dimension;}
|
static int GetDimension(const Class&) {return dimension;}
|
||||||
|
|
||||||
static TangentVector Local(const Class& origin, const Class& other) {
|
|
||||||
return origin.localCoordinates(other);
|
|
||||||
}
|
|
||||||
|
|
||||||
static Class Retract(const Class& origin, const TangentVector& v) {
|
|
||||||
return origin.retract(v);
|
|
||||||
}
|
|
||||||
|
|
||||||
static TangentVector Local(const Class& origin, const Class& other,
|
static TangentVector Local(const Class& origin, const Class& other,
|
||||||
ChartJacobian Horigin, ChartJacobian Hother = boost::none) {
|
ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
|
||||||
return origin.localCoordinates(other, Horigin, Hother);
|
return origin.localCoordinates(other, Horigin, Hother);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Class Retract(const Class& origin, const TangentVector& v,
|
static Class Retract(const Class& origin, const TangentVector& v,
|
||||||
ChartJacobian Horigin, ChartJacobian Hv = boost::none) {
|
ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) {
|
||||||
return origin.retract(v, Horigin, Hv);
|
return origin.retract(v, Horigin, Hv);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -192,17 +181,18 @@ struct LieGroupTraits : Testable<Class> {
|
||||||
return Class::Expmap(v, Hv);
|
return Class::Expmap(v, Hv);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Class Compose(const Class& m1, const Class& m2, ChartJacobian H1,
|
static Class Compose(const Class& m1, const Class& m2, //
|
||||||
ChartJacobian H2 = boost::none) {
|
ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
|
||||||
return m1.compose(m2, H1, H2);
|
return m1.compose(m2, H1, H2);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Class Between(const Class& m1, const Class& m2, ChartJacobian H1,
|
static Class Between(const Class& m1, const Class& m2, //
|
||||||
ChartJacobian H2 = boost::none) {
|
ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
|
||||||
return m1.between(m2, H1, H2);
|
return m1.between(m2, H1, H2);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Class Inverse(const Class& m, ChartJacobian H) {
|
static Class Inverse(const Class& m, //
|
||||||
|
ChartJacobian H = boost::none) {
|
||||||
return m.inverse(H);
|
return m.inverse(H);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -8,14 +8,14 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/nonlinear/Expression.h>
|
#include <gtsam/nonlinear/Expression.h>
|
||||||
#include <boost/bind.hpp>
|
#include <gtsam/base/Lie.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
// Generics
|
// Generics
|
||||||
template<typename T>
|
template<typename T>
|
||||||
Expression<T> between(const Expression<T>& t1, const Expression<T>& t2) {
|
Expression<T> between(const Expression<T>& t1, const Expression<T>& t2) {
|
||||||
return Expression<T>(t1, &T::between, t2);
|
return Expression<T>(traits<T>::Between, t1, t2);
|
||||||
}
|
}
|
||||||
|
|
||||||
typedef Expression<double> double_;
|
typedef Expression<double> double_;
|
||||||
|
|
|
@ -18,8 +18,8 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// The two new headers that allow using our Automatic Differentiation Expression framework
|
// The two new headers that allow using our Automatic Differentiation Expression framework
|
||||||
#include <gtsam_unstable/slam/expressions.h>
|
#include <gtsam/slam/expressions.h>
|
||||||
#include <gtsam_unstable/nonlinear/ExpressionFactor.h>
|
#include <gtsam/nonlinear/ExpressionFactor.h>
|
||||||
|
|
||||||
// Header order is close to far
|
// Header order is close to far
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
|
@ -48,6 +48,8 @@ int main(int argc, char** argv) {
|
||||||
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
|
||||||
|
|
||||||
// 2b. Add odometry factors
|
// 2b. Add odometry factors
|
||||||
|
BinaryExpression<Pose2, Pose2, Pose2>::Function f = traits<Pose2>::Between;
|
||||||
|
Expression<Pose2>(traits<Pose2>::Between, x1, x2);
|
||||||
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, 0 ), between(x1,x2)));
|
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, 0 ), between(x1,x2)));
|
||||||
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, M_PI_2), between(x2,x3)));
|
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, M_PI_2), between(x2,x3)));
|
||||||
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, M_PI_2), between(x3,x4)));
|
graph.push_back(ExpressionFactor<Pose2>(model, Pose2(2, 0, M_PI_2), between(x3,x4)));
|
||||||
|
|
Loading…
Reference in New Issue