FunctorizedFactor.h
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 
18 #pragma once
19 
20 #include <gtsam/base/Testable.h>
22 
23 #include <cmath>
24 
25 namespace gtsam {
26 
58 template <typename R, typename T>
59 class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1<T> {
60  private:
62 
65  std::function<R(T, boost::optional<Matrix &>)> func_;
66 
67  public:
70 
79  const std::function<R(T, boost::optional<Matrix &>)> func)
80  : Base(model, key), measured_(z), noiseModel_(model), func_(func) {}
81 
82  ~FunctorizedFactor() override {}
83 
86  return boost::static_pointer_cast<NonlinearFactor>(
88  }
89 
90  Vector evaluateError(const T &params, boost::optional<Matrix &> H =
91  boost::none) const override {
92  R x = func_(params, H);
93  Vector error = traits<R>::Local(measured_, x);
94  return error;
95  }
96 
99  void print(
100  const std::string &s = "",
101  const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override {
102  Base::print(s, keyFormatter);
103  std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor("
104  << keyFormatter(this->key()) << ")" << std::endl;
105  traits<R>::Print(measured_, " measurement: ");
106  std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose()
107  << std::endl;
108  }
109 
110  bool equals(const NonlinearFactor &other, double tol = 1e-9) const override {
111  const FunctorizedFactor<R, T> *e =
112  dynamic_cast<const FunctorizedFactor<R, T> *>(&other);
113  return e && Base::equals(other, tol) &&
114  traits<R>::Equals(this->measured_, e->measured_, tol);
115  }
117 
118  private:
120  friend class boost::serialization::access;
121  template <class ARCHIVE>
122  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
123  ar &boost::serialization::make_nvp(
124  "NoiseModelFactor1", boost::serialization::base_object<Base>(*this));
125  ar &BOOST_SERIALIZATION_NVP(measured_);
126  ar &BOOST_SERIALIZATION_NVP(func_);
127  }
128 };
129 
131 template <typename R, typename T>
133  : public Testable<FunctorizedFactor<R, T>> {};
134 
141 template <typename T, typename R, typename FUNC>
143  const SharedNoiseModel &model,
144  const FUNC func) {
146 }
147 
157 template <typename R, typename T1, typename T2>
158 class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
159  private:
161 
164  using FunctionType = std::function<R(T1, T2, boost::optional<Matrix &>,
165  boost::optional<Matrix &>)>;
167 
168  public:
171 
180  const SharedNoiseModel &model, const FunctionType func)
181  : Base(model, key1, key2),
182  measured_(z),
183  noiseModel_(model),
184  func_(func) {}
185 
186  ~FunctorizedFactor2() override {}
187 
190  return boost::static_pointer_cast<NonlinearFactor>(
192  }
193 
195  const T1 &params1, const T2 &params2,
196  boost::optional<Matrix &> H1 = boost::none,
197  boost::optional<Matrix &> H2 = boost::none) const override {
198  R x = func_(params1, params2, H1, H2);
199  Vector error = traits<R>::Local(measured_, x);
200  return error;
201  }
202 
205  void print(
206  const std::string &s = "",
207  const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override {
208  Base::print(s, keyFormatter);
209  std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor2("
210  << keyFormatter(this->key1()) << ", "
211  << keyFormatter(this->key2()) << ")" << std::endl;
212  traits<R>::Print(measured_, " measurement: ");
213  std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose()
214  << std::endl;
215  }
216 
217  bool equals(const NonlinearFactor &other, double tol = 1e-9) const override {
219  dynamic_cast<const FunctorizedFactor2<R, T1, T2> *>(&other);
220  return e && Base::equals(other, tol) &&
221  traits<R>::Equals(this->measured_, e->measured_, tol);
222  }
224 
225  private:
227  friend class boost::serialization::access;
228  template <class ARCHIVE>
229  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
230  ar &boost::serialization::make_nvp(
231  "NoiseModelFactor2", boost::serialization::base_object<Base>(*this));
232  ar &BOOST_SERIALIZATION_NVP(measured_);
233  ar &BOOST_SERIALIZATION_NVP(func_);
234  }
235 };
236 
238 template <typename R, typename T1, typename T2>
240  : public Testable<FunctorizedFactor2<R, T1, T2>> {};
241 
248 template <typename T1, typename T2, typename R, typename FUNC>
250  Key key1, Key key2, const R &z, const SharedNoiseModel &model,
251  const FUNC func) {
253 }
254 
255 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
R measured_
value that is compared with functor return value
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
std::function< R(T1, T2, boost::optional< Matrix & >, boost::optional< Matrix & >)> FunctionType
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
R measured_
value that is compared with functor return value
bool equals(const NonlinearFactor &other, double tol=1e-9) const override
NonlinearFactor::shared_ptr clone() const override
Concept check for values that can be used in unit tests.
FunctorizedFactor2(Key key1, Key key2, const R &z, const SharedNoiseModel &model, const FunctionType func)
noiseModel::Diagonal::shared_ptr model
Vector evaluateError(const T &params, boost::optional< Matrix & > H=boost::none) const override
void serialize(ARCHIVE &ar, const unsigned int)
Rot2 R(Rot2::fromAngle(0.1))
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
FunctionType func_
functor instance
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
FunctorizedFactor2< R, T1, T2 > MakeFunctorizedFactor2(Key key1, Key key2, const R &z, const SharedNoiseModel &model, const FUNC func)
const Symbol key1('v', 1)
Eigen::VectorXd Vector
Definition: Vector.h:38
bool equals(const NonlinearFactor &other, double tol=1e-9) const override
boost::shared_ptr< This > shared_ptr
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
FunctorizedFactor< R, T > MakeFunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, const FUNC func)
static SmartStereoProjectionParams params
traits
Definition: chartTesting.h:28
FunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, const std::function< R(T, boost::optional< Matrix & >)> func)
int func(const int &a)
Definition: testDSF.cpp:225
Non-linear factor base classes.
Vector evaluateError(const T1 &params1, const T2 &params2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
const Symbol key2('v', 2)
void serialize(ARCHIVE &ar, const unsigned int)
SharedNoiseModel noiseModel_
noise model
static double error
Definition: testRot3.cpp:39
const G double tol
Definition: Group.h:83
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
NonlinearFactor::shared_ptr clone() const override
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
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:59
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
SharedNoiseModel noiseModel_
noise model


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:05