2010-01-08 23:32:45 +08:00
|
|
|
/**
|
|
|
|
* @file BetweenFactor.h
|
|
|
|
* @authors Frank Dellaert, Viorela Ila
|
|
|
|
**/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <ostream>
|
|
|
|
|
|
|
|
#include "NonlinearFactor.h"
|
|
|
|
#include "GaussianFactor.h"
|
|
|
|
#include "Lie.h"
|
|
|
|
#include "Matrix.h"
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
|
|
|
/**
|
|
|
|
* A class for a measurement predicted by "between(config[key1],config[key2])"
|
|
|
|
* T is the Lie group type, Config where the T's are gotten from
|
|
|
|
*/
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
template<class Config, class Key, class T>
|
|
|
|
class BetweenFactor: public NonlinearFactor2<Config, Key, T, Key, T> {
|
2010-01-08 23:32:45 +08:00
|
|
|
|
|
|
|
private:
|
|
|
|
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
typedef NonlinearFactor2<Config, Key, T, Key, T> Base;
|
|
|
|
|
2010-01-08 23:32:45 +08:00
|
|
|
T measured_; /** The measurement */
|
|
|
|
Matrix square_root_inverse_covariance_; /** sqrt(inv(measurement_covariance)) */
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
// shorthand for a smart pointer to a factor
|
|
|
|
typedef typename boost::shared_ptr<BetweenFactor> shared_ptr;
|
|
|
|
|
|
|
|
/** Constructor */
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
BetweenFactor(const Key& key1, const Key& key2, const T& measured,
|
|
|
|
const Matrix& measurement_covariance) :
|
|
|
|
Base(1, key1, key2), measured_(measured) {
|
2010-01-08 23:32:45 +08:00
|
|
|
square_root_inverse_covariance_ = inverse_square_root(
|
|
|
|
measurement_covariance);
|
|
|
|
}
|
|
|
|
|
|
|
|
/** implement functions needed for Testable */
|
|
|
|
|
|
|
|
/** print */
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
void print(const std::string& s) const {
|
|
|
|
Base::print(s);
|
2010-01-08 23:32:45 +08:00
|
|
|
measured_.print("measured ");
|
|
|
|
gtsam::print(square_root_inverse_covariance_, "MeasurementCovariance");
|
|
|
|
}
|
|
|
|
|
|
|
|
/** equals */
|
|
|
|
bool equals(const NonlinearFactor<Config>& expected, double tol) const {
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
const BetweenFactor<Config, Key, T> *e =
|
|
|
|
dynamic_cast<const BetweenFactor<Config, Key, T>*> (&expected);
|
|
|
|
return e != NULL && Base::equals(expected)
|
|
|
|
&& this->measured_.equals(e->measured_, tol);
|
2010-01-08 23:32:45 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/** implement functions needed to derive from Factor */
|
|
|
|
|
|
|
|
/** vector of errors */
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
Vector evaluateError(const T& p1, const T& p2, boost::optional<Matrix&> H1 =
|
|
|
|
boost::none, boost::optional<Matrix&> H2 = boost::none) const {
|
|
|
|
// h - z
|
|
|
|
T hx = between(p1, p2);
|
|
|
|
// TODO should be done by noise model
|
2010-01-16 09:16:59 +08:00
|
|
|
if (H1 || H2) {
|
|
|
|
between(p1,p2,H1,H2);
|
|
|
|
if (H1) *H1 = square_root_inverse_covariance_ * *H1;
|
|
|
|
if (H2) *H2 = square_root_inverse_covariance_ * *H2;
|
|
|
|
}
|
Large gtsam refactoring
To support faster development *and* better performance Richard and I pushed through a large refactoring of NonlinearFactors.
The following are the biggest changes:
1) NonLinearFactor1 and NonLinearFactor2 are now templated on Config, Key type, and X type, where X is the argument to the measurement function.
2) The measurement itself is no longer kept in the nonlinear factor. Instead, a derived class (see testVSLAMFactor, testNonlinearEquality, testPose3Factor etc...) has to implement a function to compute the errors, "evaluateErrors". Instead of (h(x)-z), it needs to return (z-h(x)), so Ax-b is an approximation of the error. IMPORTANT: evaluateErrors needs - if asked - *combine* the calculation of the function value h(x) and the derivatives dh(x)/dx. This was a major performance issue. To do this, boost::optional<Matrix&> arguments are provided, and tin EvaluateErrors you just says something like
if (H) *H = Matrix_(3,6,....);
3) We are no longer using int or strings for nonlinear factors. Instead, the preferred key type is now Symbol, defined in Key.h. This is both fast and cool: you can construct it from an int, and cast it to a strong. It also does type checking: a Symbol<Pose3,'x'> will not match a Symbol<Pose2,'x'>
4) minor: take a look at LieConfig.h: it help you avoid writing a lot of code bu automatically creating configs for a certain type. See e.g. Pose3Config.h. A "double" LieConfig is on the way - Thanks Richard and Manohar !
2010-01-14 06:25:03 +08:00
|
|
|
// manifold equivalent of h(x)-z -> log(z,h(x))
|
|
|
|
// TODO use noise model, error vector is not whitened yet
|
|
|
|
return square_root_inverse_covariance_ * logmap(measured_, hx);
|
2010-01-13 00:11:24 +08:00
|
|
|
}
|
|
|
|
|
2010-01-13 00:12:25 +08:00
|
|
|
/** return the measured */
|
|
|
|
inline const T measured() const {return measured_;}
|
|
|
|
|
2010-01-08 23:32:45 +08:00
|
|
|
/** number of variables attached to this factor */
|
|
|
|
inline std::size_t size() const { return 2;}
|
|
|
|
};
|
|
|
|
|
|
|
|
} /// namespace gtsam
|