Go to the documentation of this file.
25 #pragma GCC diagnostic push
26 #pragma GCC diagnostic ignored "-Wunused-variable"
29 #pragma GCC diagnostic pop
45 GaussianConditional::GaussianConditional(
70 const Matrix R = Matrix::Identity(
mu.size(),
mu.size());
80 const Matrix R = Matrix::Identity(
b.size(),
b.size());
92 const Matrix R = Matrix::Identity(
b.size(),
b.size());
102 cout << (
s.empty() ?
"" :
s +
" ") <<
"p(";
124 cout <<
" logNormalizationConstant: " << -
negLogConstant() << endl;
126 model_->print(
" Noise model: ");
128 cout <<
" No noise model" << endl;
140 list<Vector> rows1, rows2;
142 rows2.push_back(
Vector(
c->R().row(
i)));
151 rows2.push_back(
row(
c->getA(it2),
i));
176 return diag.unaryExpr([](
double x) {
return log(
x); }).sum();
178 return R().diagonal().unaryExpr([](
double x) {
return log(
x); }).sum();
186 constexpr
double log2pi = 1.8378770664093454835606594728112;
187 size_t n =
d().size();
229 if (solution.hasNaN()) {
237 result.emplace(*frontal, solution.segment(vectorPosition,
getDim(frontal)));
238 vectorPosition +=
getDim(frontal);
252 xS = rhsR -
S() * xS;
259 soln.array() *=
model_->sigmas().array();
265 result.emplace(*frontal, soln.segment(vectorPosition,
getDim(frontal)));
266 vectorPosition +=
getDim(frontal);
281 gy[*it].noalias() += -1.0 *
getA(it).transpose() * frontalVec;
285 frontalVec.array() *=
model_->sigmas().array();
290 gy[*frontal] = frontalVec.segment(vectorPosition,
getDim(frontal));
291 vectorPosition +=
getDim(frontal);
314 auto last = newAb.matrix().cols() - 1;
316 newAb.matrix().col(
last) -= RR *
x;
324 return std::make_shared<JacobianFactor>(newKeys, newAb,
model_);
329 const Vector& frontal)
const {
331 throw std::invalid_argument(
332 "GaussianConditional Single value likelihood can only be invoked on "
333 "single-variable conditional");
341 std::mt19937_64*
rng)
const {
343 throw std::invalid_argument(
344 "GaussianConditional::sample can only be called on single variable "
359 throw std::invalid_argument(
360 "sample() can only be invoked on no-parent prior");
Conditional Gaussian Base class.
static const double d[K][N]
const SharedDiagonal & get_model() const
void solveTransposeInPlace(VectorValues &gy) const
Matrix diag(const std::vector< Matrix > &Hs)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
const KeyFormatter & formatter
const EIGEN_DEVICE_FUNC LogReturnType log() const
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
static Vector sampleDiagonal(const Vector &sigmas, std::mt19937_64 *rng)
sample with given random number generator
double evaluate(const VectorValues &x) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Vector concatVectors(const std::list< Vector > &vs)
const constBVector getb() const
static const double sigma
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
noiseModel::Diagonal::shared_ptr model_
const DenseIndex & firstBlock() const
JacobianFactor ::const_iterator endParents() const
Exceptions that may be thrown by linear solver components.
DenseIndex getDim(const_iterator variable) const override
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
double negLogConstant() const override
Return the negative log of the normalization constant.
JacobianFactor ::const_iterator endFrontals() const
static std::mt19937 kRandomNumberGenerator(42)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void print(const std::string &="GaussianConditional", const KeyFormatter &formatter=DefaultKeyFormatter) const override
noiseModel::Diagonal::shared_ptr SharedDiagonal
bool equals(const GaussianFactor &cg, double tol=1e-9) const override
const constBVector d() const
double logProbability(const VectorValues &x) const
JacobianFactor ::const_iterator beginFrontals() const
size_t nrFrontals() const
const gtsam::Symbol key('X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
JacobianFactor ::const_iterator beginParents() const
static std::mt19937_64 kRandomNumberGenerator(42)
Key firstFrontalKey() const
KeyVector::const_iterator const_iterator
Const iterator over keys.
KeyVector keys_
The keys involved in this factor.
Key front() const
First key.
Point3 mean(const CONTAINER &points)
mean
const KeyVector & keys() const
Access the factor's involved variable keys.
ptrdiff_t DenseIndex
The index type for Eigen objects.
JacobianFactor::shared_ptr likelihood(const VectorValues &frontalValues) const
double logDeterminant() const
Compute the log determinant of the R matrix.
DenseIndex rows() const
Row size.
double error(const VectorValues &c) const override
std::shared_ptr< This > shared_ptr
shared_ptr to this class
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
sampling from a NoiseModel
std::uint64_t Key
Integer nonlinear key type.
VectorValues solveOtherRHS(const VectorValues &parents, const VectorValues &rhs) const
VectorValues solve(const VectorValues &parents) const
Rot2 R(Rot2::fromAngle(0.1))
bool linear_dependent(const Matrix &A, const Matrix &B, double tol)
static GaussianConditional FromMeanAndStddev(Key key, const Vector &mu, double sigma)
Construct from mean mu and standard deviation sigma.
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
VectorValues sample() const
Sample, use default rng.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:34