Fixed a number of clang warnings

release/4.3a0
Richard Roberts 2014-02-23 18:53:48 -05:00
parent fdd891c7c9
commit 1770f44ad9
5 changed files with 94 additions and 91 deletions

View File

@ -160,7 +160,7 @@ macro(gtsamAddTestsGlob_impl groupName globPatterns excludedFiles linkLibraries)
# Only have a main function in one script - use preprocessor # Only have a main function in one script - use preprocessor
set(rest_script_srcs ${script_srcs}) set(rest_script_srcs ${script_srcs})
list(REMOVE_AT rest_script_srcs 0) list(REMOVE_AT rest_script_srcs 0)
set_property(SOURCE ${rest_script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "main=static no_main") set_property(SOURCE ${rest_script_srcs} APPEND PROPERTY COMPILE_DEFINITIONS "main=inline no_main")
# Add target dependencies # Add target dependencies
add_test(NAME ${target_name} COMMAND ${target_name}) add_test(NAME ${target_name} COMMAND ${target_name})

View File

@ -150,10 +150,8 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::update(const NonlinearFacto
if(removeFactorIndices){ if(removeFactorIndices){
if(debug){ if(debug){
BOOST_FOREACH(size_t slot, *removeFactorIndices) {
std::cout << "ConcurrentBatchFilter::update removeFactorIndices " << std::endl; std::cout << "ConcurrentBatchFilter::update removeFactorIndices " << std::endl;
} }
}
removeFactors(*removeFactorIndices); removeFactors(*removeFactorIndices);
} }

View File

@ -83,14 +83,13 @@ namespace simulated2D {
} }
}; };
namespace {
/// Prior on a single pose /// Prior on a single pose
inline Point2 prior(const Point2& x) { inline Point2 prior(const Point2& x) {
return x; return x;
} }
/// Prior on a single pose, optionally returns derivative /// Prior on a single pose, optionally returns derivative
Point2 prior(const Point2& x, boost::optional<Matrix&> H = boost::none) { inline Point2 prior(const Point2& x, boost::optional<Matrix&> H = boost::none) {
if (H) *H = gtsam::eye(2); if (H) *H = gtsam::eye(2);
return x; return x;
} }
@ -101,7 +100,7 @@ namespace simulated2D {
} }
/// odometry between two poses, optionally returns derivative /// odometry between two poses, optionally returns derivative
Point2 odo(const Point2& x1, const Point2& x2, boost::optional<Matrix&> H1 = inline Point2 odo(const Point2& x1, const Point2& x2, boost::optional<Matrix&> H1 =
boost::none, boost::optional<Matrix&> H2 = boost::none) { boost::none, boost::optional<Matrix&> H2 = boost::none) {
if (H1) *H1 = -gtsam::eye(2); if (H1) *H1 = -gtsam::eye(2);
if (H2) *H2 = gtsam::eye(2); if (H2) *H2 = gtsam::eye(2);
@ -114,13 +113,12 @@ namespace simulated2D {
} }
/// measurement between landmark and pose, optionally returns derivative /// measurement between landmark and pose, optionally returns derivative
Point2 mea(const Point2& x, const Point2& l, boost::optional<Matrix&> H1 = inline Point2 mea(const Point2& x, const Point2& l, boost::optional<Matrix&> H1 =
boost::none, boost::optional<Matrix&> H2 = boost::none) { boost::none, boost::optional<Matrix&> H2 = boost::none) {
if (H1) *H1 = -gtsam::eye(2); if (H1) *H1 = -gtsam::eye(2);
if (H2) *H2 = gtsam::eye(2); if (H2) *H2 = gtsam::eye(2);
return l - x; return l - x;
} }
}
/** /**
* Unary factor encoding a soft prior on a vector * Unary factor encoding a soft prior on a vector

View File

@ -31,68 +31,67 @@
namespace gtsam { namespace gtsam {
namespace example { namespace example {
namespace {
/** /**
* Create small example for non-linear factor graph * Create small example for non-linear factor graph
*/ */
boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph(); // inline boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph();
NonlinearFactorGraph createNonlinearFactorGraph(); // inline NonlinearFactorGraph createNonlinearFactorGraph();
/** /**
* Create values structure to go with it * Create values structure to go with it
* The ground truth values structure for the example above * The ground truth values structure for the example above
*/ */
Values createValues(); // inline Values createValues();
/** Vector Values equivalent */ /** Vector Values equivalent */
VectorValues createVectorValues(); // inline VectorValues createVectorValues();
/** /**
* create a noisy values structure for a nonlinear factor graph * create a noisy values structure for a nonlinear factor graph
*/ */
boost::shared_ptr<const Values> sharedNoisyValues(); // inline boost::shared_ptr<const Values> sharedNoisyValues();
Values createNoisyValues(); // inline Values createNoisyValues();
/** /**
* Zero delta config * Zero delta config
*/ */
VectorValues createZeroDelta(); // inline VectorValues createZeroDelta();
/** /**
* Delta config that, when added to noisyValues, returns the ground truth * Delta config that, when added to noisyValues, returns the ground truth
*/ */
VectorValues createCorrectDelta(); // inline VectorValues createCorrectDelta();
/** /**
* create a linear factor graph * create a linear factor graph
* The non-linear graph above evaluated at NoisyValues * The non-linear graph above evaluated at NoisyValues
*/ */
GaussianFactorGraph createGaussianFactorGraph(); // inline GaussianFactorGraph createGaussianFactorGraph();
/** /**
* create small Chordal Bayes Net x <- y * create small Chordal Bayes Net x <- y
*/ */
GaussianBayesNet createSmallGaussianBayesNet(); // inline GaussianBayesNet createSmallGaussianBayesNet();
/** /**
* Create really non-linear factor graph (cos/sin) * Create really non-linear factor graph (cos/sin)
*/ */
boost::shared_ptr<const NonlinearFactorGraph> // inline boost::shared_ptr<const NonlinearFactorGraph>
sharedReallyNonlinearFactorGraph(); //sharedReallyNonlinearFactorGraph();
NonlinearFactorGraph createReallyNonlinearFactorGraph(); // inline NonlinearFactorGraph createReallyNonlinearFactorGraph();
/** /**
* Create a full nonlinear smoother * Create a full nonlinear smoother
* @param T number of time-steps * @param T number of time-steps
*/ */
std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T); // inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T);
/** /**
* Create a Kalman smoother by linearizing a non-linear factor graph * Create a Kalman smoother by linearizing a non-linear factor graph
* @param T number of time-steps * @param T number of time-steps
*/ */
GaussianFactorGraph createSmoother(int T); // inline GaussianFactorGraph createSmoother(int T);
/* ******************************************************* */ /* ******************************************************* */
// Linear Constrained Examples // Linear Constrained Examples
@ -102,22 +101,22 @@ GaussianFactorGraph createSmoother(int T);
* Creates a simple constrained graph with one linear factor and * Creates a simple constrained graph with one linear factor and
* one binary equality constraint that sets x = y * one binary equality constraint that sets x = y
*/ */
GaussianFactorGraph createSimpleConstraintGraph(); // inline GaussianFactorGraph createSimpleConstraintGraph();
VectorValues createSimpleConstraintValues(); // inline VectorValues createSimpleConstraintValues();
/** /**
* Creates a simple constrained graph with one linear factor and * Creates a simple constrained graph with one linear factor and
* one binary constraint. * one binary constraint.
*/ */
GaussianFactorGraph createSingleConstraintGraph(); // inline GaussianFactorGraph createSingleConstraintGraph();
VectorValues createSingleConstraintValues(); // inline VectorValues createSingleConstraintValues();
/** /**
* Creates a constrained graph with a linear factor and two * Creates a constrained graph with a linear factor and two
* binary constraints that share a node * binary constraints that share a node
*/ */
GaussianFactorGraph createMultiConstraintGraph(); // inline GaussianFactorGraph createMultiConstraintGraph();
VectorValues createMultiConstraintValues(); // inline VectorValues createMultiConstraintValues();
/* ******************************************************* */ /* ******************************************************* */
// Planar graph with easy subtree for SubgraphPreconditioner // Planar graph with easy subtree for SubgraphPreconditioner
@ -132,14 +131,14 @@ VectorValues createMultiConstraintValues();
* -x11-x21-x31 * -x11-x21-x31
* with x11 clamped at (1,1), and others related by 2D odometry. * with x11 clamped at (1,1), and others related by 2D odometry.
*/ */
boost::tuple<GaussianFactorGraph, VectorValues> planarGraph(size_t N); // inline boost::tuple<GaussianFactorGraph, VectorValues> planarGraph(size_t N);
/* /*
* Create canonical ordering for planar graph that also works for tree * Create canonical ordering for planar graph that also works for tree
* With x11 the root, e.g. for N=3 * With x11 the root, e.g. for N=3
* x33 x23 x13 x32 x22 x12 x31 x21 x11 * x33 x23 x13 x32 x22 x12 x31 x21 x11
*/ */
Ordering planarOrdering(size_t N); // inline Ordering planarOrdering(size_t N);
/* /*
* Split graph into tree and loop closing constraints, e.g., with N=3 * Split graph into tree and loop closing constraints, e.g., with N=3
@ -149,8 +148,8 @@ Ordering planarOrdering(size_t N);
* | * |
* -x11-x21-x31 * -x11-x21-x31
*/ */
std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree( // inline std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(
size_t N, const GaussianFactorGraph& original); // size_t N, const GaussianFactorGraph& original);
@ -172,7 +171,7 @@ static const Key _x_=0, _y_=1, _z_=2;
/* ************************************************************************* */ /* ************************************************************************* */
boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph() { inline boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph() {
using namespace impl; using namespace impl;
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
@ -204,12 +203,12 @@ boost::shared_ptr<const NonlinearFactorGraph> sharedNonlinearFactorGraph() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
NonlinearFactorGraph createNonlinearFactorGraph() { inline NonlinearFactorGraph createNonlinearFactorGraph() {
return *sharedNonlinearFactorGraph(); return *sharedNonlinearFactorGraph();
} }
/* ************************************************************************* */ /* ************************************************************************* */
Values createValues() { inline Values createValues() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
Values c; Values c;
@ -220,7 +219,7 @@ Values createValues() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createVectorValues() { inline VectorValues createVectorValues() {
using namespace impl; using namespace impl;
VectorValues c = boost::assign::pair_list_of<Key, Vector> VectorValues c = boost::assign::pair_list_of<Key, Vector>
(_l1_, (Vector(2) << 0.0, -1.0)) (_l1_, (Vector(2) << 0.0, -1.0))
@ -230,7 +229,7 @@ VectorValues createVectorValues() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
boost::shared_ptr<const Values> sharedNoisyValues() { inline boost::shared_ptr<const Values> sharedNoisyValues() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
boost::shared_ptr<Values> c(new Values); boost::shared_ptr<Values> c(new Values);
@ -241,12 +240,12 @@ boost::shared_ptr<const Values> sharedNoisyValues() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
Values createNoisyValues() { inline Values createNoisyValues() {
return *sharedNoisyValues(); return *sharedNoisyValues();
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createCorrectDelta() { inline VectorValues createCorrectDelta() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
VectorValues c; VectorValues c;
@ -257,7 +256,7 @@ VectorValues createCorrectDelta() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createZeroDelta() { inline VectorValues createZeroDelta() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
VectorValues c; VectorValues c;
@ -268,7 +267,7 @@ VectorValues createZeroDelta() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph createGaussianFactorGraph() { inline GaussianFactorGraph createGaussianFactorGraph() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
// Create empty graph // Create empty graph
@ -295,7 +294,7 @@ GaussianFactorGraph createGaussianFactorGraph() {
* 1 1 9 * 1 1 9
* 1 5 * 1 5
*/ */
GaussianBayesNet createSmallGaussianBayesNet() { inline GaussianBayesNet createSmallGaussianBayesNet() {
using namespace impl; using namespace impl;
Matrix R11 = (Matrix(1, 1) << 1.0), S12 = (Matrix(1, 1) << 1.0); Matrix R11 = (Matrix(1, 1) << 1.0), S12 = (Matrix(1, 1) << 1.0);
Matrix R22 = (Matrix(1, 1) << 1.0); Matrix R22 = (Matrix(1, 1) << 1.0);
@ -318,11 +317,11 @@ GaussianBayesNet createSmallGaussianBayesNet() {
/* ************************************************************************* */ /* ************************************************************************* */
namespace smallOptimize { namespace smallOptimize {
Point2 h(const Point2& v) { inline Point2 h(const Point2& v) {
return Point2(cos(v.x()), sin(v.y())); return Point2(cos(v.x()), sin(v.y()));
} }
Matrix H(const Point2& v) { inline Matrix H(const Point2& v) {
return (Matrix(2, 2) << return (Matrix(2, 2) <<
-sin(v.x()), 0.0, -sin(v.x()), 0.0,
0.0, cos(v.y())); 0.0, cos(v.y()));
@ -346,7 +345,7 @@ struct UnaryFactor: public gtsam::NoiseModelFactor1<Point2> {
} }
/* ************************************************************************* */ /* ************************************************************************* */
boost::shared_ptr<const NonlinearFactorGraph> sharedReallyNonlinearFactorGraph() { inline boost::shared_ptr<const NonlinearFactorGraph> sharedReallyNonlinearFactorGraph() {
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph); boost::shared_ptr<NonlinearFactorGraph> fg(new NonlinearFactorGraph);
@ -358,12 +357,12 @@ boost::shared_ptr<const NonlinearFactorGraph> sharedReallyNonlinearFactorGraph()
return fg; return fg;
} }
NonlinearFactorGraph createReallyNonlinearFactorGraph() { inline NonlinearFactorGraph createReallyNonlinearFactorGraph() {
return *sharedReallyNonlinearFactorGraph(); return *sharedReallyNonlinearFactorGraph();
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T) { inline std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T) {
using namespace impl; using namespace impl;
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
@ -397,7 +396,7 @@ std::pair<NonlinearFactorGraph, Values> createNonlinearSmoother(int T) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph createSmoother(int T) { inline GaussianFactorGraph createSmoother(int T) {
NonlinearFactorGraph nlfg; NonlinearFactorGraph nlfg;
Values poses; Values poses;
boost::tie(nlfg, poses) = createNonlinearSmoother(T); boost::tie(nlfg, poses) = createNonlinearSmoother(T);
@ -406,7 +405,7 @@ GaussianFactorGraph createSmoother(int T) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph createSimpleConstraintGraph() { inline GaussianFactorGraph createSimpleConstraintGraph() {
using namespace impl; using namespace impl;
// create unary factor // create unary factor
// prior on _x_, mean = [1,-1], sigma=0.1 // prior on _x_, mean = [1,-1], sigma=0.1
@ -435,7 +434,7 @@ GaussianFactorGraph createSimpleConstraintGraph() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createSimpleConstraintValues() { inline VectorValues createSimpleConstraintValues() {
using namespace impl; using namespace impl;
using symbol_shorthand::X; using symbol_shorthand::X;
using symbol_shorthand::L; using symbol_shorthand::L;
@ -447,7 +446,7 @@ VectorValues createSimpleConstraintValues() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph createSingleConstraintGraph() { inline GaussianFactorGraph createSingleConstraintGraph() {
using namespace impl; using namespace impl;
// create unary factor // create unary factor
// prior on _x_, mean = [1,-1], sigma=0.1 // prior on _x_, mean = [1,-1], sigma=0.1
@ -481,7 +480,7 @@ GaussianFactorGraph createSingleConstraintGraph() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createSingleConstraintValues() { inline VectorValues createSingleConstraintValues() {
using namespace impl; using namespace impl;
VectorValues config = boost::assign::pair_list_of<Key, Vector> VectorValues config = boost::assign::pair_list_of<Key, Vector>
(_x_, (Vector(2) << 1.0, -1.0)) (_x_, (Vector(2) << 1.0, -1.0))
@ -490,7 +489,7 @@ VectorValues createSingleConstraintValues() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
GaussianFactorGraph createMultiConstraintGraph() { inline GaussianFactorGraph createMultiConstraintGraph() {
using namespace impl; using namespace impl;
// unary factor 1 // unary factor 1
Matrix A = eye(2); Matrix A = eye(2);
@ -545,7 +544,7 @@ GaussianFactorGraph createMultiConstraintGraph() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createMultiConstraintValues() { inline VectorValues createMultiConstraintValues() {
using namespace impl; using namespace impl;
VectorValues config = boost::assign::pair_list_of<Key, Vector> VectorValues config = boost::assign::pair_list_of<Key, Vector>
(_x_, (Vector(2) << -2.0, 2.0)) (_x_, (Vector(2) << -2.0, 2.0))
@ -557,14 +556,14 @@ VectorValues createMultiConstraintValues() {
/* ************************************************************************* */ /* ************************************************************************* */
// Create key for simulated planar graph // Create key for simulated planar graph
namespace impl { namespace impl {
Symbol key(size_t x, size_t y) { inline Symbol key(size_t x, size_t y) {
using symbol_shorthand::X; using symbol_shorthand::X;
return X(1000*x+y); return X(1000*x+y);
} }
} // \namespace impl } // \namespace impl
/* ************************************************************************* */ /* ************************************************************************* */
boost::tuple<GaussianFactorGraph, VectorValues> planarGraph(size_t N) { inline boost::tuple<GaussianFactorGraph, VectorValues> planarGraph(size_t N) {
using namespace impl; using namespace impl;
// create empty graph // create empty graph
@ -606,7 +605,7 @@ boost::tuple<GaussianFactorGraph, VectorValues> planarGraph(size_t N) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
Ordering planarOrdering(size_t N) { inline Ordering planarOrdering(size_t N) {
Ordering ordering; Ordering ordering;
for (size_t y = N; y >= 1; y--) for (size_t y = N; y >= 1; y--)
for (size_t x = N; x >= 1; x--) for (size_t x = N; x >= 1; x--)
@ -615,7 +614,7 @@ Ordering planarOrdering(size_t N) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(size_t N, inline std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(size_t N,
const GaussianFactorGraph& original) { const GaussianFactorGraph& original) {
GaussianFactorGraph T, C; GaussianFactorGraph T, C;
@ -641,6 +640,5 @@ std::pair<GaussianFactorGraph, GaussianFactorGraph > splitOffPlanarTree(size_t N
/* ************************************************************************* */ /* ************************************************************************* */
} // anonymous namespace
} // \namespace example } // \namespace example
} // \namespace gtsam } // \namespace gtsam

View File

@ -323,6 +323,11 @@ void Module::parseMarkup(const std::string& data) {
Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>'); Rule include_p = str_p("#include") >> ch_p('<') >> (*(anychar_p - '>'))[push_back_a(includes)] >> ch_p('>');
#ifdef __clang__
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Wuninitialized"
#endif
Rule namespace_def_p = Rule namespace_def_p =
(str_p("namespace") (str_p("namespace")
>> namespace_name_p[push_back_a(namespaces)] >> namespace_name_p[push_back_a(namespaces)]
@ -331,6 +336,10 @@ void Module::parseMarkup(const std::string& data) {
>> ch_p('}')) >> ch_p('}'))
[pop_a(namespaces)]; [pop_a(namespaces)];
#ifdef __clang__
#pragma clang diagnostic pop
#endif
Rule forward_declaration_p = Rule forward_declaration_p =
!(str_p("virtual")[assign_a(fwDec.isVirtual, true)]) !(str_p("virtual")[assign_a(fwDec.isVirtual, true)])
>> str_p("class") >> str_p("class")