NonlinearFactor.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 
21 
22 #include <cassert>
23 
24 namespace gtsam {
25 
26 /* ************************************************************************* */
27 double NonlinearFactor::error(const Values& c) const {
28  throw std::runtime_error("NonlinearFactor::error is not implemented");
29 }
30 
31 /* ************************************************************************* */
32 double NonlinearFactor::error(const HybridValues& c) const {
33  return this->error(c.nonlinear());
34 }
35 
36 /* ************************************************************************* */
37 void NonlinearFactor::print(const std::string& s,
38  const KeyFormatter& keyFormatter) const {
39  std::cout << s << " keys = { ";
40  for(Key key: keys()) {
41  std::cout << keyFormatter(key) << " ";
42  }
43  std::cout << "}" << std::endl;
44 }
45 
46 /* ************************************************************************* */
47 bool NonlinearFactor::equals(const NonlinearFactor& f, double tol) const {
48  return Base::equals(f);
49 }
50 
51 /* ************************************************************************* */
53  const std::map<Key, Key>& rekey_mapping) const {
54  shared_ptr new_factor = clone();
55  for (size_t i = 0; i < new_factor->size(); ++i) {
56  Key& cur_key = new_factor->keys()[i];
57  std::map<Key, Key>::const_iterator mapping = rekey_mapping.find(cur_key);
58  if (mapping != rekey_mapping.end())
59  cur_key = mapping->second;
60  }
61  return new_factor;
62 }
63 
64 /* ************************************************************************* */
66  const KeyVector& new_keys) const {
67  assert(new_keys.size() == keys().size());
68  shared_ptr new_factor = clone();
69  new_factor->keys() = new_keys;
70  return new_factor;
71 }
72 
73 /* ************************************************************************* */
74 void NoiseModelFactor::print(const std::string& s,
75  const KeyFormatter& keyFormatter) const {
76  Base::print(s, keyFormatter);
77  if (noiseModel_)
78  noiseModel_->print(" noise model: ");
79 }
80 
81 /* ************************************************************************* */
82 bool NoiseModelFactor::equals(const NonlinearFactor& f, double tol) const {
83  const NoiseModelFactor* e = dynamic_cast<const NoiseModelFactor*>(&f);
84  return e && Base::equals(f, tol)
85  && ((!noiseModel_ && !e->noiseModel_)
86  || (noiseModel_ && e->noiseModel_
87  && noiseModel_->equals(*e->noiseModel_, tol)));
88 }
89 
90 /* ************************************************************************* */
92  const SharedNoiseModel newNoise) const {
93  NoiseModelFactor::shared_ptr new_factor = std::dynamic_pointer_cast<NoiseModelFactor>(clone());
94  new_factor->noiseModel_ = newNoise;
95  return new_factor;
96 }
97 
98 /* ************************************************************************* */
99 static void check(const SharedNoiseModel& noiseModel, size_t m) {
100  if (noiseModel && m != noiseModel->dim()) {
101  throw std::invalid_argument(
102  "NoiseModelFactor: NoiseModel has dimension " +
103  std::to_string(noiseModel->dim()) +
104  " instead of " + std::to_string(m) + ".");
105  }
106 }
107 
108 /* ************************************************************************* */
110  const Vector b = unwhitenedError(c);
111  check(noiseModel_, b.size());
112  return noiseModel_ ? noiseModel_->whiten(b) : b;
113 }
114 
115 /* ************************************************************************* */
117  const Vector b = unwhitenedError(c);
118  check(noiseModel_, b.size());
119  return noiseModel_ ? noiseModel_->unweightedWhiten(b) : b;
120 }
121 
122 /* ************************************************************************* */
123 double NoiseModelFactor::weight(const Values& c) const {
124  if (active(c)) {
125  if (noiseModel_) {
126  const Vector b = unwhitenedError(c);
127  check(noiseModel_, b.size());
128  return noiseModel_->weight(b);
129  }
130  else
131  return 1.0;
132  } else {
133  return 0.0;
134  }
135 }
136 
137 /* ************************************************************************* */
138 double NoiseModelFactor::error(const Values& c) const {
139  if (active(c)) {
140  const Vector b = unwhitenedError(c);
141  check(noiseModel_, b.size());
142  if (noiseModel_)
143  return noiseModel_->loss(noiseModel_->squaredMahalanobisDistance(b));
144  else
145  return 0.5 * b.squaredNorm();
146  } else {
147  return 0.0;
148  }
149 }
150 
151 /* ************************************************************************* */
152 std::shared_ptr<GaussianFactor> NoiseModelFactor::linearize(
153  const Values& x) const {
154 
155  // Only linearize if the factor is active
156  if (!active(x))
157  return std::shared_ptr<JacobianFactor>();
158 
159  // Call evaluate error to get Jacobians and RHS vector b
160  std::vector<Matrix> A(size());
161  Vector b = -unwhitenedError(x, A);
162  check(noiseModel_, b.size());
163 
164  // Whiten the corresponding system now
165  if (noiseModel_)
166  noiseModel_->WhitenSystem(A, b);
167 
168  // Fill in terms, needed to create JacobianFactor below
169  std::vector<std::pair<Key, Matrix> > terms(size());
170  for (size_t j = 0; j < size(); ++j) {
171  terms[j].first = keys()[j];
172  terms[j].second.swap(A[j]);
173  }
174 
175  // TODO pass unwhitened + noise model to Gaussian factor
177  if (noiseModel_ && noiseModel_->isConstrained())
179  new JacobianFactor(terms, b,
180  std::static_pointer_cast<Constrained>(noiseModel_)->unit()));
181  else {
182  return GaussianFactor::shared_ptr(new JacobianFactor(terms, b));
183  }
184 }
185 
186 /* ************************************************************************* */
187 
188 } // \namespace gtsam
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:79
gtsam::HybridValues
Definition: HybridValues.h:37
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::NoiseModelFactor::error
double error(const Values &c) const override
Definition: NonlinearFactor.cpp:138
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::NonlinearFactor::equals
virtual bool equals(const NonlinearFactor &f, double tol=1e-9) const
Definition: NonlinearFactor.cpp:47
gtsam::NoiseModelFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:210
gtsam::NonlinearFactor::rekey
virtual shared_ptr rekey(const std::map< Key, Key > &rekey_mapping) const
Definition: NonlinearFactor.cpp:52
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:206
gtsam::Factor::shared_ptr
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:76
gtsam::NonlinearFactor::active
virtual bool active(const Values &) const
Definition: NonlinearFactor.h:142
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::noiseModel::Constrained
Definition: NoiseModel.h:404
gtsam::NoiseModelFactor::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &x) const override
Definition: NonlinearFactor.cpp:152
gtsam::NoiseModelFactor::whitenedError
Vector whitenedError(const Values &c) const
Definition: NonlinearFactor.cpp:109
A
Definition: test_numpy_dtypes.cpp:298
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
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::HybridValues::nonlinear
const Values & nonlinear() const
Return the nonlinear values.
Definition: HybridValues.cpp:60
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::check
static void check(const SharedNoiseModel &noiseModel, size_t m)
Definition: NonlinearFactor.cpp:99
gtsam::NoiseModelFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactor.cpp:74
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:82
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::NoiseModelFactor::weight
double weight(const Values &c) const
Definition: NonlinearFactor.cpp:123
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::NonlinearFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactor.cpp:37
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::NoiseModelFactor::unweightedWhitenedError
Vector unweightedWhitenedError(const Values &c) const
Definition: NonlinearFactor.cpp:116
NonlinearFactor.h
Non-linear factor base classes.
gtsam::b
const G & b
Definition: Group.h:79
gtsam::NoiseModelFactor::cloneWithNewNoiseModel
shared_ptr cloneWithNewNoiseModel(const SharedNoiseModel newNoise) const
Definition: NonlinearFactor.cpp:91
gtsam
traits
Definition: SFMdata.h:40
gtsam::NoiseModelFactor
Definition: NonlinearFactor.h:198
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::Factor::equals
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Factor::size
size_t size() const
Definition: Factor.h:160
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::NonlinearFactor::clone
virtual shared_ptr clone() const
Definition: NonlinearFactor.h:154
HybridValues.h
gtsam::NoiseModelFactor::unwhitenedError
virtual Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const =0
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::NonlinearFactor::error
virtual double error(const Values &c) const
Definition: NonlinearFactor.cpp:27


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:23