Merged in bugfix/boost_1_61_0_support (pull request #276)
Fixes compile errors when using BOOST version 1.61.0release/4.3a0
commit
a738529af9
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include <boost/assign/list_of.hpp>
|
#include <boost/assign/list_of.hpp>
|
||||||
#include <map>
|
#include <map>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#include <boost/pool/pool_alloc.hpp>
|
#include <boost/pool/pool_alloc.hpp>
|
||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <iosfwd>
|
#include <iostream>
|
||||||
#include <typeinfo> // operator typeid
|
#include <typeinfo> // operator typeid
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
|
@ -32,6 +32,7 @@
|
||||||
#include <list>
|
#include <list>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include <stdexcept>
|
#include <stdexcept>
|
||||||
#include <cstdarg>
|
#include <cstdarg>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
#include <iostream>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <sstream>
|
#include <sstream>
|
||||||
#include <iomanip>
|
#include <iomanip>
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#include <gtsam/dllexport.h>
|
#include <gtsam/dllexport.h>
|
||||||
#include <gtsam/base/VectorSpace.h>
|
#include <gtsam/base/VectorSpace.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
#include <gtsam/base/Testable.h>
|
#include <gtsam/base/Testable.h>
|
||||||
#include <gtsam/base/OptionalJacobian.h>
|
#include <gtsam/base/OptionalJacobian.h>
|
||||||
#include <boost/concept/assert.hpp>
|
#include <boost/concept/assert.hpp>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
|
|
@ -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
|
|
@ -18,6 +18,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/geometry/Cal3_S2.h>
|
#include <gtsam/geometry/Cal3_S2.h>
|
||||||
|
#include <iosfwd>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -62,16 +63,10 @@ namespace gtsam {
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
void print(const std::string& s = "") const {
|
void print(const std::string& s = "") const;
|
||||||
K_.print(s+"K: ");
|
|
||||||
std::cout << s << "Baseline: " << b_ << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Check if equal up to specified tolerance
|
/// Check if equal up to specified tolerance
|
||||||
bool equals(const Cal3_S2Stereo& other, double tol = 10e-9) const {
|
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);
|
|
||||||
}
|
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
/// @name Standard Interface
|
/// @name Standard Interface
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
|
|
||||||
#include <gtsam/geometry/Point3.h>
|
#include <gtsam/geometry/Point3.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#include <gtsam/base/concepts.h>
|
#include <gtsam/base/concepts.h>
|
||||||
#include <gtsam/geometry/SO3.h> // Logmap/Expmap derivatives
|
#include <gtsam/geometry/SO3.h> // Logmap/Expmap derivatives
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
#define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options>
|
#define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options>
|
||||||
|
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/geometry/Rot2.h>
|
#include <gtsam/geometry/Rot2.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
#include <gtsam/base/concepts.h>
|
#include <gtsam/base/concepts.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -116,6 +117,12 @@ SO3 SO3::AxisAngle(const Vector3& axis, double theta) {
|
||||||
return so3::ExpmapFunctor(axis, theta).expmap();
|
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) {
|
SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) {
|
||||||
if (H) {
|
if (H) {
|
||||||
so3::DexpFunctor impl(omega);
|
so3::DexpFunctor impl(omega);
|
||||||
|
|
|
@ -24,6 +24,7 @@
|
||||||
#include <gtsam/base/Lie.h>
|
#include <gtsam/base/Lie.h>
|
||||||
|
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <iosfwd>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -67,9 +68,7 @@ public:
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
void print(const std::string& s) const {
|
void print(const std::string& s) const;
|
||||||
std::cout << s << *this << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool equals(const SO3 & R, double tol) const {
|
bool equals(const SO3 & R, double tol) const {
|
||||||
return equal_with_abs_tol(*this, R, tol);
|
return equal_with_abs_tol(*this, R, tol);
|
||||||
|
|
|
@ -219,15 +219,13 @@ FastVector<JacobianFactor::shared_ptr> _convertOrCastToJacobians(
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
|
JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
|
||||||
boost::optional<const Ordering&> ordering,
|
boost::optional<const Ordering&> ordering,
|
||||||
boost::optional<const VariableSlots&> variableSlots) {
|
boost::optional<const VariableSlots&> p_variableSlots) {
|
||||||
gttic(JacobianFactor_combine_constructor);
|
gttic(JacobianFactor_combine_constructor);
|
||||||
|
|
||||||
// Compute VariableSlots if one was not provided
|
// Compute VariableSlots if one was not provided
|
||||||
boost::optional<VariableSlots> computedVariableSlots;
|
// Binds reference, does not copy VariableSlots
|
||||||
if (!variableSlots) {
|
const VariableSlots & variableSlots =
|
||||||
computedVariableSlots = VariableSlots(graph);
|
p_variableSlots ? p_variableSlots.get() : VariableSlots(graph);
|
||||||
variableSlots = computedVariableSlots; // Binds reference, does not copy VariableSlots
|
|
||||||
}
|
|
||||||
|
|
||||||
// Cast or convert to Jacobians
|
// Cast or convert to Jacobians
|
||||||
FastVector<JacobianFactor::shared_ptr> jacobians = _convertOrCastToJacobians(
|
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
|
// 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
|
||||||
// be added after all of the ordered variables.
|
// be added after all of the ordered variables.
|
||||||
FastVector<VariableSlots::const_iterator> orderedSlots;
|
FastVector<VariableSlots::const_iterator> orderedSlots;
|
||||||
orderedSlots.reserve(variableSlots->size());
|
orderedSlots.reserve(variableSlots.size());
|
||||||
if (ordering) {
|
if (ordering) {
|
||||||
// If an ordering is provided, arrange the slots first that ordering
|
// If an ordering is provided, arrange the slots first that ordering
|
||||||
FastList<VariableSlots::const_iterator> unorderedSlots;
|
FastList<VariableSlots::const_iterator> unorderedSlots;
|
||||||
size_t nOrderingSlotsUsed = 0;
|
size_t nOrderingSlotsUsed = 0;
|
||||||
orderedSlots.resize(ordering->size());
|
orderedSlots.resize(ordering->size());
|
||||||
FastMap<Key, size_t> inverseOrdering = ordering->invert();
|
FastMap<Key, size_t> inverseOrdering = ordering->invert();
|
||||||
for (VariableSlots::const_iterator item = variableSlots->begin();
|
for (VariableSlots::const_iterator item = variableSlots.begin();
|
||||||
item != variableSlots->end(); ++item) {
|
item != variableSlots.end(); ++item) {
|
||||||
FastMap<Key, size_t>::const_iterator orderingPosition =
|
FastMap<Key, size_t>::const_iterator orderingPosition =
|
||||||
inverseOrdering.find(item->first);
|
inverseOrdering.find(item->first);
|
||||||
if (orderingPosition == inverseOrdering.end()) {
|
if (orderingPosition == inverseOrdering.end()) {
|
||||||
|
@ -267,8 +265,8 @@ JacobianFactor::JacobianFactor(const GaussianFactorGraph& graph,
|
||||||
} else {
|
} else {
|
||||||
// If no ordering is provided, arrange the slots as they were, which will be sorted
|
// If no ordering is provided, arrange the slots as they were, which will be sorted
|
||||||
// numerically since VariableSlots uses a map sorting on Key.
|
// numerically since VariableSlots uses a map sorting on Key.
|
||||||
for (VariableSlots::const_iterator item = variableSlots->begin();
|
for (VariableSlots::const_iterator item = variableSlots.begin();
|
||||||
item != variableSlots->end(); ++item)
|
item != variableSlots.end(); ++item)
|
||||||
orderedSlots.push_back(item);
|
orderedSlots.push_back(item);
|
||||||
}
|
}
|
||||||
gttoc(Order_slots);
|
gttoc(Order_slots);
|
||||||
|
|
|
@ -154,7 +154,7 @@ namespace gtsam {
|
||||||
explicit JacobianFactor(
|
explicit JacobianFactor(
|
||||||
const GaussianFactorGraph& graph,
|
const GaussianFactorGraph& graph,
|
||||||
boost::optional<const Ordering&> ordering = boost::none,
|
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 destructor */
|
||||||
virtual ~JacobianFactor() {}
|
virtual ~JacobianFactor() {}
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
#include <gtsam/nonlinear/NonlinearOptimizer.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtParams.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtParams.h>
|
||||||
#include <gtsam/linear/VectorValues.h>
|
#include <gtsam/linear/VectorValues.h>
|
||||||
|
#include <boost/date_time/posix_time/posix_time.hpp>
|
||||||
|
|
||||||
class NonlinearOptimizerMoreOptimizationTest;
|
class NonlinearOptimizerMoreOptimizationTest;
|
||||||
|
|
||||||
|
|
|
@ -25,6 +25,7 @@
|
||||||
#include <boost/type_traits/aligned_storage.hpp>
|
#include <boost/type_traits/aligned_storage.hpp>
|
||||||
|
|
||||||
#include <Eigen/Core>
|
#include <Eigen/Core>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
namespace internal {
|
namespace internal {
|
||||||
|
|
|
@ -23,6 +23,7 @@
|
||||||
#include <gtsam/base/Testable.h>
|
#include <gtsam/base/Testable.h>
|
||||||
|
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
|
|
@ -18,7 +18,21 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/Event.h>
|
#include <gtsam_unstable/geometry/Event.h>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
namespace gtsam {
|
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
|
} //\ namespace gtsam
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
|
|
||||||
#include <gtsam/geometry/Point3.h>
|
#include <gtsam/geometry/Point3.h>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
|
#include <iosfwd>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
|
@ -59,15 +60,10 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/** print with optional string */
|
/** print with optional string */
|
||||||
void print(const std::string& s = "") const {
|
void print(const std::string& s = "") const;
|
||||||
std::cout << s << "time = " << time_ << "location = " << location_.transpose();
|
|
||||||
}
|
|
||||||
|
|
||||||
/** equals with an tolerance */
|
/** equals with an tolerance */
|
||||||
bool equals(const Event& other, double tol = 1e-9) const {
|
bool equals(const Event& other, double tol = 1e-9) const;
|
||||||
return std::abs(time_ - other.time_) < tol
|
|
||||||
&& traits<Point3>::Equals(location_, other.location_, tol);
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Updates a with tangent space delta
|
/// Updates a with tangent space delta
|
||||||
inline Event retract(const Vector4& v) const {
|
inline Event retract(const Vector4& v) const {
|
||||||
|
|
Loading…
Reference in New Issue