Go to the documentation of this file.
22 #include <unordered_set>
39 const KeySet &lastKeysToEliminate) {
47 for (
auto &
k : lastKeysToEliminate) {
49 lastKeys.push_back(
k);
54 std::copy(allDiscrete.begin(), allDiscrete.end(),
55 std::back_inserter(lastKeys));
67 const std::optional<Ordering> givenOrdering) {
70 if (!givenOrdering.has_value()) {
72 KeySet continuousKeysToInclude;
99 std::vector<double> probabilities(
116 std::optional<size_t> maxNrLeaves,
117 const std::optional<Ordering> given_ordering) {
125 const KeySet originalNewFactorKeys = newFactors.
keys();
126 #ifdef DEBUG_SMOOTHER
129 std::cout <<
"newFactors size: " << newFactors.
size() << std::endl;
135 #ifdef DEBUG_SMOOTHER
137 std::cout <<
"updatedGraph size: " << updatedGraph.
size() << std::endl;
151 #if GTSAM_HYBRID_TIMING
152 gttic_(HybridSmootherEliminate);
156 #if GTSAM_HYBRID_TIMING
157 gttoc_(HybridSmootherEliminate);
160 #ifdef DEBUG_SMOOTHER_DETAIL
161 for (
auto conditional : bayesNetFragment) {
162 auto e = std::dynamic_pointer_cast<HybridConditional::BaseConditional>(
168 #ifdef DEBUG_SMOOTHER
170 std::cout <<
"Discrete keys in bayesNetFragment: ";
178 #if GTSAM_HYBRID_TIMING
179 gttic_(HybridSmootherPrune);
187 #if GTSAM_HYBRID_TIMING
188 gttoc_(HybridSmootherPrune);
192 #ifdef DEBUG_SMOOTHER
194 std::cout <<
"\nAfter pruning: ";
198 std::cout << std::endl << std::endl;
201 #ifdef DEBUG_SMOOTHER_DETAIL
202 for (
auto conditional : bayesNetFragment) {
203 auto c = std::dynamic_pointer_cast<HybridConditional::BaseConditional>(
214 std::pair<HybridGaussianFactorGraph, HybridBayesNet>
221 auto involved = [](
const KeySet &involvedKeys,
const Key &
key) {
222 return involvedKeys.find(
key) != involvedKeys.end();
244 for (
auto &
key : conditional->frontals()) {
245 if (involved(involvedKeys,
key)) {
248 for (
auto &&parentKey : conditional->parents()) {
249 involvedKeys.insert(parentKey);
256 #ifdef DEBUG_SMOOTHER
263 for (
auto &
key : conditional->frontals()) {
264 if (involved(involvedKeys,
key)) {
268 auto it = find(updatedHybridBayesNet.
begin(),
269 updatedHybridBayesNet.
end(), conditional);
270 updatedHybridBayesNet.
erase(it);
277 graph.push_back(newConditionals);
280 return {
graph, updatedHybridBayesNet};
285 size_t index)
const {
305 if (std::find(
gbn.begin(),
gbn.end(),
nullptr) !=
gbn.end()) {
306 throw std::runtime_error(
"At least one nullptr factor in hybridBayesNet_");
321 linearized->eliminateSequential(
ordering);
const HybridBayesNet & hybridBayesNet() const
Return the Bayes Net posterior.
static Ordering ColamdConstrainedLast(const FACTOR_GRAPH &graph, const KeyVector &constrainLast, bool forceOrder=false)
std::shared_ptr< This > shared_ptr
shared_ptr to This
Values linearizationPoint() const
Return the current linearization point.
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
std::optional< double > marginalThreshold_
The threshold above which we make a decision about a mode.
std::set< DiscreteKey > discreteKeys() const
Get all the discrete keys in the factor graph.
static const DiscreteBayesNet bayesNet
void update(const HybridNonlinearFactorGraph &graph, const Values &initial, std::optional< size_t > maxNrLeaves={}, const std::optional< Ordering > givenOrdering={})
std::shared_ptr< This > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
HybridNonlinearFactorGraph allFactors() const
Return all the recorded nonlinear factors.
HybridGaussianFactorGraph removeFixedValues(const HybridGaussianFactorGraph &graph, const HybridGaussianFactorGraph &newFactors)
Remove fixed discrete values for discrete keys introduced in newFactors, and reintroduce discrete fac...
Ordering maybeComputeOrdering(const HybridGaussianFactorGraph &updatedGraph, const std::optional< Ordering > givenOrdering)
Helper to compute the ordering if ordering is not given.
bool exists(const VALUE &e) const
Ordering getOrdering(const HybridGaussianFactorGraph &factors, const KeySet &newFactorKeys)
Get an elimination ordering which eliminates continuous and then discrete.
const GaussianFactorGraph factors
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
void relinearize(const std::optional< Ordering > givenOrdering={})
Relinearize the nonlinear factor graph with the latest stored linearization point.
An incremental smoother for hybrid factor graphs.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
iterator erase(iterator item)
const sharedFactor at(size_t i) const
Values retract(const VectorValues &delta) const
HybridValues optimize() const
Optimize the hybrid Bayes Net, taking into accound fixed values.
std::pair< HybridGaussianFactorGraph, HybridBayesNet > addConditionals(const HybridGaussianFactorGraph &graph, const HybridBayesNet &hybridBayesNet) const
Add conditionals from previous timestep as part of liquefication.
DiscreteValues mpe() const
Compute the Most Probable Explanation (MPE) of the discrete variables.
static const GaussianBayesNet gbn
Values linearizationPoint_
static const DiscreteValues mpe
static enum @1096 ordering
const gtsam::Symbol key('X', 0)
void reInitialize(HybridBayesNet &&hybridBayesNet)
HybridBayesNet hybridBayesNet_
void push_back(std::shared_ptr< HybridConditional > conditional)
Add a hybrid conditional using a shared_ptr.
HybridNonlinearFactorGraph restrict(const DiscreteValues &assignment) const
Restrict all factors in the graph to the given discrete values.
HybridGaussianConditional::shared_ptr gaussianMixture(size_t index) const
Get the hybrid Gaussian conditional from the Bayes Net posterior at index.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
std::pair< Key, size_t > DiscreteKey
const_iterator end() const
std::pair< iterator, bool > insert(const value_type &value)
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
DiscreteValues fixedValues_
const_iterator begin() const
std::shared_ptr< HybridBayesNet > shared_ptr
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
void PrintKeySet(const KeySet &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
HybridNonlinearFactorGraph allFactors_
static constexpr double k
GaussianBayesNet choose(const DiscreteValues &assignment) const
Get the Gaussian Bayes net P(X|M=m) corresponding to a specific assignment m for the discrete variabl...
void insert_or_assign(Key j, const Value &val)
If key j exists, update value, else perform an insert.
gtsam
Author(s):
autogenerated on Wed May 28 2025 03:01:25