Merge remote-tracking branch 'origin/develop' into feature/SoundSlam
Conflicts: examples/SFMExampleExpressions.cpprelease/4.3a0
commit
3587ad4e2c
32
.cproject
32
.cproject
|
@ -510,22 +510,6 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
<target name="SFMExampleExpressions.run" path="build/gtsam_unstable/examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>SFMExampleExpressions.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="Pose2SLAMExampleExpressions.run" path="build/gtsam_unstable/examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
|
||||||
<buildCommand>make</buildCommand>
|
|
||||||
<buildArguments>-j5</buildArguments>
|
|
||||||
<buildTarget>Pose2SLAMExampleExpressions.run</buildTarget>
|
|
||||||
<stopOnError>true</stopOnError>
|
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
|
||||||
<runAllBuilders>true</runAllBuilders>
|
|
||||||
</target>
|
|
||||||
<target name="testInvDepthCamera3.run" path="build/gtsam_unstable/geometry/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testInvDepthCamera3.run" path="build/gtsam_unstable/geometry/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
@ -3102,6 +3086,22 @@
|
||||||
<useDefaultCommand>true</useDefaultCommand>
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
<runAllBuilders>true</runAllBuilders>
|
<runAllBuilders>true</runAllBuilders>
|
||||||
</target>
|
</target>
|
||||||
|
<target name="Pose2SLAMExampleExpressions.run" path="build/examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments>-j4</buildArguments>
|
||||||
|
<buildTarget>Pose2SLAMExampleExpressions.run</buildTarget>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
|
<target name="SFMExampleExpressions.run" path="build/examples" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
|
<buildCommand>make</buildCommand>
|
||||||
|
<buildArguments>-j4</buildArguments>
|
||||||
|
<buildTarget>SFMExampleExpressions.run</buildTarget>
|
||||||
|
<stopOnError>true</stopOnError>
|
||||||
|
<useDefaultCommand>true</useDefaultCommand>
|
||||||
|
<runAllBuilders>true</runAllBuilders>
|
||||||
|
</target>
|
||||||
<target name="testLago.run" path="build/gtsam/nonlinear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
<target name="testLago.run" path="build/gtsam/nonlinear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
|
||||||
<buildCommand>make</buildCommand>
|
<buildCommand>make</buildCommand>
|
||||||
<buildArguments>-j5</buildArguments>
|
<buildArguments>-j5</buildArguments>
|
||||||
|
|
|
@ -72,22 +72,22 @@ typedef NoiseModelFactor1<Pose> NM1;
|
||||||
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
||||||
typedef BearingRangeFactor<Pose,Point2> BR;
|
typedef BearingRangeFactor<Pose,Point2> BR;
|
||||||
|
|
||||||
GTSAM_VALUE_EXPORT(Value);
|
//GTSAM_VALUE_EXPORT(Value);
|
||||||
GTSAM_VALUE_EXPORT(Pose);
|
//GTSAM_VALUE_EXPORT(Pose);
|
||||||
GTSAM_VALUE_EXPORT(Rot2);
|
//GTSAM_VALUE_EXPORT(Rot2);
|
||||||
GTSAM_VALUE_EXPORT(Point2);
|
//GTSAM_VALUE_EXPORT(Point2);
|
||||||
GTSAM_VALUE_EXPORT(NonlinearFactor);
|
//GTSAM_VALUE_EXPORT(NonlinearFactor);
|
||||||
GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
//GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
||||||
GTSAM_VALUE_EXPORT(NM1);
|
//GTSAM_VALUE_EXPORT(NM1);
|
||||||
GTSAM_VALUE_EXPORT(NM2);
|
//GTSAM_VALUE_EXPORT(NM2);
|
||||||
GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
//GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
||||||
GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
//GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
||||||
GTSAM_VALUE_EXPORT(BR);
|
//GTSAM_VALUE_EXPORT(BR);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Base);
|
//GTSAM_VALUE_EXPORT(noiseModel::Base);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
//GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
//GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
//GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
//GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
||||||
|
|
||||||
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
||||||
// Compute degrees of freedom (observations - variables)
|
// Compute degrees of freedom (observations - variables)
|
||||||
|
@ -295,7 +295,7 @@ void runIncremental()
|
||||||
NonlinearFactorGraph newFactors;
|
NonlinearFactorGraph newFactors;
|
||||||
Values newVariables;
|
Values newVariables;
|
||||||
|
|
||||||
newFactors.push_back(boost::make_shared<PriorFactor<Pose> >(firstPose, Pose(), noiseModel::Unit::Create(Pose::Dim())));
|
newFactors.push_back(boost::make_shared<PriorFactor<Pose> >(firstPose, Pose(), noiseModel::Unit::Create(3)));
|
||||||
newVariables.insert(firstPose, Pose());
|
newVariables.insert(firstPose, Pose());
|
||||||
|
|
||||||
isam2.update(newFactors, newVariables);
|
isam2.update(newFactors, newVariables);
|
||||||
|
@ -474,7 +474,7 @@ void runBatch()
|
||||||
cout << "Creating batch optimizer..." << endl;
|
cout << "Creating batch optimizer..." << endl;
|
||||||
|
|
||||||
NonlinearFactorGraph measurements = datasetMeasurements;
|
NonlinearFactorGraph measurements = datasetMeasurements;
|
||||||
measurements.push_back(boost::make_shared<PriorFactor<Pose> >(0, Pose(), noiseModel::Unit::Create(Pose::Dim())));
|
measurements.push_back(boost::make_shared<PriorFactor<Pose> >(0, Pose(), noiseModel::Unit::Create(3)));
|
||||||
|
|
||||||
gttic_(Create_optimizer);
|
gttic_(Create_optimizer);
|
||||||
GaussNewtonParams params;
|
GaussNewtonParams params;
|
||||||
|
|
|
@ -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_;
|
||||||
|
|
Loading…
Reference in New Issue