Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Override print methods #760

Merged
merged 2 commits into from
Apr 30, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions gtsam/discrete/DiscreteBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ namespace gtsam {
template<class DERIVEDCONDITIONAL>
DiscreteBayesNet(const FactorGraph<DERIVEDCONDITIONAL>& graph) : Base(graph) {}

/// Destructor
virtual ~DiscreteBayesNet() {}

/// @}

/// @name Testable
Expand Down
11 changes: 6 additions & 5 deletions gtsam/discrete/DiscreteFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,13 +74,14 @@ class GTSAM_EXPORT DiscreteFactor: public Factor {
/// @name Testable
/// @{

// equals
/// equals
virtual bool equals(const DiscreteFactor& lf, double tol = 1e-9) const = 0;

// print
virtual void print(const std::string& s = "DiscreteFactor\n",
const KeyFormatter& formatter = DefaultKeyFormatter) const {
Factor::print(s, formatter);
/// print
void print(
const std::string& s = "DiscreteFactor\n",
const KeyFormatter& formatter = DefaultKeyFormatter) const override {
Base::print(s, formatter);
}

/** Test whether the factor is empty */
Expand Down
8 changes: 6 additions & 2 deletions gtsam/discrete/DiscreteFactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,9 @@ public EliminateableFactorGraph<DiscreteFactorGraph> {
template<class DERIVEDFACTOR>
DiscreteFactorGraph(const FactorGraph<DERIVEDFACTOR>& graph) : Base(graph) {}

/// Destructor
virtual ~DiscreteFactorGraph() {}

/// @name Testable
/// @{

Expand Down Expand Up @@ -129,8 +132,9 @@ public EliminateableFactorGraph<DiscreteFactorGraph> {
double operator()(const DiscreteFactor::Values & values) const;

/// print
void print(const std::string& s = "DiscreteFactorGraph",
const KeyFormatter& formatter =DefaultKeyFormatter) const;
void print(
const std::string& s = "DiscreteFactorGraph",
const KeyFormatter& formatter = DefaultKeyFormatter) const override;

/** Solve the factor graph by performing variable elimination in COLAMD order using
* the dense elimination function specified in \c function,
Expand Down
7 changes: 6 additions & 1 deletion gtsam/geometry/CalibratedCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ class GTSAM_EXPORT PinholeBase {
bool equals(const PinholeBase &camera, double tol = 1e-9) const;

/// print
void print(const std::string& s = "PinholeBase") const;
virtual void print(const std::string& s = "PinholeBase") const;

/// @}
/// @name Standard Interface
Expand Down Expand Up @@ -324,6 +324,11 @@ class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
/// Return canonical coordinate
Vector localCoordinates(const CalibratedCamera& T2) const;

/// print
void print(const std::string& s = "CalibratedCamera") const override {
PinholeBase::print(s);
}

/// @deprecated
inline size_t dim() const {
return dimension;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholeCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ class PinholeCamera: public PinholeBaseK<Calibration> {
}

/// print
void print(const std::string& s = "PinholeCamera") const {
void print(const std::string& s = "PinholeCamera") const override {
Base::print(s);
K_.print(s + ".calibration");
}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholePose.h
Original file line number Diff line number Diff line change
Expand Up @@ -340,7 +340,7 @@ class PinholePose: public PinholeBaseK<CALIBRATION> {
}

/// print
void print(const std::string& s = "PinholePose") const {
void print(const std::string& s = "PinholePose") const override {
Base::print(s);
if (!K_)
std::cout << "s No calibration given" << std::endl;
Expand Down
22 changes: 13 additions & 9 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -986,7 +986,7 @@ class CalibratedCamera {
static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height);

// Testable
void print(string s = "") const;
void print(string s = "CalibratedCamera") const;
bool equals(const gtsam::CalibratedCamera& camera, double tol) const;

// Manifold
Expand Down Expand Up @@ -1163,8 +1163,9 @@ virtual class SymbolicFactor {

// From Factor
size_t size() const;
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void print(string s = "SymbolicFactor",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicFactor& other, double tol) const;
gtsam::KeyVector keys();
};
Expand All @@ -1177,8 +1178,9 @@ virtual class SymbolicFactorGraph {

// From FactorGraph
void push_back(gtsam::SymbolicFactor* factor);
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void print(string s = "SymbolicFactorGraph",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const;
size_t size() const;
bool exists(size_t idx) const;
Expand Down Expand Up @@ -1242,8 +1244,9 @@ class SymbolicBayesNet {
SymbolicBayesNet();
SymbolicBayesNet(const gtsam::SymbolicBayesNet& other);
// Testable
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void print(string s = "SymbolicBayesNet",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::SymbolicBayesNet& other, double tol) const;

// Standard interface
Expand Down Expand Up @@ -2097,8 +2100,9 @@ class NonlinearFactorGraph {
NonlinearFactorGraph(const gtsam::NonlinearFactorGraph& graph);

// FactorGraph
void print(string s = "", const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
void print(string s = "NonlinearFactorGraph: ",
const gtsam::KeyFormatter& keyFormatter =
gtsam::DefaultKeyFormatter) const;
bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const;
size_t size() const;
bool empty() const;
Expand Down
46 changes: 23 additions & 23 deletions gtsam/inference/BayesNet-inst.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,30 +26,30 @@

namespace gtsam {

/* ************************************************************************* */
template<class CONDITIONAL>
void BayesNet<CONDITIONAL>::print(const std::string& s, const KeyFormatter& formatter) const
{
Base::print(s, formatter);
}
/* ************************************************************************* */
template <class CONDITIONAL>
void BayesNet<CONDITIONAL>::print(
const std::string& s, const KeyFormatter& formatter) const {
Base::print(s, formatter);
}

/* ************************************************************************* */
template<class CONDITIONAL>
void BayesNet<CONDITIONAL>::saveGraph(const std::string &s, const KeyFormatter& keyFormatter) const
{
std::ofstream of(s.c_str());
of << "digraph G{\n";

for (auto conditional: boost::adaptors::reverse(*this)) {
typename CONDITIONAL::Frontals frontals = conditional->frontals();
Key me = frontals.front();
typename CONDITIONAL::Parents parents = conditional->parents();
for(Key p: parents)
of << keyFormatter(p) << "->" << keyFormatter(me) << std::endl;
}

of << "}";
of.close();
/* ************************************************************************* */
template <class CONDITIONAL>
void BayesNet<CONDITIONAL>::saveGraph(const std::string& s,
const KeyFormatter& keyFormatter) const {
std::ofstream of(s.c_str());
of << "digraph G{\n";

for (auto conditional : boost::adaptors::reverse(*this)) {
typename CONDITIONAL::Frontals frontals = conditional->frontals();
Key me = frontals.front();
typename CONDITIONAL::Parents parents = conditional->parents();
for (Key p : parents)
of << keyFormatter(p) << "->" << keyFormatter(me) << std::endl;
}

of << "}";
of.close();
}

} // namespace gtsam
16 changes: 9 additions & 7 deletions gtsam/inference/BayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,16 +57,18 @@ namespace gtsam {
/// @name Testable
/// @{

/** print out graph */
void print(const std::string& s = "BayesNet",
const KeyFormatter& formatter = DefaultKeyFormatter) const;
/** print out graph */
void print(
const std::string& s = "BayesNet",
const KeyFormatter& formatter = DefaultKeyFormatter) const override;

/// @}
/// @}

/// @name Standard Interface
/// @{
/// @name Standard Interface
/// @{

void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
void saveGraph(const std::string& s,
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
};

}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/inference/Factor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ namespace gtsam {

/* ************************************************************************* */
void Factor::printKeys(const std::string& s, const KeyFormatter& formatter) const {
std::cout << s << " ";
for(Key key: keys_) std::cout << " " << formatter(key);
std::cout << (s.empty() ? "" : s + " ");
for (Key key : keys_) std::cout << " " << formatter(key);
std::cout << std::endl;
}

Expand Down
8 changes: 6 additions & 2 deletions gtsam/inference/Factor.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,10 +135,14 @@ typedef FastSet<FactorIndex> FactorIndexSet;
/// @{

/// print
void print(const std::string& s = "Factor", const KeyFormatter& formatter = DefaultKeyFormatter) const;
virtual void print(
const std::string& s = "Factor",
const KeyFormatter& formatter = DefaultKeyFormatter) const;

/// print only keys
void printKeys(const std::string& s = "Factor", const KeyFormatter& formatter = DefaultKeyFormatter) const;
virtual void printKeys(
const std::string& s = "Factor",
const KeyFormatter& formatter = DefaultKeyFormatter) const;

protected:
/// check equality
Expand Down
2 changes: 1 addition & 1 deletion gtsam/inference/FactorGraph-inst.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace gtsam {
template <class FACTOR>
void FactorGraph<FACTOR>::print(const std::string& s,
const KeyFormatter& formatter) const {
std::cout << s << std::endl;
std::cout << (s.empty() ? "" : s + " ") << std::endl;
std::cout << "size: " << size() << std::endl;
for (size_t i = 0; i < factors_.size(); i++) {
std::stringstream ss;
Expand Down
6 changes: 3 additions & 3 deletions gtsam/inference/FactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,9 +285,9 @@ class FactorGraph {
/// @name Testable
/// @{

/** print out graph */
void print(const std::string& s = "FactorGraph",
const KeyFormatter& formatter = DefaultKeyFormatter) const;
/// print out graph
virtual void print(const std::string& s = "FactorGraph",
const KeyFormatter& formatter = DefaultKeyFormatter) const;

/** Check equality */
bool equals(const This& fg, double tol = 1e-9) const;
Expand Down
10 changes: 10 additions & 0 deletions gtsam/linear/GaussianBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ namespace gtsam {
template<class DERIVEDCONDITIONAL>
GaussianBayesNet(const FactorGraph<DERIVEDCONDITIONAL>& graph) : Base(graph) {}

/// Destructor
virtual ~GaussianBayesNet() {}

/// @}

/// @name Testable
Expand Down Expand Up @@ -177,6 +180,13 @@ namespace gtsam {
*/
VectorValues backSubstituteTranspose(const VectorValues& gx) const;

/// print graph
void print(
const std::string& s = "",
const KeyFormatter& formatter = DefaultKeyFormatter) const override {
Base::print(s, formatter);
}

/**
* @brief Save the GaussianBayesNet as an image. Requires `dot` to be
* installed.
Expand Down
7 changes: 5 additions & 2 deletions gtsam/linear/GaussianFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,11 @@ namespace gtsam {
virtual ~GaussianFactor() {}

// Implementing Testable interface
virtual void print(const std::string& s = "",
const KeyFormatter& formatter = DefaultKeyFormatter) const = 0;

/// print
void print(
const std::string& s = "",
const KeyFormatter& formatter = DefaultKeyFormatter) const override = 0;

/** Equals for testable */
virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const = 0;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/linear/Preconditioner.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,9 @@ struct GTSAM_EXPORT PreconditionerParameters {
inline Kernel kernel() const { return kernel_; }
inline Verbosity verbosity() const { return verbosity_; }

void print() const ;
void print() const;

virtual void print(std::ostream &os) const ;
virtual void print(std::ostream &os) const;

static Kernel kernelTranslator(const std::string &s);
static Verbosity verbosityTranslator(const std::string &s);
Expand Down
3 changes: 2 additions & 1 deletion gtsam/navigation/AttitudeFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ Vector AttitudeFactor::attitudeError(const Rot3& nRb,
//***************************************************************************
void Rot3AttitudeFactor::print(const string& s,
const KeyFormatter& keyFormatter) const {
cout << s << "Rot3AttitudeFactor on " << keyFormatter(this->key()) << "\n";
cout << (s.empty() ? "" : s + " ") << "Rot3AttitudeFactor on "
<< keyFormatter(this->key()) << "\n";
nZ_.print(" measured direction in nav frame: ");
bRef_.print(" reference direction in body frame: ");
this->noiseModel_->print(" noise model: ");
Expand Down
8 changes: 4 additions & 4 deletions gtsam/navigation/AttitudeFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,8 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactor1<Rot3>, public At
}

/** print */
void print(const std::string& s, const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;
void print(const std::string& s = "", const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;

/** equals */
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
Expand Down Expand Up @@ -188,8 +188,8 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactor1<Pose3>,
}

/** print */
void print(const std::string& s, const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;
void print(const std::string& s = "", const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;

/** equals */
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
Expand Down
3 changes: 2 additions & 1 deletion gtsam/navigation/GPSFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ namespace gtsam {

//***************************************************************************
void GPSFactor::print(const string& s, const KeyFormatter& keyFormatter) const {
cout << s << "GPSFactor on " << keyFormatter(key()) << "\n";
cout << (s.empty() ? "" : s + " ") << "GPSFactor on " << keyFormatter(key())
<< "\n";
cout << " GPS measurement: " << nT_ << "\n";
noiseModel_->print(" noise model: ");
}
Expand Down
8 changes: 4 additions & 4 deletions gtsam/navigation/GPSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ class GTSAM_EXPORT GPSFactor: public NoiseModelFactor1<Pose3> {
}

/// print
void print(const std::string& s, const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;
void print(const std::string& s = "", const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;

/// equals
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
Expand Down Expand Up @@ -143,8 +143,8 @@ class GTSAM_EXPORT GPSFactor2: public NoiseModelFactor1<NavState> {
}

/// print
void print(const std::string& s, const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;
void print(const std::string& s = "", const KeyFormatter& keyFormatter =
DefaultKeyFormatter) const override;

/// equals
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
Expand Down
Loading