/* ---------------------------------------------------------------------------- * 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-inl.h * @date September 18, 2014 * @author Frank Dellaert * @author Paul Furgale * @brief Internals for Expression.h, not for general consumption */ #pragma once #include #include #include #include #include #include // for placement new struct TestBinaryExpression; // template meta-programming headers #include #include #include #include #include #include #include namespace MPL = boost::mpl::placeholders; namespace gtsam { template class Expression; typedef std::map JacobianMap; /// Move terms to array, destroys content void move(JacobianMap& jacobians, std::vector& H) { assert(H.size()==jacobians.size()); size_t j = 0; JacobianMap::iterator it = jacobians.begin(); for (; it != jacobians.end(); ++it) it->second.swap(H[j++]); } //----------------------------------------------------------------------------- /** * Value and Jacobians */ template class Augmented { private: T value_; JacobianMap jacobians_; typedef std::pair Pair; /// Insert terms into jacobians_, adding if already exists void add(const JacobianMap& terms) { BOOST_FOREACH(const Pair& term, terms) { JacobianMap::iterator it = jacobians_.find(term.first); if (it != jacobians_.end()) it->second += term.second; else jacobians_[term.first] = term.second; } } /// Insert terms into jacobians_, premultiplying by H, adding if already exists void add(const Matrix& H, const JacobianMap& terms) { BOOST_FOREACH(const Pair& term, terms) { JacobianMap::iterator it = jacobians_.find(term.first); if (it != jacobians_.end()) it->second += H * term.second; else jacobians_[term.first] = H * term.second; } } public: /// Construct value that does not depend on anything Augmented(const T& t) : value_(t) { } /// Construct value dependent on a single key Augmented(const T& t, Key key) : value_(t) { size_t n = t.dim(); jacobians_[key] = Eigen::MatrixXd::Identity(n, n); } /// Construct value, pre-multiply jacobians by dTdA Augmented(const T& t, const Matrix& dTdA, const JacobianMap& jacobians) : value_(t) { add(dTdA, jacobians); } /// Construct value, pre-multiply jacobians Augmented(const T& t, const Matrix& dTdA1, const JacobianMap& jacobians1, const Matrix& dTdA2, const JacobianMap& jacobians2) : value_(t) { add(dTdA1, jacobians1); add(dTdA2, jacobians2); } /// Construct value, pre-multiply jacobians Augmented(const T& t, const Matrix& dTdA1, const JacobianMap& jacobians1, const Matrix& dTdA2, const JacobianMap& jacobians2, const Matrix& dTdA3, const JacobianMap& jacobians3) : value_(t) { add(dTdA1, jacobians1); add(dTdA2, jacobians2); add(dTdA3, jacobians3); } /// Return value const T& value() const { return value_; } /// Return jacobians const JacobianMap& jacobians() const { return jacobians_; } /// Return jacobians JacobianMap& jacobians() { return jacobians_; } /// Not dependent on any key bool constant() const { return jacobians_.empty(); } /// debugging void print(const KeyFormatter& keyFormatter = DefaultKeyFormatter) { BOOST_FOREACH(const Pair& term, jacobians_) std::cout << "(" << keyFormatter(term.first) << ", " << term.second.rows() << "x" << term.second.cols() << ") "; std::cout << std::endl; } /// Move terms to array, destroys content void move(std::vector& H) { move(jacobians_, H); } }; //----------------------------------------------------------------------------- /** * The CallRecord class stores the Jacobians of applying a function * with respect to each of its arguments. It also stores an executation trace * (defined below) for each of its arguments. * * It is sub-classed in the function-style ExpressionNode sub-classes below. */ template struct CallRecord { static size_t const N = 0; virtual void print(const std::string& indent) const { } virtual void startReverseAD(JacobianMap& jacobians) const { } virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const { } typedef Eigen::Matrix Jacobian2T; virtual void reverseAD2(const Jacobian2T& dFdT, JacobianMap& jacobians) const { } }; //----------------------------------------------------------------------------- /** * The ExecutionTrace class records a tree-structured expression's execution * It is a tagged union that obviates the need to create * a ExecutionTrace subclass for Constants and Leaf Expressions. Instead * the key for the leaf is stored in the space normally used to store a * CallRecord*. Nothing is stored for a Constant. */ template class ExecutionTrace { enum { Constant, Leaf, Function } type; union { Key key; CallRecord* ptr; } content; public: /// Pointer always starts out as a Constant ExecutionTrace() : type(Constant) { } /// Change pointer to a Leaf Record void setLeaf(Key key) { type = Leaf; content.key = key; } /// Take ownership of pointer to a Function Record void setFunction(CallRecord* record) { type = Function; content.ptr = record; } /// Print void print(const std::string& indent = "") const { if (type == Constant) std::cout << indent << "Constant" << std::endl; else if (type == Leaf) std::cout << indent << "Leaf, key = " << content.key << std::endl; else if (type == Function) { std::cout << indent << "Function" << std::endl; content.ptr->print(indent + " "); } } /// Return record pointer, quite unsafe, used only for testing template boost::optional record() { if (type != Function) return boost::none; else { Record* p = dynamic_cast(content.ptr); return p ? boost::optional(p) : boost::none; } } // *** This is the main entry point for reverseAD, called from Expression::augmented *** // Called only once, either inserts identity into Jacobians (Leaf) or starts AD (Function) void startReverseAD(JacobianMap& jacobians) const { if (type == Leaf) { // This branch will only be called on trivial Leaf expressions, i.e. Priors size_t n = T::Dim(); jacobians[content.key] = Eigen::MatrixXd::Identity(n, n); } else if (type == Function) // This is the more typical entry point, starting the AD pipeline // It is inside the startReverseAD that the correctly dimensioned pipeline is chosen. content.ptr->startReverseAD(jacobians); } // Either add to Jacobians (Leaf) or propagate (Function) void reverseAD(const Matrix& dTdA, JacobianMap& jacobians) const { if (type == Leaf) { JacobianMap::iterator it = jacobians.find(content.key); if (it != jacobians.end()) it->second += dTdA; else jacobians[content.key] = dTdA; } else if (type == Function) content.ptr->reverseAD(dTdA, jacobians); } // Either add to Jacobians (Leaf) or propagate (Function) typedef Eigen::Matrix Jacobian2T; void reverseAD2(const Jacobian2T& dTdA, JacobianMap& jacobians) const { if (type == Leaf) { JacobianMap::iterator it = jacobians.find(content.key); if (it != jacobians.end()) it->second += dTdA; else jacobians[content.key] = dTdA; } else if (type == Function) content.ptr->reverseAD2(dTdA, jacobians); } }; /// Primary template calls the generic Matrix reverseAD pipeline template struct Select { typedef Eigen::Matrix Jacobian; static void reverseAD(const ExecutionTrace& trace, const Jacobian& dTdA, JacobianMap& jacobians) { trace.reverseAD(dTdA, jacobians); } }; /// Partially specialized template calls the 2-dimensional output version template struct Select<2, A> { typedef Eigen::Matrix Jacobian; static void reverseAD(const ExecutionTrace& trace, const Jacobian& dTdA, JacobianMap& jacobians) { trace.reverseAD2(dTdA, jacobians); } }; //----------------------------------------------------------------------------- /** * Expression node. The superclass for objects that do the heavy lifting * An Expression has a pointer to an ExpressionNode underneath * allowing Expressions to have polymorphic behaviour even though they * are passed by value. This is the same way boost::function works. * http://loki-lib.sourceforge.net/html/a00652.html */ template class ExpressionNode { public: static size_t const N = 0; // number of arguments protected: size_t traceSize_; /// Constructor, traceSize is size of the execution trace of expression rooted here ExpressionNode(size_t traceSize = 0) : traceSize_(traceSize) { } public: /// Destructor virtual ~ExpressionNode() { } /// Return keys that play in this expression as a set virtual std::set keys() const = 0; // Return size needed for memory buffer in traceExecution size_t traceSize() const { return traceSize_; } /// Return value virtual T value(const Values& values) const = 0; /// Return value and derivatives virtual Augmented forward(const Values& values) const = 0; /// Construct an execution trace for reverse AD virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const = 0; }; //----------------------------------------------------------------------------- /// Constant Expression template class ConstantExpression: public ExpressionNode { /// The constant value T constant_; /// Constructor with a value, yielding a constant ConstantExpression(const T& value) : constant_(value) { } friend class Expression ; public: /// Return keys that play in this expression, i.e., the empty set virtual std::set keys() const { std::set keys; return keys; } /// Return value virtual T value(const Values& values) const { return constant_; } /// Return value and derivatives virtual Augmented forward(const Values& values) const { return Augmented(constant_); } /// Construct an execution trace for reverse AD virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const { return constant_; } }; //----------------------------------------------------------------------------- /// Leaf Expression template class LeafExpression: public ExpressionNode { /// The key into values Key key_; /// Constructor with a single key LeafExpression(Key key) : key_(key) { } friend class Expression ; public: /// Return keys that play in this expression virtual std::set keys() const { std::set keys; keys.insert(key_); return keys; } /// Return value virtual T value(const Values& values) const { return values.at(key_); } /// Return value and derivatives virtual Augmented forward(const Values& values) const { return Augmented(values.at(key_), key_); } /// Construct an execution trace for reverse AD virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const { trace.setLeaf(key_); return values.at(key_); } }; //----------------------------------------------------------------------------- /** * Building block for Recursive Record Class * Records the evaluation of a single argument in a functional expression * The integer argument N is to guarantee a unique type signature, * so we are guaranteed to be able to extract their values by static cast. */ template struct JacobianTrace { typedef Eigen::Matrix JacobianTA; ExecutionTrace trace; JacobianTA dTdA; }; /** * Recursive Record Class for Functional Expressions * Abrahams, David; Gurtovoy, Aleksey (2004-12-10). * C++ Template Metaprogramming: Concepts, Tools, and Techniques from Boost * and Beyond. Pearson Education. */ template struct GenerateRecord: JacobianTrace, Base { typedef T return_type; static size_t const N = Base::N + 1; typedef JacobianTrace This; /// Print to std::cout virtual void print(const std::string& indent) const { Base::print(indent); static const Eigen::IOFormat matlab(0, 1, " ", "; ", "", "", "[", "]"); std::cout << This::dTdA.format(matlab) << std::endl; This::trace.print(indent); } /// Start the reverse AD process virtual void startReverseAD(JacobianMap& jacobians) const { Base::startReverseAD(jacobians); Select::reverseAD(This::trace, This::dTdA, jacobians); } /// Given df/dT, multiply in dT/dA and continue reverse AD process virtual void reverseAD(const Matrix& dFdT, JacobianMap& jacobians) const { Base::reverseAD(dFdT, jacobians); This::trace.reverseAD(dFdT * This::dTdA, jacobians); } /// Version specialized to 2-dimensional output typedef Eigen::Matrix Jacobian2T; virtual void reverseAD2(const Jacobian2T& dFdT, JacobianMap& jacobians) const { Base::reverseAD2(dFdT, jacobians); This::trace.reverseAD2(dFdT * This::dTdA, jacobians); } }; /// Recursive Record class Generator template struct Record: public boost::mpl::fold, GenerateRecord >::type { }; /// Access JacobianTrace template JacobianTrace& jacobianTrace( Record& record) { return static_cast&>(record); } /// Access Trace template ExecutionTrace& getTrace(Record* record) { return jacobianTrace(*record).trace; } /// Access Jacobian template Eigen::Matrix& jacobian( Record* record) { return jacobianTrace(*record).dTdA; } //----------------------------------------------------------------------------- /** * Building block for Recursive FunctionalNode Class */ template struct Argument { boost::shared_ptr > expression; }; /** * Recursive Definition of Functional ExpressionNode */ template struct GenerateFunctionalNode: Argument, Base { typedef T return_type; static size_t const N = Base::N + 1; typedef Argument This; }; /// Recursive GenerateFunctionalNode class Generator template struct FunctionalNode: public boost::mpl::fold, GenerateFunctionalNode >::type { }; /// Access Argument template Argument& argument(Record& record) { return static_cast&>(record); } /// Access Expression template ExecutionTrace& expression(Record* record) { return argument(*record).expression; } //----------------------------------------------------------------------------- /// Unary Function Expression template class UnaryExpression: public FunctionalNode > { public: typedef Eigen::Matrix JacobianTA; typedef boost::function)> Function; private: Function function_; boost::shared_ptr > expressionA1_; /// Constructor with a unary function f, and input argument e UnaryExpression(Function f, const Expression& e1) : function_(f), expressionA1_(e1.root()) { ExpressionNode::traceSize_ = sizeof(Record) + e1.traceSize(); } friend class Expression ; public: /// Return keys that play in this expression virtual std::set keys() const { return expressionA1_->keys(); } /// Return value virtual T value(const Values& values) const { return function_(this->expressionA1_->value(values), boost::none); } /// Return value and derivatives virtual Augmented forward(const Values& values) const { using boost::none; Augmented argument = this->expressionA1_->forward(values); JacobianTA dTdA; T t = function_(argument.value(), argument.constant() ? none : boost::optional(dTdA)); return Augmented(t, dTdA, argument.jacobians()); } /// CallRecord structure for reverse AD typedef boost::mpl::vector Arguments; typedef Record Record; /// Construct an execution trace for reverse AD virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const { Record* record = new (raw) Record(); trace.setFunction(record); raw = (char*) (record + 1); A1 a1 = expressionA1_->traceExecution(values, getTrace(record), raw); return function_(a1, jacobian(record)); } }; //----------------------------------------------------------------------------- /// Binary Expression template class BinaryExpression: public ExpressionNode { public: typedef Eigen::Matrix JacobianTA1; typedef Eigen::Matrix JacobianTA2; typedef boost::function< T(const A1&, const A2&, boost::optional, boost::optional)> Function; private: Function function_; boost::shared_ptr > expressionA1_; boost::shared_ptr > expressionA2_; /// Constructor with a binary function f, and two input arguments BinaryExpression(Function f, // const Expression& e1, const Expression& e2) : function_(f), expressionA1_(e1.root()), expressionA2_(e2.root()) { ExpressionNode::traceSize_ = // sizeof(Record) + e1.traceSize() + e2.traceSize(); } friend class Expression ; friend struct ::TestBinaryExpression; public: /// Return keys that play in this expression virtual std::set keys() const { std::set keys1 = expressionA1_->keys(); std::set keys2 = expressionA2_->keys(); keys1.insert(keys2.begin(), keys2.end()); return keys1; } /// Return value virtual T value(const Values& values) const { using boost::none; return function_(this->expressionA1_->value(values), this->expressionA2_->value(values), none, none); } /// Return value and derivatives virtual Augmented forward(const Values& values) const { using boost::none; Augmented a1 = this->expressionA1_->forward(values); Augmented a2 = this->expressionA2_->forward(values); JacobianTA1 dTdA1; JacobianTA2 dTdA2; T t = function_(a1.value(), a2.value(), a1.constant() ? none : boost::optional(dTdA1), a2.constant() ? none : boost::optional(dTdA2)); return Augmented(t, dTdA1, a1.jacobians(), dTdA2, a2.jacobians()); } /// CallRecord structure for reverse AD typedef boost::mpl::vector Arguments; typedef Record Record; /// Construct an execution trace for reverse AD /// The raw buffer is [Record | A1 raw | A2 raw] virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const { Record* record = new (raw) Record(); trace.setFunction(record); raw = (char*) (record + 1); A1 a1 = expressionA1_->traceExecution(values, getTrace(record), raw); raw = raw + expressionA1_->traceSize(); A2 a2 = expressionA2_->traceExecution(values, getTrace(record), raw); return function_(a1, a2, jacobian(record), jacobian(record)); } }; //----------------------------------------------------------------------------- /// Ternary Expression template class TernaryExpression: public ExpressionNode { public: typedef Eigen::Matrix JacobianTA1; typedef Eigen::Matrix JacobianTA2; typedef Eigen::Matrix JacobianTA3; typedef boost::function< T(const A1&, const A2&, const A3&, boost::optional, boost::optional, boost::optional)> Function; private: Function function_; boost::shared_ptr > expressionA1_; boost::shared_ptr > expressionA2_; boost::shared_ptr > expressionA3_; /// Constructor with a ternary function f, and three input arguments TernaryExpression(Function f, const Expression& e1, const Expression& e2, const Expression& e3) : function_(f), expressionA1_(e1.root()), expressionA2_(e2.root()), expressionA3_( e3.root()) { ExpressionNode::traceSize_ = // sizeof(Record) + e1.traceSize() + e2.traceSize() + e3.traceSize(); } friend class Expression ; public: /// Return keys that play in this expression virtual std::set keys() const { std::set keys1 = expressionA1_->keys(); std::set keys2 = expressionA2_->keys(); std::set keys3 = expressionA3_->keys(); keys2.insert(keys3.begin(), keys3.end()); keys1.insert(keys2.begin(), keys2.end()); return keys1; } /// Return value virtual T value(const Values& values) const { using boost::none; return function_(this->expressionA1_->value(values), this->expressionA2_->value(values), this->expressionA3_->value(values), none, none, none); } /// Return value and derivatives virtual Augmented forward(const Values& values) const { using boost::none; Augmented a1 = this->expressionA1_->forward(values); Augmented a2 = this->expressionA2_->forward(values); Augmented a3 = this->expressionA3_->forward(values); JacobianTA1 dTdA1; JacobianTA2 dTdA2; JacobianTA3 dTdA3; T t = function_(a1.value(), a2.value(), a3.value(), a1.constant() ? none : boost::optional(dTdA1), a2.constant() ? none : boost::optional(dTdA2), a3.constant() ? none : boost::optional(dTdA3)); return Augmented(t, dTdA1, a1.jacobians(), dTdA2, a2.jacobians(), dTdA3, a3.jacobians()); } /// CallRecord structure for reverse AD typedef boost::mpl::vector Arguments; typedef Record Record; /// Construct an execution trace for reverse AD virtual T traceExecution(const Values& values, ExecutionTrace& trace, char* raw) const { Record* record = new (raw) Record(); trace.setFunction(record); raw = (char*) (record + 1); A1 a1 = expressionA1_->traceExecution(values, getTrace(record), raw); raw = raw + expressionA1_->traceSize(); A2 a2 = expressionA2_->traceExecution(values, getTrace(record), raw); raw = raw + expressionA2_->traceSize(); A3 a3 = expressionA3_->traceExecution(values, getTrace(record), raw); return function_(a1, a2, a3, jacobian(record), jacobian(record), jacobian(record)); } }; //----------------------------------------------------------------------------- }