Merged in bugfix/boost_1_61_0_support (pull request #276)

Fixes compile errors when using BOOST version 1.61.0
release/4.3a0
Chris Beall 2016-11-01 21:14:30 +00:00
commit a738529af9
21 changed files with 91 additions and 31 deletions

View File

@ -20,6 +20,7 @@
#include <boost/assign/list_of.hpp>
#include <map>
#include <iostream>
using namespace std;
using namespace gtsam;

View File

@ -26,7 +26,7 @@
#include <boost/pool/pool_alloc.hpp>
#include <cmath>
#include <iosfwd>
#include <iostream>
#include <typeinfo> // operator typeid
namespace gtsam {

View File

@ -32,6 +32,7 @@
#include <list>
#include <fstream>
#include <limits>
#include <iostream>
using namespace std;

View File

@ -21,6 +21,7 @@
#include <stdexcept>
#include <cstdarg>
#include <limits>
#include <iostream>
#include <fstream>
#include <sstream>
#include <iomanip>

View File

@ -19,6 +19,7 @@
#include <gtsam/dllexport.h>
#include <gtsam/base/VectorSpace.h>
#include <iostream>
namespace gtsam {

View File

@ -22,6 +22,7 @@
#include <gtsam/base/Testable.h>
#include <gtsam/base/OptionalJacobian.h>
#include <boost/concept/assert.hpp>
#include <iostream>
namespace gtsam {

View File

@ -0,0 +1,39 @@
/* ----------------------------------------------------------------------------
* 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 Cal3_S2Stereo.cpp
* @brief The most common 5DOF 3D->2D calibration + Stereo baseline
* @author Chris Beall
*/
#include <gtsam/geometry/Cal3_S2Stereo.h>
#include <iostream>
namespace gtsam {
using namespace std;
/* ************************************************************************* */
void Cal3_S2Stereo::print(const std::string& s) const {
K_.print(s+"K: ");
std::cout << s << "Baseline: " << b_ << std::endl;
}
/* ************************************************************************* */
bool Cal3_S2Stereo::equals(const Cal3_S2Stereo& other, double tol) const {
if (fabs(b_ - other.b_) > tol) return false;
return K_.equals(other.K_,tol);
}
/* ************************************************************************* */
} // namespace gtsam

View File

@ -18,6 +18,7 @@
#pragma once
#include <gtsam/geometry/Cal3_S2.h>
#include <iosfwd>
namespace gtsam {
@ -62,16 +63,10 @@ namespace gtsam {
/// @name Testable
/// @{
void print(const std::string& s = "") const {
K_.print(s+"K: ");
std::cout << s << "Baseline: " << b_ << std::endl;
}
void print(const std::string& s = "") const;
/// Check if equal up to specified tolerance
bool equals(const Cal3_S2Stereo& other, double tol = 10e-9) const {
if (fabs(b_ - other.b_) > tol) return false;
return K_.equals(other.K_,tol);
}
bool equals(const Cal3_S2Stereo& other, double tol = 10e-9) const;
/// @}
/// @name Standard Interface

View File

@ -17,6 +17,7 @@
#include <gtsam/geometry/Point2.h>
#include <cmath>
#include <iostream>
using namespace std;

View File

@ -16,6 +16,7 @@
#include <gtsam/geometry/Point3.h>
#include <cmath>
#include <iostream>
using namespace std;

View File

@ -21,6 +21,7 @@
#include <gtsam/base/concepts.h>
#include <gtsam/geometry/SO3.h> // Logmap/Expmap derivatives
#include <limits>
#include <iostream>
#define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options>

View File

@ -17,6 +17,7 @@
*/
#include <gtsam/geometry/Rot2.h>
#include <iostream>
using namespace std;

View File

@ -22,6 +22,7 @@
#include <gtsam/base/concepts.h>
#include <cmath>
#include <limits>
#include <iostream>
namespace gtsam {
@ -116,6 +117,12 @@ SO3 SO3::AxisAngle(const Vector3& axis, double theta) {
return so3::ExpmapFunctor(axis, theta).expmap();
}
/* ************************************************************************* */
void SO3::print(const std::string& s) const {
std::cout << s << *this << std::endl;
}
/* ************************************************************************* */
SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) {
if (H) {
so3::DexpFunctor impl(omega);

View File

@ -24,6 +24,7 @@
#include <gtsam/base/Lie.h>
#include <cmath>
#include <iosfwd>
namespace gtsam {
@ -67,9 +68,7 @@ public:
/// @name Testable
/// @{
void print(const std::string& s) const {
std::cout << s << *this << std::endl;
}
void print(const std::string& s) const;
bool equals(const SO3 & R, double tol) const {
return equal_with_abs_tol(*this, R, tol);

View File

@ -219,15 +219,13 @@ FastVector<JacobianFactor::shared_ptr> _convertOrCastToJacobians(
/* ************************************************************************* */
JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
boost::optional<const Ordering&> ordering,
boost::optional<const VariableSlots&> variableSlots) {
boost::optional<const VariableSlots&> p_variableSlots) {
gttic(JacobianFactor_combine_constructor);
// Compute VariableSlots if one was not provided
boost::optional<VariableSlots> computedVariableSlots;
if (!variableSlots) {
computedVariableSlots = VariableSlots(graph);
variableSlots = computedVariableSlots; // Binds reference, does not copy VariableSlots
}
// Binds reference, does not copy VariableSlots
const VariableSlots & variableSlots =
p_variableSlots ? p_variableSlots.get() : VariableSlots(graph);
// Cast or convert to Jacobians
FastVector<JacobianFactor::shared_ptr> jacobians = _convertOrCastToJacobians(
@ -238,15 +236,15 @@ JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
// 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
// be added after all of the ordered variables.
FastVector<VariableSlots::const_iterator> orderedSlots;
orderedSlots.reserve(variableSlots->size());
orderedSlots.reserve(variableSlots.size());
if (ordering) {
// If an ordering is provided, arrange the slots first that ordering
FastList<VariableSlots::const_iterator> unorderedSlots;
size_t nOrderingSlotsUsed = 0;
orderedSlots.resize(ordering->size());
FastMap<Key, size_t> inverseOrdering = ordering->invert();
for (VariableSlots::const_iterator item = variableSlots->begin();
item != variableSlots->end(); ++item) {
for (VariableSlots::const_iterator item = variableSlots.begin();
item != variableSlots.end(); ++item) {
FastMap<Key, size_t>::const_iterator orderingPosition =
inverseOrdering.find(item->first);
if (orderingPosition == inverseOrdering.end()) {
@ -267,8 +265,8 @@ JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
} else {
// If no ordering is provided, arrange the slots as they were, which will be sorted
// numerically since VariableSlots uses a map sorting on Key.
for (VariableSlots::const_iterator item = variableSlots->begin();
item != variableSlots->end(); ++item)
for (VariableSlots::const_iterator item = variableSlots.begin();
item != variableSlots.end(); ++item)
orderedSlots.push_back(item);
}
gttoc(Order_slots);

View File

@ -154,7 +154,7 @@ namespace gtsam {
explicit JacobianFactor(
const GaussianFactorGraph& graph,
boost::optional<const Ordering&> ordering = boost::none,
boost::optional<const VariableSlots&> variableSlots = boost::none);
boost::optional<const VariableSlots&> p_variableSlots = boost::none);
/** Virtual destructor */
virtual ~JacobianFactor() {}

View File

@ -23,6 +23,7 @@
#include <gtsam/nonlinear/NonlinearOptimizer.h>
#include <gtsam/nonlinear/LevenbergMarquardtParams.h>
#include <gtsam/linear/VectorValues.h>
#include <boost/date_time/posix_time/posix_time.hpp>
class NonlinearOptimizerMoreOptimizationTest;

View File

@ -25,6 +25,7 @@
#include <boost/type_traits/aligned_storage.hpp>
#include <Eigen/Core>
#include <iostream>
namespace gtsam {
namespace internal {

View File

@ -23,6 +23,7 @@
#include <gtsam/base/Testable.h>
#include <CppUnitLite/TestHarness.h>
#include <iostream>
using namespace std;
using namespace gtsam;

View File

@ -18,7 +18,21 @@
*/
#include <gtsam_unstable/geometry/Event.h>
#include <iostream>
namespace gtsam {
/* ************************************************************************* */
void Event::print(const std::string& s) const {
std::cout << s << "time = " << time_ << "location = " << location_.transpose();
}
/* ************************************************************************* */
bool Event::equals(const Event& other, double tol) const {
return std::abs(time_ - other.time_) < tol
&& traits<Point3>::Equals(location_, other.location_, tol);
}
/* ************************************************************************* */
} //\ namespace gtsam

View File

@ -21,6 +21,7 @@
#include <gtsam/geometry/Point3.h>
#include <cmath>
#include <iosfwd>
namespace gtsam {
@ -59,15 +60,10 @@ public:
}
/** print with optional string */
void print(const std::string& s = "") const {
std::cout << s << "time = " << time_ << "location = " << location_.transpose();
}
void print(const std::string& s = "") const;
/** equals with an tolerance */
bool equals(const Event& other, double tol = 1e-9) const {
return std::abs(time_ - other.time_) < tol
&& traits<Point3>::Equals(location_, other.location_, tol);
}
bool equals(const Event& other, double tol = 1e-9) const;
/// Updates a with tangent space delta
inline Event retract(const Vector4& v) const {