gtsam/gtsam_unstable/nonlinear/ExpressionFactor.h

151 lines
5.1 KiB
C
Raw Normal View History

/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Expression.h
* @date September 18, 2014
* @author Frank Dellaert
* @author Paul Furgale
* @brief Expressions for Block Automatic Differentiation
*/
2014-09-30 18:34:03 +08:00
#include <gtsam_unstable/nonlinear/Expression.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/base/Testable.h>
#include <boost/range/adaptor/map.hpp>
#include <boost/range/algorithm.hpp>
#include <numeric>
namespace gtsam {
/**
2014-10-09 19:00:56 +08:00
* Factor that supports arbitrary expressions via AD
*/
template<class T>
2014-10-09 19:00:56 +08:00
class ExpressionFactor: public NoiseModelFactor {
T measurement_; ///< the measurement to be compared with the expression
Expression<T> expression_; ///< the expression that is AD enabled
std::vector<size_t> dimensions_; ///< dimensions of the Jacobian matrices
size_t augmentedCols_; ///< total number of columns + 1 (for RHS)
2014-10-21 07:26:17 +08:00
static const int Dim = traits::dimension<T>::value;
public:
/// Constructor
2014-10-09 19:00:56 +08:00
ExpressionFactor(const SharedNoiseModel& noiseModel, //
const T& measurement, const Expression<T>& expression) :
measurement_(measurement), expression_(expression) {
if (!noiseModel)
throw std::invalid_argument("ExpressionFactor: no NoiseModel.");
2014-10-21 07:26:17 +08:00
if (noiseModel->dim() != Dim)
throw std::invalid_argument(
"ExpressionFactor was created with a NoiseModel of incorrect dimension.");
noiseModel_ = noiseModel;
// Get dimensions of Jacobian matrices
// An Expression is assumed unmutable, so we do this now
std::map<Key, size_t> map;
expression_.dims(map);
size_t n = map.size();
keys_.resize(n);
boost::copy(map | boost::adaptors::map_keys, keys_.begin());
dimensions_.resize(n);
boost::copy(map | boost::adaptors::map_values, dimensions_.begin());
// Add sizes to know how much memory to allocate on stack in linearize
augmentedCols_ = std::accumulate(dimensions_.begin(), dimensions_.end(), 1);
#ifdef DEBUG_ExpressionFactor
BOOST_FOREACH(size_t d, dimensions_)
std::cout << d << " ";
2014-10-21 07:26:17 +08:00
std::cout << " -> " << Dim << "x" << augmentedCols_ << std::endl;
#endif
}
/**
* Error function *without* the NoiseModel, \f$ z-h(x) \f$.
* We override this method to provide
* both the function evaluation and its derivative(s) in H.
*/
virtual Vector unwhitenedError(const Values& x,
boost::optional<std::vector<Matrix>&> H = boost::none) const {
if (H) {
2014-10-14 21:43:41 +08:00
// H should be pre-allocated
assert(H->size()==size());
2014-10-14 21:43:41 +08:00
// Create and zero out blocks to be passed to expression_
2014-10-14 23:16:31 +08:00
JacobianMap blocks;
blocks.reserve(size());
for (DenseIndex i = 0; i < size(); i++) {
2014-10-14 23:16:31 +08:00
Matrix& Hi = H->at(i);
2014-10-21 07:26:17 +08:00
Hi.resize(Dim, dimensions_[i]);
2014-10-14 21:43:41 +08:00
Hi.setZero(); // zero out
2014-10-21 07:26:17 +08:00
Eigen::Block<Matrix> block = Hi.block(0, 0, Dim, dimensions_[i]);
blocks.push_back(std::make_pair(keys_[i], block));
2014-10-14 21:43:41 +08:00
}
T value = expression_.value(x, blocks);
return measurement_.localCoordinates(value);
} else {
const T& value = expression_.value(x);
return measurement_.localCoordinates(value);
}
}
virtual boost::shared_ptr<GaussianFactor> linearize(const Values& x) const {
2014-10-19 17:19:09 +08:00
// This method has been heavily optimized for maximum performance.
// We allocate a VerticalBlockMatrix on the stack first, and then create
// Eigen::Block<Matrix> views on this piece of memory which is then passed
// to [expression_.value] below, which writes directly into Ab_.
// Another malloc saved by creating a Matrix on the stack
double memory[Dim * augmentedCols_];
2014-10-21 07:26:17 +08:00
Eigen::Map<Eigen::Matrix<double, Dim, Eigen::Dynamic> > //
matrix(memory, Dim, augmentedCols_);
matrix.setZero(); // zero out
2014-10-14 14:59:01 +08:00
// Construct block matrix, is of right size but un-initialized
VerticalBlockMatrix Ab(dimensions_, matrix, true);
// Create blocks into Ab_ to be passed to expression_
JacobianMap blocks;
blocks.reserve(size());
for (DenseIndex i = 0; i < size(); i++)
blocks.push_back(std::make_pair(keys_[i], Ab(i)));
2014-10-19 17:19:09 +08:00
// Evaluate error to get Jacobians and RHS vector b
2014-10-19 17:19:09 +08:00
T value = expression_.value(x, blocks); // <<< Reverse AD happens here !
2014-10-14 23:16:31 +08:00
Ab(size()).col(0) = -measurement_.localCoordinates(value);
// Whiten the corresponding system now
2014-10-14 23:16:31 +08:00
// TODO ! this->noiseModel_->WhitenSystem(Ab);
// TODO pass unwhitened + noise model to Gaussian factor
// For now, only linearized constrained factors have noise model at linear level!!!
noiseModel::Constrained::shared_ptr constrained = //
boost::dynamic_pointer_cast<noiseModel::Constrained>(this->noiseModel_);
if (constrained) {
2014-10-14 23:16:31 +08:00
return boost::make_shared<JacobianFactor>(this->keys(), Ab,
constrained->unit());
} else
2014-10-14 23:16:31 +08:00
return boost::make_shared<JacobianFactor>(this->keys(), Ab);
}
};
2014-10-09 19:00:56 +08:00
// ExpressionFactor
}