Move print methods to cpp files wherever possible

release/4.3a0
chrisbeall 2016-11-01 15:11:57 -04:00
parent 799c5d8bb9
commit efd966b45a
8 changed files with 70 additions and 24 deletions

View File

@ -26,9 +26,8 @@
#include <boost/pool/pool_alloc.hpp> #include <boost/pool/pool_alloc.hpp>
#include <cmath> #include <cmath>
#include <iosfwd>
#include <typeinfo> // operator typeid
#include <iostream> #include <iostream>
#include <typeinfo> // operator typeid
namespace gtsam { 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,7 +18,7 @@
#pragma once #pragma once
#include <gtsam/geometry/Cal3_S2.h> #include <gtsam/geometry/Cal3_S2.h>
#include <iostream> #include <iosfwd>
namespace gtsam { namespace gtsam {
@ -63,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

View File

@ -21,7 +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 <iosfwd> #include <iostream>
#define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options> #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options>

View File

@ -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);

View File

@ -24,7 +24,7 @@
#include <gtsam/base/Lie.h> #include <gtsam/base/Lie.h>
#include <cmath> #include <cmath>
#include <iostream> #include <iosfwd>
namespace gtsam { namespace gtsam {
@ -68,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);

View File

@ -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

View File

@ -21,7 +21,7 @@
#include <gtsam/geometry/Point3.h> #include <gtsam/geometry/Point3.h>
#include <cmath> #include <cmath>
#include <iostream> #include <iosfwd>
namespace gtsam { namespace gtsam {
@ -60,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 {