Go to the documentation of this file.
42 public Conditional<JacobianFactor, GaussianConditional>
73 template<
typename TERMS>
75 size_t nrFrontals,
const Vector&
d,
82 template<
typename KEYS>
104 template<
typename... Args>
106 return std::make_shared<This>(FromMeanAndStddev(std::forward<Args>(
args)...));
116 template<
typename ITERATOR>
117 static shared_ptr
Combine(ITERATOR firstConditional, ITERATOR lastConditional);
125 const std::string& =
"GaussianConditional",
143 double negLogConstant()
const override;
209 std::mt19937_64*
rng)
const;
275 using Conditional::operator();
281 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
283 friend class boost::serialization::access;
284 template<
class Archive>
285 void serialize(Archive & ar,
const unsigned int ) {
286 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
287 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
Expression of a fixed-size or dynamic-size block.
JacobianFactor BaseFactor
Typedef to our factor base class.
Included from all GTSAM files.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
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
double operator()(const VectorValues &x) const
Evaluate probability density, sugar.
const KeyFormatter & formatter
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Conditional Gaussian Base class.
static const double sigma
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Conditional< BaseFactor, This > BaseConditional
Typedef to our conditional base class.
void print(const Matrix &A, const string &s, ostream &stream)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
double logDeterminant(const typename BAYESTREE::sharedClique &clique)
noiseModel::Diagonal::shared_ptr SharedDiagonal
GaussianConditional This
Typedef to this class.
const constBVector d() const
A small structure to hold a non zero as a triplet (i,j,value).
const gtsam::Symbol key('X', 0)
KeyVector::const_iterator const_iterator
Const iterator over keys.
constABlock::ConstColXpr constBVector
constABlock S(const_iterator it) const
std::shared_ptr< This > shared_ptr
shared_ptr to this class
double error(const VectorValues &c) const override
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Base class for conditional densities.
std::uint64_t Key
Integer nonlinear key type.
Rot2 R(Rot2::fromAngle(0.1))
double determinant() const
Compute the determinant of the R matrix.
static shared_ptr sharedMeanAndStddev(Args &&... args)
Create shared pointer by forwarding arguments to fromMeanAndStddev.
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:34