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 
22 
23 #include <memory>
24 
25 namespace gtsam {
26 
27 /* *******************************************************************************/
29  KeyVector continuousKeys; // Continuous keys extracted from factors
30  DiscreteKeys discreteKeys; // Discrete keys provided to the constructors
32 
34  if (!factor) return;
35  if (continuousKeys.empty()) {
36  continuousKeys = factor->keys();
37  } else if (factor->keys() != continuousKeys) {
38  throw std::runtime_error(
39  "HybridNonlinearFactor: all factors should have the same keys!");
40  }
41  }
42 
43  ConstructorHelper(const DiscreteKey& discreteKey,
44  const std::vector<NoiseModelFactor::shared_ptr>& factors)
45  : discreteKeys({discreteKey}) {
46  std::vector<NonlinearFactorValuePair> pairs;
47  // Extract continuous keys from the first non-null factor
48  for (const auto& factor : factors) {
49  pairs.emplace_back(factor, 0.0);
51  }
52  factorTree = FactorValuePairs({discreteKey}, pairs);
53  }
54 
55  ConstructorHelper(const DiscreteKey& discreteKey,
56  const std::vector<NonlinearFactorValuePair>& pairs)
57  : discreteKeys({discreteKey}) {
58  // Extract continuous keys from the first non-null factor
59  for (const auto& pair : pairs) {
60  copyOrCheckContinuousKeys(pair.first);
61  }
62  factorTree = FactorValuePairs({discreteKey}, pairs);
63  }
64 
66  const FactorValuePairs& factorPairs)
67  : discreteKeys(discreteKeys), factorTree(factorPairs) {
68  // Extract continuous keys from the first non-null factor
69  factorPairs.visit([&](const NonlinearFactorValuePair& pair) {
70  copyOrCheckContinuousKeys(pair.first);
71  });
72  }
73 };
74 
75 /* *******************************************************************************/
77  : Base(helper.continuousKeys, helper.discreteKeys),
78  factors_(helper.factorTree) {}
79 
81  const DiscreteKey& discreteKey,
82  const std::vector<NoiseModelFactor::shared_ptr>& factors)
84 
86  const DiscreteKey& discreteKey,
87  const std::vector<NonlinearFactorValuePair>& pairs)
88  : HybridNonlinearFactor(ConstructorHelper(discreteKey, pairs)) {}
89 
93 
94 /* *******************************************************************************/
96  const Values& continuousValues) const {
97  // functor to convert from sharedFactor to double error value.
98  auto errorFunc =
99  [continuousValues](const std::pair<sharedFactor, double>& f) {
100  auto [factor, val] = f;
101  return factor->error(continuousValues) + val;
102  };
104  return result;
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  if (auto gaussian = std::dynamic_pointer_cast<noiseModel::Gaussian>(
189  factor->noiseModel())) {
190  return {factor->linearize(continuousValues),
191  val + gaussian->negLogConstant()};
192  } else {
193  throw std::runtime_error(
194  "HybridNonlinearFactor: linearize() only supports NoiseModelFactors "
195  "with Gaussian (or derived) noise models.");
196  }
197  };
198 
200  linearized_factors(factors_, linearizeDT);
201 
202  return std::make_shared<HybridGaussianFactor>(discreteKeys_,
203  linearized_factors);
204 }
205 
206 } // namespace gtsam
gtsam::HybridNonlinearFactor::HybridNonlinearFactor
HybridNonlinearFactor()=default
Default constructor, mainly for serialization.
compare
bool compare
Definition: SolverComparer.cpp:98
gtsam::HybridValues
Definition: HybridValues.h:37
gtsam::HybridNonlinearFactor::ConstructorHelper::continuousKeys
KeyVector continuousKeys
Definition: HybridNonlinearFactor.cpp:29
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:65
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:899
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::HybridNonlinearFactor::ConstructorHelper
Definition: HybridNonlinearFactor.cpp:28
gtsam::HybridFactor
Definition: HybridFactor.h:54
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:195
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:905
gtsam::NoiseModelFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:209
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::AlgebraicDecisionTree< Key >
gtsam::HybridNonlinearFactor::ConstructorHelper::ConstructorHelper
ConstructorHelper(const DiscreteKey &discreteKey, const std::vector< NoiseModelFactor::shared_ptr > &factors)
Definition: HybridNonlinearFactor.cpp:43
gtsam::HybridNonlinearFactor::ConstructorHelper::discreteKeys
DiscreteKeys discreteKeys
Definition: HybridNonlinearFactor.cpp:30
gtsam::GaussianFactorValuePair
std::pair< GaussianFactor::shared_ptr, double > GaussianFactorValuePair
Alias for pair of GaussianFactor::shared_pointer and a double value.
Definition: HybridGaussianFactor.h:37
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:769
gtsam::HybridFactor::discreteKeys_
DiscreteKeys discreteKeys_
Definition: HybridFactor.h:65
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: chartTesting.h:28
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::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
gtsam::HybridNonlinearFactor::ConstructorHelper::ConstructorHelper
ConstructorHelper(const DiscreteKey &discreteKey, const std::vector< NonlinearFactorValuePair > &pairs)
Definition: HybridNonlinearFactor.cpp:55
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:33
gtsam::tol
const G double tol
Definition: Group.h:79
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:264
gtsam::HybridNonlinearFactor::errorTree
AlgebraicDecisionTree< Key > errorTree(const VectorValues &continuousValues) const override
HybridFactor method implementation. Should not be used.
Definition: HybridNonlinearFactor.h:76
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::equal
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
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:31
factorError
Vector factorError(const Point3 &T1, const Point3 &T2, const TranslationFactor &factor)
Definition: testTranslationFactor.cpp:74


gtsam
Author(s):
autogenerated on Fri Oct 4 2024 03:02:14