HybridNonlinearFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
23 
24 #include <memory>
25 
26 namespace gtsam {
27 
28 /* *******************************************************************************/
30  KeyVector continuousKeys; // Continuous keys extracted from factors
31  DiscreteKeys discreteKeys; // Discrete keys provided to the constructors
33 
35  if (!factor) return;
36  if (continuousKeys.empty()) {
37  continuousKeys = factor->keys();
38  } else if (factor->keys() != continuousKeys) {
39  throw std::runtime_error(
40  "HybridNonlinearFactor: all factors should have the same keys!");
41  }
42  }
43 
44  ConstructorHelper(const DiscreteKey& discreteKey,
45  const std::vector<NoiseModelFactor::shared_ptr>& factors)
46  : discreteKeys({discreteKey}) {
47  std::vector<NonlinearFactorValuePair> pairs;
48  // Extract continuous keys from the first non-null factor
49  for (const auto& factor : factors) {
50  pairs.emplace_back(factor, 0.0);
52  }
53  factorTree = FactorValuePairs({discreteKey}, pairs);
54  }
55 
56  ConstructorHelper(const DiscreteKey& discreteKey,
57  const std::vector<NonlinearFactorValuePair>& pairs)
58  : discreteKeys({discreteKey}) {
59  // Extract continuous keys from the first non-null factor
60  for (const auto& pair : pairs) {
61  copyOrCheckContinuousKeys(pair.first);
62  }
63  factorTree = FactorValuePairs({discreteKey}, pairs);
64  }
65 
67  const FactorValuePairs& factorPairs)
68  : discreteKeys(discreteKeys), factorTree(factorPairs) {
69  // Extract continuous keys from the first non-null factor
70  factorPairs.visit([&](const NonlinearFactorValuePair& pair) {
71  copyOrCheckContinuousKeys(pair.first);
72  });
73  }
74 };
75 
76 /* *******************************************************************************/
78  : Base(helper.continuousKeys, helper.discreteKeys),
79  factors_(helper.factorTree) {}
80 
82  const DiscreteKey& discreteKey,
83  const std::vector<NoiseModelFactor::shared_ptr>& factors)
85 
87  const DiscreteKey& discreteKey,
88  const std::vector<NonlinearFactorValuePair>& pairs)
89  : HybridNonlinearFactor(ConstructorHelper(discreteKey, pairs)) {}
90 
94 
95 /* *******************************************************************************/
97  const Values& continuousValues) const {
98  // functor to convert from sharedFactor to double error value.
99  auto errorFunc =
100  [continuousValues](const std::pair<sharedFactor, double>& f) {
101  auto [factor, val] = f;
102  return factor->error(continuousValues) + val;
103  };
104  return {factors_, errorFunc};
105 }
106 
107 /* *******************************************************************************/
109  const Values& continuousValues,
110  const DiscreteValues& discreteValues) const {
111  // Retrieve the factor corresponding to the assignment in discreteValues.
112  auto [factor, val] = factors_(discreteValues);
113  // Compute the error for the selected factor
114  const double factorError = factor->error(continuousValues);
115  return factorError + val;
116 }
117 
118 /* *******************************************************************************/
120  return error(values.nonlinear(), values.discrete());
121 }
122 
123 /* *******************************************************************************/
125  const auto assignments = DiscreteValues::CartesianProduct(discreteKeys_);
126  auto [factor, val] = factors_(assignments.at(0));
127  return factor->dim();
128 }
129 
130 /* *******************************************************************************/
131 void HybridNonlinearFactor::print(const std::string& s,
132  const KeyFormatter& keyFormatter) const {
133  std::cout << (s.empty() ? "" : s + " ");
134  Base::print("", keyFormatter);
135  std::cout << "\nHybridNonlinearFactor\n";
136  auto valueFormatter = [](const std::pair<sharedFactor, double>& v) {
137  auto [factor, val] = v;
138  if (factor) {
139  return "Nonlinear factor on " + std::to_string(factor->size()) + " keys";
140  } else {
141  return std::string("nullptr");
142  }
143  };
144  factors_.print("", keyFormatter, valueFormatter);
145 }
146 
147 /* *******************************************************************************/
149  double tol) const {
150  // We attempt a dynamic cast from HybridFactor to HybridNonlinearFactor. If
151  // it fails, return false.
152  if (!dynamic_cast<const HybridNonlinearFactor*>(&other)) return false;
153 
154  // If the cast is successful, we'll properly construct a
155  // HybridNonlinearFactor object from `other`
156  const HybridNonlinearFactor& f(
157  static_cast<const HybridNonlinearFactor&>(other));
158 
159  // Ensure that this HybridNonlinearFactor and `f` have the same `factors_`.
160  auto compare = [tol](const std::pair<sharedFactor, double>& a,
161  const std::pair<sharedFactor, double>& b) {
162  return a.first->equals(*b.first, tol) && (a.second == b.second);
163  };
164  if (!factors_.equals(f.factors_, compare)) return false;
165 
166  // If everything above passes, and the keys_ and discreteKeys_
167  // member variables are identical, return true.
168  return (std::equal(keys_.begin(), keys_.end(), f.keys().begin()) &&
169  (discreteKeys_ == f.discreteKeys_));
170 }
171 
172 /* *******************************************************************************/
174  const Values& continuousValues,
175  const DiscreteValues& discreteValues) const {
176  auto factor = factors_(discreteValues).first;
177  return factor->linearize(continuousValues);
178 }
179 
180 /* *******************************************************************************/
181 std::shared_ptr<HybridGaussianFactor> HybridNonlinearFactor::linearize(
182  const Values& continuousValues) const {
183  // functional to linearize each factor in the decision tree
184  auto linearizeDT =
185  [continuousValues](
186  const std::pair<sharedFactor, double>& f) -> GaussianFactorValuePair {
187  auto [factor, val] = f;
188  // Check if valid factor. If not, return null and infinite error.
189  if (!factor) {
190  return {nullptr, std::numeric_limits<double>::infinity()};
191  }
192 
193  if (auto gaussian = std::dynamic_pointer_cast<noiseModel::Gaussian>(
194  factor->noiseModel())) {
195  return {factor->linearize(continuousValues),
196  val + gaussian->negLogConstant()};
197  } else {
198  throw std::runtime_error(
199  "HybridNonlinearFactor: linearize() only supports NoiseModelFactors "
200  "with Gaussian (or derived) noise models.");
201  }
202  };
203 
205  linearized_factors(factors_, linearizeDT);
206 
207  return std::make_shared<HybridGaussianFactor>(discreteKeys_,
208  linearized_factors);
209 }
210 
211 /* *******************************************************************************/
213  const DecisionTreeFactor& discreteProbs) const {
214  // Find keys in discreteProbs.keys() but not in this->keys():
215  std::set<Key> mine(this->keys().begin(), this->keys().end());
216  std::set<Key> theirs(discreteProbs.keys().begin(),
217  discreteProbs.keys().end());
218  std::vector<Key> diff;
219  std::set_difference(theirs.begin(), theirs.end(), mine.begin(), mine.end(),
220  std::back_inserter(diff));
221 
222  // Find maximum probability value for every combination of our keys.
223  Ordering keys(diff);
224  auto max = discreteProbs.max(keys);
225 
226  // Check the max value for every combination of our keys.
227  // If the max value is 0.0, we can prune the corresponding conditional.
228  auto pruner =
229  [&](const Assignment<Key>& choices,
231  if (max->evaluate(choices) == 0.0)
232  return {nullptr, std::numeric_limits<double>::infinity()};
233  else
234  return pair;
235  };
236 
237  FactorValuePairs prunedFactors = factors().apply(pruner);
238  return std::make_shared<HybridNonlinearFactor>(discreteKeys(), prunedFactors);
239 }
240 
241 } // namespace gtsam
gtsam::HybridNonlinearFactor::HybridNonlinearFactor
HybridNonlinearFactor()=default
Default constructor, mainly for serialization.
compare
bool compare
Definition: SolverComparer.cpp:98
gtsam::DecisionTreeFactor
Definition: DecisionTreeFactor.h:44
gtsam::HybridValues
Definition: HybridValues.h:37
gtsam::HybridNonlinearFactor::ConstructorHelper::continuousKeys
KeyVector continuousKeys
Definition: HybridNonlinearFactor.cpp:30
gtsam::HybridNonlinearFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print to stdout
Definition: HybridNonlinearFactor.cpp:131
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::HybridNonlinearFactor::ConstructorHelper::ConstructorHelper
ConstructorHelper(const DiscreteKeys &discreteKeys, const FactorValuePairs &factorPairs)
Definition: HybridNonlinearFactor.cpp:66
gtsam::HybridNonlinearFactor::linearize
GaussianFactor::shared_ptr linearize(const Values &continuousValues, const DiscreteValues &discreteValues) const
Definition: HybridNonlinearFactor.cpp:173
gtsam::DecisionTree::equals
bool equals(const DecisionTree &other, const CompareFunc &compare=&DefaultCompare) const
Definition: DecisionTree-inl.h:972
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::HybridNonlinearFactor::ConstructorHelper
Definition: HybridNonlinearFactor.cpp:29
gtsam::HybridFactor
Definition: HybridFactor.h:51
gtsam::HybridNonlinearFactor::error
double error(const Values &continuousValues, const DiscreteValues &discreteValues) const
Compute error of factor given both continuous and discrete values.
Definition: HybridNonlinearFactor.cpp:108
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
gtsam::Factor
Definition: Factor.h:70
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
gtsam::DecisionTree::print
void print(const std::string &s, const LabelFormatter &labelFormatter, const ValueFormatter &valueFormatter) const
GTSAM-style print.
Definition: DecisionTree-inl.h:978
gtsam::NoiseModelFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:209
gtsam::Factor::begin
const_iterator begin() const
Definition: Factor.h:146
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::AlgebraicDecisionTree< Key >
gtsam::HybridNonlinearFactor::ConstructorHelper::ConstructorHelper
ConstructorHelper(const DiscreteKey &discreteKey, const std::vector< NoiseModelFactor::shared_ptr > &factors)
Definition: HybridNonlinearFactor.cpp:44
gtsam::HybridNonlinearFactor::ConstructorHelper::discreteKeys
DiscreteKeys discreteKeys
Definition: HybridNonlinearFactor.cpp:31
gtsam::GaussianFactorValuePair
std::pair< GaussianFactor::shared_ptr, double > GaussianFactorValuePair
Alias for pair of GaussianFactor::shared_pointer and a double value.
Definition: HybridGaussianFactor.h:38
gtsam::DiscreteValues::CartesianProduct
static std::vector< DiscreteValues > CartesianProduct(const DiscreteKeys &keys)
Return a vector of DiscreteValues, one for each possible combination of values.
Definition: DiscreteValues.h:85
gtsam::HybridNonlinearFactor::equals
bool equals(const HybridFactor &other, double tol=1e-9) const override
Check equality.
Definition: HybridNonlinearFactor.cpp:148
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::DecisionTree::visit
void visit(Func f) const
Visit all leaves in depth-first fashion.
Definition: DecisionTree-inl.h:842
gtsam::HybridNonlinearFactor::shared_ptr
std::shared_ptr< HybridNonlinearFactor > shared_ptr
Definition: HybridNonlinearFactor.h:62
gtsam::Assignment< Key >
gtsam::HybridFactor::discreteKeys_
DiscreteKeys discreteKeys_
Definition: HybridFactor.h:62
gtsam::DecisionTree::apply
DecisionTree apply(const Unary &op) const
Definition: DecisionTree-inl.h:1000
gtsam::Factor::end
const_iterator end() const
Definition: Factor.h:149
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
NonlinearFactor.h
Non-linear factor base classes.
gtsam::DecisionTree< Key, NonlinearFactorValuePair >
gtsam::b
const G & b
Definition: Group.h:79
gtsam::HybridFactor::print
void print(const std::string &s="HybridFactor\n", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print
Definition: HybridFactor.cpp:94
HybridNonlinearFactor.h
A set of nonlinear factors indexed by a set of discrete keys.
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam
traits
Definition: SFMdata.h:40
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
NoiseModel.h
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::Values
Definition: Values.h:65
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
gtsam::DecisionTreeFactor::max
shared_ptr max(size_t nrFrontals) const
Create new factor by maximizing over all values with the same separator.
Definition: DecisionTreeFactor.h:172
gtsam::HybridNonlinearFactor::ConstructorHelper::ConstructorHelper
ConstructorHelper(const DiscreteKey &discreteKey, const std::vector< NonlinearFactorValuePair > &pairs)
Definition: HybridNonlinearFactor.cpp:56
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::HybridNonlinearFactor::dim
size_t dim() const
Get the dimension of the factor (number of rows on linearization). Returns the dimension of the first...
Definition: HybridNonlinearFactor.cpp:124
gtsam::HybridNonlinearFactor::ConstructorHelper::copyOrCheckContinuousKeys
void copyOrCheckContinuousKeys(const NoiseModelFactor::shared_ptr &factor)
Definition: HybridNonlinearFactor.cpp:34
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::HybridNonlinearFactor::prune
HybridNonlinearFactor::shared_ptr prune(const DecisionTreeFactor &discreteProbs) const
Prune this factor based on the discrete probabilities.
Definition: HybridNonlinearFactor.cpp:212
gtsam::HybridNonlinearFactor::factors_
FactorValuePairs factors_
Decision tree of nonlinear factors indexed by discrete keys.
Definition: HybridNonlinearFactor.h:73
gtsam::NonlinearFactorValuePair
std::pair< NoiseModelFactor::shared_ptr, double > NonlinearFactorValuePair
Alias for a NoiseModelFactor shared pointer and double scalar pair.
Definition: HybridNonlinearFactor.h:35
gtsam::valueFormatter
static std::string valueFormatter(const double &v)
Definition: DecisionTreeFactor.cpp:248
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::HybridNonlinearFactor::errorTree
AlgebraicDecisionTree< Key > errorTree(const VectorValues &continuousValues) const override
HybridFactor method implementation. Should not be used.
Definition: HybridNonlinearFactor.h:76
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::HybridNonlinearFactor::FactorValuePairs
DecisionTree< Key, NonlinearFactorValuePair > FactorValuePairs
typedef for DecisionTree which has Keys as node labels and pairs of NoiseModelFactor & an arbitrary s...
Definition: HybridNonlinearFactor.h:69
gtsam::HybridNonlinearFactor::factors
const FactorValuePairs & factors() const
Getter for NonlinearFactor decision tree.
Definition: HybridNonlinearFactor.h:170
DecisionTreeFactor.h
gtsam::equal
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
gtsam::HybridFactor::discreteKeys
const DiscreteKeys & discreteKeys() const
Return the discrete keys for this factor.
Definition: HybridFactor.h:131
gtsam::HybridNonlinearFactor
Implementation of a discrete-conditioned hybrid factor.
Definition: HybridNonlinearFactor.h:58
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::HybridNonlinearFactor::ConstructorHelper::factorTree
FactorValuePairs factorTree
Definition: HybridNonlinearFactor.cpp:32
factorError
Vector factorError(const Point3 &T1, const Point3 &T2, const TranslationFactor &factor)
Definition: testTranslationFactor.cpp:74


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:26