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

Improvements in linear #1091

Merged
merged 10 commits into from
Feb 8, 2022
55 changes: 40 additions & 15 deletions gtsam/linear/GaussianBayesNet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@
using namespace std;
using namespace gtsam;

// In Wrappers we have no access to this so have a default ready
static std::mt19937_64 kRandomNumberGenerator(42);

namespace gtsam {

// Instantiate base class
Expand All @@ -37,28 +40,50 @@ namespace gtsam {
return Base::equals(bn, tol);
}

/* ************************************************************************* */
VectorValues GaussianBayesNet::optimize() const
{
VectorValues soln; // no missing variables -> just create an empty vector
return optimize(soln);
/* ************************************************************************ */
VectorValues GaussianBayesNet::optimize() const {
VectorValues solution; // no missing variables -> create an empty vector
return optimize(solution);
}

/* ************************************************************************* */
VectorValues GaussianBayesNet::optimize(
const VectorValues& solutionForMissing) const {
VectorValues soln(solutionForMissing); // possibly empty
VectorValues GaussianBayesNet::optimize(VectorValues solution) const {
// (R*x)./sigmas = y by solving x=inv(R)*(y.*sigmas)
/** solve each node in turn in topological sort order (parents first)*/
for (auto cg: boost::adaptors::reverse(*this)) {
// solve each node in reverse topological sort order (parents first)
for (auto cg : boost::adaptors::reverse(*this)) {
// i^th part of R*x=y, x=inv(R)*y
// (Rii*xi + R_i*x(i+1:))./si = yi <-> xi = inv(Rii)*(yi.*si - R_i*x(i+1:))
soln.insert(cg->solve(soln));
// (Rii*xi + R_i*x(i+1:))./si = yi =>
// xi = inv(Rii)*(yi.*si - R_i*x(i+1:))
solution.insert(cg->solve(solution));
}
return soln;
return solution;
}

/* ************************************************************************* */
/* ************************************************************************ */
VectorValues GaussianBayesNet::sample(std::mt19937_64* rng) const {
VectorValues result; // no missing variables -> create an empty vector
return sample(result, rng);
}

VectorValues GaussianBayesNet::sample(VectorValues result,
std::mt19937_64* rng) const {
// sample each node in reverse topological sort order (parents first)
for (auto cg : boost::adaptors::reverse(*this)) {
const VectorValues sampled = cg->sample(result, rng);
result.insert(sampled);
}
return result;
}

/* ************************************************************************ */
VectorValues GaussianBayesNet::sample() const {
return sample(&kRandomNumberGenerator);
}

VectorValues GaussianBayesNet::sample(VectorValues given) const {
return sample(given, &kRandomNumberGenerator);
}

/* ************************************************************************ */
VectorValues GaussianBayesNet::optimizeGradientSearch() const
{
gttic(GaussianBayesTree_optimizeGradientSearch);
Expand Down
30 changes: 27 additions & 3 deletions gtsam/linear/GaussianBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,11 +88,35 @@ namespace gtsam {
/// @name Standard Interface
/// @{

/// Solve the GaussianBayesNet, i.e. return \f$ x = R^{-1}*d \f$, by back-substitution
/// Solve the GaussianBayesNet, i.e. return \f$ x = R^{-1}*d \f$, by
/// back-substitution
VectorValues optimize() const;

/// Version of optimize for incomplete BayesNet, needs solution for missing variables
VectorValues optimize(const VectorValues& solutionForMissing) const;
/// Version of optimize for incomplete BayesNet, given missing variables
VectorValues optimize(const VectorValues given) const;

/**
* Sample using ancestral sampling
* Example:
* std::mt19937_64 rng(42);
* auto sample = gbn.sample(&rng);
*/
VectorValues sample(std::mt19937_64* rng) const;

/**
* Sample from an incomplete BayesNet, given missing variables
* Example:
* std::mt19937_64 rng(42);
* VectorValues given = ...;
* auto sample = gbn.sample(given, &rng);
*/
VectorValues sample(VectorValues given, std::mt19937_64* rng) const;
dellaert marked this conversation as resolved.
Show resolved Hide resolved
Copy link
Collaborator

@varunagrawal varunagrawal Feb 8, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Okay, I have a better suggestion. You can change this signature to

VectorValues sample(VectorValues given, std::mt19937_64 rng = std::mt19937_64(42)) const;

and the definition would have us pass &rng. I tried it out locally and this works great!

Con: You will have convert from a pointer to a reference pass-by-value.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm sticking to my solution, as it uses one static rng in cpp.
Don't spend too much time on this.


/// Sample using ancestral sampling, use default rng
VectorValues sample() const;

/// Sample from an incomplete BayesNet, use default rng
VectorValues sample(VectorValues given) const;

/**
* Return ordering corresponding to a topological sort.
Expand Down
93 changes: 81 additions & 12 deletions gtsam/linear/GaussianConditional.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtsam/linear/linearExceptions.h>
#include <gtsam/linear/GaussianConditional.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/linear/Sampler.h>

#include <boost/format.hpp>
#ifdef __GNUC__
Expand All @@ -34,6 +35,9 @@
#include <list>
#include <string>

// In Wrappers we have no access to this so have a default ready
static std::mt19937_64 kRandomNumberGenerator(42);

using namespace std;

namespace gtsam {
Expand All @@ -43,19 +47,47 @@ namespace gtsam {
Key key, const Vector& d, const Matrix& R, const SharedDiagonal& sigmas) :
BaseFactor(key, R, d, sigmas), BaseConditional(1) {}

/* ************************************************************************* */
GaussianConditional::GaussianConditional(
Key key, const Vector& d, const Matrix& R,
Key name1, const Matrix& S, const SharedDiagonal& sigmas) :
BaseFactor(key, R, name1, S, d, sigmas), BaseConditional(1) {}
/* ************************************************************************ */
GaussianConditional::GaussianConditional(Key key, const Vector& d,
const Matrix& R, Key parent1,
const Matrix& S,
const SharedDiagonal& sigmas)
: BaseFactor(key, R, parent1, S, d, sigmas), BaseConditional(1) {}

/* ************************************************************************ */
GaussianConditional::GaussianConditional(Key key, const Vector& d,
const Matrix& R, Key parent1,
const Matrix& S, Key parent2,
const Matrix& T,
const SharedDiagonal& sigmas)
: BaseFactor(key, R, parent1, S, parent2, T, d, sigmas),
BaseConditional(1) {}

/* ************************************************************************ */
GaussianConditional GaussianConditional::FromMeanAndStddev(
Key key, const Matrix& A, Key parent, const Vector& b, double sigma) {
// |Rx + Sy - d| = |x-(Ay + b)|/sigma
const Matrix R = Matrix::Identity(b.size(), b.size());
const Matrix S = -A;
const Vector d = b;
return GaussianConditional(key, d, R, parent, S,
noiseModel::Isotropic::Sigma(b.size(), sigma));
}

/* ************************************************************************* */
GaussianConditional::GaussianConditional(
Key key, const Vector& d, const Matrix& R,
Key name1, const Matrix& S, Key name2, const Matrix& T, const SharedDiagonal& sigmas) :
BaseFactor(key, R, name1, S, name2, T, d, sigmas), BaseConditional(1) {}
/* ************************************************************************ */
GaussianConditional GaussianConditional::FromMeanAndStddev(
Key key, const Matrix& A1, Key parent1, const Matrix& A2, Key parent2,
const Vector& b, double sigma) {
// |Rx + Sy + Tz - d| = |x-(A1 y + A2 z + b)|/sigma
const Matrix R = Matrix::Identity(b.size(), b.size());
const Matrix S = -A1;
const Matrix T = -A2;
const Vector d = b;
return GaussianConditional(key, d, R, parent1, S, parent2, T,
noiseModel::Isotropic::Sigma(b.size(), sigma));
}

/* ************************************************************************* */
/* ************************************************************************ */
void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const {
cout << s << " Conditional density ";
for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) {
Expand Down Expand Up @@ -192,7 +224,44 @@ namespace gtsam {
}
}

/* ************************************************************************* */
/* ************************************************************************ */
VectorValues GaussianConditional::sample(const VectorValues& parentsValues,
std::mt19937_64* rng) const {
if (nrFrontals() != 1) {
throw std::invalid_argument(
"GaussianConditional::sample can only be called on single variable "
"conditionals");
}
if (!model_) {
throw std::invalid_argument(
"GaussianConditional::sample can only be called if a diagonal noise "
dellaert marked this conversation as resolved.
Show resolved Hide resolved
"model was specified at construction.");
}
VectorValues solution = solve(parentsValues);
Key key = firstFrontalKey();
const Vector& sigmas = model_->sigmas();
solution[key] += Sampler::sampleDiagonal(sigmas, rng);
return solution;
}

VectorValues GaussianConditional::sample(std::mt19937_64* rng) const {
if (nrParents() != 0)
throw std::invalid_argument(
"sample() can only be invoked on no-parent prior");
VectorValues values;
return sample(values);
}

/* ************************************************************************ */
VectorValues GaussianConditional::sample() const {
return sample(&kRandomNumberGenerator);
}

VectorValues GaussianConditional::sample(const VectorValues& given) const {
return sample(given, &kRandomNumberGenerator);
}

/* ************************************************************************ */
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
void GTSAM_DEPRECATED
GaussianConditional::scaleFrontalsBySigma(VectorValues& gy) const {
Expand Down
67 changes: 61 additions & 6 deletions gtsam/linear/GaussianConditional.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,15 @@
#include <gtsam/inference/Conditional.h>
#include <gtsam/linear/VectorValues.h>

#include <random> // for std::mt19937_64

namespace gtsam {

/**
* A conditional Gaussian functions as the node in a Bayes network
* A GaussianConditional functions as the node in a Bayes network.
* It has a set of parents y,z, etc. and implements a probability density on x.
* The negative log-probability is given by \f$ \frac{1}{2} |Rx - (d - Sy - Tz - ...)|^2 \f$
* @addtogroup linear
*/
class GTSAM_EXPORT GaussianConditional :
public JacobianFactor,
Expand All @@ -43,6 +46,9 @@ namespace gtsam {
typedef JacobianFactor BaseFactor; ///< Typedef to our factor base class
typedef Conditional<BaseFactor, This> BaseConditional; ///< Typedef to our conditional base class

/// @name Constructors
/// @{

/** default constructor needed for serialization */
GaussianConditional() {}

Expand All @@ -51,13 +57,14 @@ namespace gtsam {
const SharedDiagonal& sigmas = SharedDiagonal());

/** constructor with only one parent |Rx+Sy-d| */
GaussianConditional(Key key, const Vector& d, const Matrix& R,
Key name1, const Matrix& S, const SharedDiagonal& sigmas = SharedDiagonal());
GaussianConditional(Key key, const Vector& d, const Matrix& R, Key parent1,
const Matrix& S,
const SharedDiagonal& sigmas = SharedDiagonal());

/** constructor with two parents |Rx+Sy+Tz-d| */
GaussianConditional(Key key, const Vector& d, const Matrix& R,
Key name1, const Matrix& S, Key name2, const Matrix& T,
const SharedDiagonal& sigmas = SharedDiagonal());
GaussianConditional(Key key, const Vector& d, const Matrix& R, Key parent1,
const Matrix& S, Key parent2, const Matrix& T,
const SharedDiagonal& sigmas = SharedDiagonal());

/** Constructor with arbitrary number of frontals and parents.
* @tparam TERMS A container whose value type is std::pair<Key, Matrix>, specifying the
Expand All @@ -76,6 +83,17 @@ namespace gtsam {
const KEYS& keys, size_t nrFrontals, const VerticalBlockMatrix& augmentedMatrix,
const SharedDiagonal& sigmas = SharedDiagonal());

/// Construct from mean A1 p1 + b and standard deviation.
static GaussianConditional FromMeanAndStddev(Key key, const Matrix& A,
Key parent, const Vector& b,
double sigma);

/// Construct from mean A1 p1 + A2 p2 + b and standard deviation.
static GaussianConditional FromMeanAndStddev(Key key, //
const Matrix& A1, Key parent1,
const Matrix& A2, Key parent2,
const Vector& b, double sigma);

/** Combine several GaussianConditional into a single dense GC. The conditionals enumerated by
* \c first and \c last must be in increasing order, meaning that the parents of any
* conditional may not include a conditional coming before it.
Expand All @@ -86,13 +104,21 @@ namespace gtsam {
template<typename ITERATOR>
static shared_ptr Combine(ITERATOR firstConditional, ITERATOR lastConditional);

/// @}
/// @name Testable
/// @{

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

/** equals function */
bool equals(const GaussianFactor&cg, double tol = 1e-9) const override;

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

/** Return a view of the upper-triangular R block of the conditional */
constABlock R() const { return Ab_.range(0, nrFrontals()); }

Expand Down Expand Up @@ -125,10 +151,39 @@ namespace gtsam {
/** Performs transpose backsubstition in place on values */
void solveTransposeInPlace(VectorValues& gy) const;

/**
* Sample from conditional, zero parent version
* Example:
* std::mt19937_64 rng(42);
* auto sample = gbn.sample(&rng);
*/
VectorValues sample(std::mt19937_64* rng) const;

/**
* Sample from conditional, given missing variables
* Example:
* std::mt19937_64 rng(42);
* VectorValues given = ...;
* auto sample = gbn.sample(given, &rng);
*/
VectorValues sample(const VectorValues& parentsValues,
std::mt19937_64* rng) const;

/// Sample, use default rng
VectorValues sample() const;

/// Sample with given values, use default rng
VectorValues sample(const VectorValues& parentsValues) const;
dellaert marked this conversation as resolved.
Show resolved Hide resolved

/// @}

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/// @name Deprecated
/// @{
/** Scale the values in \c gy according to the sigmas for the frontal variables in this
* conditional. */
void GTSAM_DEPRECATED scaleFrontalsBySigma(VectorValues& gy) const;
/// @}
#endif

private:
Expand Down
13 changes: 8 additions & 5 deletions gtsam/linear/GaussianDensity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,12 @@ using namespace std;
namespace gtsam {

/* ************************************************************************* */
GaussianDensity GaussianDensity::FromMeanAndStddev(Key key, const Vector& mean, const double& sigma)
{
return GaussianDensity(key, mean / sigma, Matrix::Identity(mean.size(), mean.size()) / sigma);
GaussianDensity GaussianDensity::FromMeanAndStddev(Key key,
const Vector& mean,
double sigma) {
return GaussianDensity(key, mean,
Matrix::Identity(mean.size(), mean.size()),
noiseModel::Isotropic::Sigma(mean.size(), sigma));
}

/* ************************************************************************* */
Expand All @@ -35,8 +38,8 @@ namespace gtsam {
for(const_iterator it = beginFrontals(); it != endFrontals(); ++it)
cout << (boost::format("[%1%]")%(formatter(*it))).str() << " ";
cout << endl;
gtsam::print(Matrix(R()), "R: ");
gtsam::print(Vector(d()), "d: ");
gtsam::print(mean(), "mean: ");
gtsam::print(covariance(), "covariance: ");
if(model_)
model_->print("Noise model: ");
}
Expand Down
Loading