Moved all internal data structures to internal namespace

release/4.3a0
dellaert 2015-05-11 21:16:57 -07:00
parent 134730eeee
commit 81b3860991
12 changed files with 67 additions and 78 deletions

View File

@ -2046,14 +2046,6 @@
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="testCustomChartExpression.run" path="build/gtsam_unstable/nonlinear/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j4</buildArguments>
<buildTarget>testCustomChartExpression.run</buildTarget>
<stopOnError>true</stopOnError>
<useDefaultCommand>true</useDefaultCommand>
<runAllBuilders>true</runAllBuilders>
</target>
<target name="schedulingExample.run" path="build/gtsam_unstable/discrete/tests" targetID="org.eclipse.cdt.build.MakeTargetBuilder">
<buildCommand>make</buildCommand>
<buildArguments>-j5</buildArguments>

View File

@ -20,18 +20,10 @@
#pragma once
#include <gtsam/base/VerticalBlockMatrix.h>
#include <gtsam/base/FastVector.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/nonlinear/JacobianMap.h>
#include <boost/mpl/transform.hpp>
namespace gtsam {
class JacobianMap;
// forward declaration
//-----------------------------------------------------------------------------
namespace internal {
/**
@ -64,8 +56,6 @@ struct ConvertToVirtualFunctionSupportedMatrixType<false> {
}
};
} // namespace internal
/**
* The CallRecord is an abstract base class for the any class that stores
* the Jacobians of applying a function with respect to each of its arguments,
@ -94,9 +84,8 @@ struct CallRecord {
inline void reverseAD2(const Eigen::MatrixBase<Derived> & dFdT,
JacobianMap& jacobians) const {
_reverseAD3(
internal::ConvertToVirtualFunctionSupportedMatrixType<
(Derived::RowsAtCompileTime > 5)>::convert(dFdT),
jacobians);
ConvertToVirtualFunctionSupportedMatrixType<
(Derived::RowsAtCompileTime > 5)>::convert(dFdT), jacobians);
}
// This overload supports matrices with both rows and columns dynamically sized.
@ -140,7 +129,6 @@ private:
*/
const int CallRecordMaxVirtualStaticRows = 5;
namespace internal {
/**
* The CallRecordImplementor implements the CallRecord interface for a Derived class by
* delegating to its corresponding (templated) non-virtual methods.
@ -193,5 +181,4 @@ private:
};
} // namespace internal
} // gtsam

View File

@ -27,6 +27,7 @@
#include <Eigen/Core>
namespace gtsam {
namespace internal {
template<int T> struct CallRecord;
@ -36,8 +37,6 @@ template<int T> struct CallRecord;
static const unsigned TraceAlignment = 16;
typedef boost::aligned_storage<1, TraceAlignment>::type ExecutionTraceStorage;
namespace internal {
template<bool UseBlock, typename Derived>
struct UseBlockIf {
static void addToJacobian(const Eigen::MatrixBase<Derived>& dTdA,
@ -56,13 +55,12 @@ struct UseBlockIf<false, Derived> {
jacobians(key) += dTdA;
}
};
}
/// Handle Leaf Case: reverse AD ends here, by writing a matrix into Jacobians
template<typename Derived>
void handleLeafCase(const Eigen::MatrixBase<Derived>& dTdA,
JacobianMap& jacobians, Key key) {
internal::UseBlockIf<
UseBlockIf<
Derived::RowsAtCompileTime != Eigen::Dynamic
&& Derived::ColsAtCompileTime != Eigen::Dynamic, Derived>::addToJacobian(
dTdA, jacobians, key);
@ -164,4 +162,5 @@ public:
typedef ExecutionTrace<T> type;
};
} // namespace internal
} // namespace gtsam

View File

@ -36,25 +36,25 @@ void Expression<T>::print(const std::string& s) const {
// Construct a constant expression
template<typename T>
Expression<T>::Expression(const T& value) :
root_(new ConstantExpression<T>(value)) {
root_(new internal::ConstantExpression<T>(value)) {
}
// Construct a leaf expression, with Key
template<typename T>
Expression<T>::Expression(const Key& key) :
root_(new LeafExpression<T>(key)) {
root_(new internal::LeafExpression<T>(key)) {
}
// Construct a leaf expression, with Symbol
template<typename T>
Expression<T>::Expression(const Symbol& symbol) :
root_(new LeafExpression<T>(symbol)) {
root_(new internal::LeafExpression<T>(symbol)) {
}
// Construct a leaf expression, creating Symbol
template<typename T>
Expression<T>::Expression(unsigned char c, size_t j) :
root_(new LeafExpression<T>(Symbol(c, j))) {
root_(new internal::LeafExpression<T>(Symbol(c, j))) {
}
/// Construct a nullary method expression
@ -62,7 +62,9 @@ template<typename T>
template<typename A>
Expression<T>::Expression(const Expression<A>& expression,
T (A::*method)(typename MakeOptionalJacobian<T, A>::type) const) :
root_(new UnaryExpression<T, A>(boost::bind(method, _1, _2), expression)) {
root_(
new internal::UnaryExpression<T, A>(boost::bind(method, _1, _2),
expression)) {
}
/// Construct a unary function expression
@ -70,7 +72,7 @@ template<typename T>
template<typename A>
Expression<T>::Expression(typename UnaryFunction<A>::type function,
const Expression<A>& expression) :
root_(new UnaryExpression<T, A>(function, expression)) {
root_(new internal::UnaryExpression<T, A>(function, expression)) {
}
/// Construct a unary method expression
@ -81,8 +83,8 @@ Expression<T>::Expression(const Expression<A1>& expression1,
typename MakeOptionalJacobian<T, A2>::type) const,
const Expression<A2>& expression2) :
root_(
new BinaryExpression<T, A1, A2>(boost::bind(method, _1, _2, _3, _4),
expression1, expression2)) {
new internal::BinaryExpression<T, A1, A2>(
boost::bind(method, _1, _2, _3, _4), expression1, expression2)) {
}
/// Construct a binary function expression
@ -90,7 +92,9 @@ template<typename T>
template<typename A1, typename A2>
Expression<T>::Expression(typename BinaryFunction<A1, A2>::type function,
const Expression<A1>& expression1, const Expression<A2>& expression2) :
root_(new BinaryExpression<T, A1, A2>(function, expression1, expression2)) {
root_(
new internal::BinaryExpression<T, A1, A2>(function, expression1,
expression2)) {
}
/// Construct a binary method expression
@ -103,7 +107,7 @@ Expression<T>::Expression(const Expression<A1>& expression1,
typename MakeOptionalJacobian<T, A3>::type) const,
const Expression<A2>& expression2, const Expression<A3>& expression3) :
root_(
new TernaryExpression<T, A1, A2, A3>(
new internal::TernaryExpression<T, A1, A2, A3>(
boost::bind(method, _1, _2, _3, _4, _5, _6), expression1,
expression2, expression3)) {
}
@ -115,13 +119,13 @@ Expression<T>::Expression(typename TernaryFunction<A1, A2, A3>::type function,
const Expression<A1>& expression1, const Expression<A2>& expression2,
const Expression<A3>& expression3) :
root_(
new TernaryExpression<T, A1, A2, A3>(function, expression1, expression2,
expression3)) {
new internal::TernaryExpression<T, A1, A2, A3>(function, expression1,
expression2, expression3)) {
}
/// Return root
template<typename T>
const boost::shared_ptr<ExpressionNode<T> >& Expression<T>::root() const {
const boost::shared_ptr<internal::ExpressionNode<T> >& Expression<T>::root() const {
return root_;
}
@ -186,10 +190,10 @@ T Expression<T>::value(const Values& values, const FastVector<Key>& keys,
}
template<typename T>
T Expression<T>::traceExecution(const Values& values, ExecutionTrace<T>& trace,
void* traceStorage) const {
T Expression<T>::traceExecution(const Values& values,
internal::ExecutionTrace<T>& trace, void* traceStorage) const {
return root_->traceExecution(values, trace,
static_cast<ExecutionTraceStorage*>(traceStorage));
static_cast<internal::ExecutionTraceStorage*>(traceStorage));
}
template<typename T>
@ -205,12 +209,12 @@ T Expression<T>::value(const Values& values, JacobianMap& jacobians) const {
// allocated on Visual Studio. For more information see the issue below
// https://bitbucket.org/gtborg/gtsam/issue/178/vlas-unsupported-in-visual-studio
#ifdef _MSC_VER
ExecutionTraceStorage* traceStorage = new ExecutionTraceStorage[size];
internal::ExecutionTraceStorage* traceStorage = new internal::ExecutionTraceStorage[size];
#else
ExecutionTraceStorage traceStorage[size];
internal::ExecutionTraceStorage traceStorage[size];
#endif
ExecutionTrace<T> trace;
internal::ExecutionTrace<T> trace;
T value(this->traceExecution(values, trace, traceStorage));
trace.startReverseAD1(jacobians);
@ -226,7 +230,7 @@ typename Expression<T>::KeysAndDims Expression<T>::keysAndDims() const {
std::map<Key, int> map;
dims(map);
size_t n = map.size();
KeysAndDims pair = std::make_pair(FastVector < Key > (n), FastVector<int>(n));
KeysAndDims pair = std::make_pair(FastVector<Key>(n), FastVector<int>(n));
boost::copy(map | boost::adaptors::map_keys, pair.first.begin());
boost::copy(map | boost::adaptors::map_values, pair.second.begin());
return pair;

View File

@ -32,9 +32,12 @@ namespace gtsam {
// Forward declares
class Values;
template<typename T> class ExpressionFactor;
namespace internal {
template<typename T> class ExecutionTrace;
template<typename T> class ExpressionNode;
template<typename T> class ExpressionFactor;
}
/**
* Expression class that supports automatic differentiation
@ -50,7 +53,7 @@ public:
private:
// Paul's trick shared pointer, polymorphic root of entire expression tree
boost::shared_ptr<ExpressionNode<T> > root_;
boost::shared_ptr<internal::ExpressionNode<T> > root_;
public:
@ -131,7 +134,7 @@ public:
const Expression<A3>& expression3);
/// Return root
const boost::shared_ptr<ExpressionNode<T> >& root() const;
const boost::shared_ptr<internal::ExpressionNode<T> >& root() const;
// Return size needed for memory buffer in traceExecution
size_t traceSize() const;
@ -170,7 +173,7 @@ private:
const FastVector<int>& dims, std::vector<Matrix>& H) const;
/// trace execution, very unsafe
T traceExecution(const Values& values, ExecutionTrace<T>& trace,
T traceExecution(const Values& values, internal::ExecutionTrace<T>& trace,
void* traceStorage) const;
/**

View File

@ -35,6 +35,7 @@ class ExpressionFactorBinaryTest;
// Forward declare for testing
namespace gtsam {
namespace internal {
template<typename T>
T & upAlign(T & value, unsigned requiredAlignment = TraceAlignment) {
@ -412,8 +413,8 @@ struct FunctionalNode {
/// Provide convenience access to Record storage and implement
/// the virtual function based interface of CallRecord using the CallRecordImplementor
struct Record: public internal::CallRecordImplementor<Record,
traits<T>::dimension>, public Base::Record {
struct Record: public CallRecordImplementor<Record, traits<T>::dimension>,
public Base::Record {
using Base::Record::print;
using Base::Record::startReverseAD4;
using Base::Record::reverseAD4;
@ -497,8 +498,8 @@ public:
// Inner Record Class
// The reason we inherit from JacobianTrace<T, A, N> is because we can then
// case to this unique signature to retrieve the value/trace at any level
struct Record: public internal::CallRecordImplementor<Record,
traits<T>::dimension>, JacobianTrace<T, A1, 1> {
struct Record: public CallRecordImplementor<Record, traits<T>::dimension>,
JacobianTrace<T, A1, 1> {
typedef T return_type;
typedef JacobianTrace<T, A1, 1> This;
@ -600,7 +601,7 @@ public:
private:
typedef typename Expression<T>::template BinaryFunction<A1,A2>::type Function;
typedef typename Expression<T>::template BinaryFunction<A1, A2>::type Function;
Function function_;
/// Constructor with a ternary function f, and three input arguments
@ -650,7 +651,7 @@ class TernaryExpression: public FunctionalNode<T, boost::mpl::vector<A1, A2, A3>
private:
typedef typename Expression<T>::template TernaryFunction<A1,A2,A3>::type Function;
typedef typename Expression<T>::template TernaryFunction<A1, A2, A3>::type Function;
Function function_;
/// Constructor with a ternary function f, and three input arguments
@ -693,4 +694,6 @@ public:
};
} // namespace gtsam
}
// namespace internal
}// namespace gtsam

View File

@ -88,7 +88,7 @@ void testFactorJacobians(TestResult& result_, const std::string& name_,
// Check cast result and then equality
CHECK(actual);
EXPECT( assert_equal(expected, *actual, tolerance));
EXPECT(assert_equal(expected, *actual, tolerance));
}
}
@ -112,7 +112,7 @@ void testExpressionJacobians(TestResult& result_, const std::string& name_,
expression.value(values), expression);
testFactorJacobians(result_, name_, f, values, nd_step, tolerance);
}
}
} // namespace internal
} // namespace gtsam
/// \brief Check the Jacobians produced by an expression against finite differences.

View File

@ -32,7 +32,7 @@ static const int Cols = 3;
int dynamicIfAboveMax(int i){
if(i > CallRecordMaxVirtualStaticRows){
if(i > internal::CallRecordMaxVirtualStaticRows){
return Eigen::Dynamic;
}
else return i;

View File

@ -27,7 +27,7 @@ using namespace gtsam;
/* ************************************************************************* */
// Constant
TEST(ExecutionTrace, construct) {
ExecutionTrace<Point2> trace;
internal::ExecutionTrace<Point2> trace;
}
/* ************************************************************************* */

View File

@ -165,7 +165,7 @@ TEST(Expression, BinaryDimensions) {
/* ************************************************************************* */
// dimensions
TEST(Expression, BinaryTraceSize) {
typedef BinaryExpression<Point3, Pose3, Point3> Binary;
typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary;
size_t expectedTraceSize = sizeof(Binary::Record);
EXPECT_LONGS_EQUAL(expectedTraceSize, binary::p_cam.traceSize());
}
@ -196,9 +196,9 @@ TEST(Expression, TreeDimensions) {
/* ************************************************************************* */
// TraceSize
TEST(Expression, TreeTraceSize) {
typedef UnaryExpression<Point2, Point3> Unary;
typedef BinaryExpression<Point3, Pose3, Point3> Binary1;
typedef BinaryExpression<Point2, Point2, Cal3_S2> Binary2;
typedef internal::UnaryExpression<Point2, Point3> Unary;
typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary1;
typedef internal::BinaryExpression<Point2, Point2, Cal3_S2> Binary2;
size_t expectedTraceSize = sizeof(Unary::Record) + sizeof(Binary1::Record)
+ sizeof(Binary2::Record);
EXPECT_LONGS_EQUAL(expectedTraceSize, tree::uv_hat.traceSize());

View File

@ -169,7 +169,7 @@ static Point2 myUncal(const Cal3_S2& K, const Point2& p,
// Binary(Leaf,Leaf)
TEST(ExpressionFactor, Binary) {
typedef BinaryExpression<Point2, Cal3_S2, Point2> Binary;
typedef internal::BinaryExpression<Point2, Cal3_S2, Point2> Binary;
Cal3_S2_ K_(1);
Point2_ p_(2);
@ -184,10 +184,10 @@ TEST(ExpressionFactor, Binary) {
EXPECT_LONGS_EQUAL(8, sizeof(double));
EXPECT_LONGS_EQUAL(16, sizeof(Point2));
EXPECT_LONGS_EQUAL(40, sizeof(Cal3_S2));
EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace<Point2>));
EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace<Cal3_S2>));
EXPECT_LONGS_EQUAL(2*5*8, sizeof(Jacobian<Point2,Cal3_S2>::type));
EXPECT_LONGS_EQUAL(2*2*8, sizeof(Jacobian<Point2,Point2>::type));
EXPECT_LONGS_EQUAL(16, sizeof(internal::ExecutionTrace<Point2>));
EXPECT_LONGS_EQUAL(16, sizeof(internal::ExecutionTrace<Cal3_S2>));
EXPECT_LONGS_EQUAL(2*5*8, sizeof(internal::Jacobian<Point2,Cal3_S2>::type));
EXPECT_LONGS_EQUAL(2*2*8, sizeof(internal::Jacobian<Point2,Point2>::type));
size_t expectedRecordSize = 16 + 16 + 40 + 2 * 16 + 80 + 32;
EXPECT_LONGS_EQUAL(expectedRecordSize + 8, sizeof(Binary::Record));
@ -197,8 +197,8 @@ TEST(ExpressionFactor, Binary) {
EXPECT_LONGS_EQUAL(expectedRecordSize + 8, size);
// Use Variable Length Array, allocated on stack by gcc
// Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla
ExecutionTraceStorage traceStorage[size];
ExecutionTrace<Point2> trace;
internal::ExecutionTraceStorage traceStorage[size];
internal::ExecutionTrace<Point2> trace;
Point2 value = binary.traceExecution(values, trace, traceStorage);
EXPECT(assert_equal(Point2(),value, 1e-9));
// trace.print();
@ -250,8 +250,8 @@ TEST(ExpressionFactor, Shallow) {
LONGS_EQUAL(3,dims[1]);
// traceExecution of shallow tree
typedef UnaryExpression<Point2, Point3> Unary;
typedef BinaryExpression<Point3, Pose3, Point3> Binary;
typedef internal::UnaryExpression<Point2, Point3> Unary;
typedef internal::BinaryExpression<Point3, Pose3, Point3> Binary;
size_t expectedTraceSize = sizeof(Unary::Record) + sizeof(Binary::Record);
EXPECT_LONGS_EQUAL(112, sizeof(Unary::Record));
#ifdef GTSAM_USE_QUATERNIONS
@ -264,8 +264,8 @@ TEST(ExpressionFactor, Shallow) {
size_t size = expression.traceSize();
CHECK(size);
EXPECT_LONGS_EQUAL(expectedTraceSize, size);
ExecutionTraceStorage traceStorage[size];
ExecutionTrace<Point2> trace;
internal::ExecutionTraceStorage traceStorage[size];
internal::ExecutionTrace<Point2> trace;
Point2 value = expression.traceExecution(values, trace, traceStorage);
EXPECT(assert_equal(Point2(),value, 1e-9));
// trace.print();

View File

@ -26,6 +26,7 @@
using namespace std;
using namespace gtsam;
using namespace gtsam::internal;
/* ************************************************************************* */
namespace mpl = boost::mpl;