58 template <
typename R,
typename T>
65 std::function<R(T, boost::optional<Matrix &>)> func_;
79 const std::function<
R(
T, boost::optional<Matrix &>)>
func)
80 :
Base(model, key), measured_(z), noiseModel_(model), func_(
func) {}
91 boost::none)
const override {
92 R x = func_(params,
H);
100 const std::string &
s =
"",
103 std::cout <<
s << (
s !=
"" ?
" " :
"") <<
"FunctorizedFactor(" 104 << keyFormatter(this->
key()) <<
")" << std::endl;
106 std::cout <<
" noise model sigmas: " << noiseModel_->sigmas().transpose()
113 return e && Base::equals(other,
tol) &&
120 friend class boost::serialization::access;
121 template <
class ARCHIVE>
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_);
131 template <
typename R,
typename T>
133 :
public Testable<FunctorizedFactor<R, T>> {};
141 template <
typename T,
typename R,
typename FUNC>
157 template <
typename R,
typename T1,
typename T2>
164 using FunctionType = std::function<R(T1, T2, boost::optional<Matrix &>,
165 boost::optional<Matrix &>)>;
181 :
Base(model, key1, key2),
195 const T1 ¶ms1,
const T2 ¶ms2,
196 boost::optional<Matrix &> H1 = boost::none,
197 boost::optional<Matrix &> H2 = boost::none)
const override {
198 R x = func_(params1, params2, H1, H2);
206 const std::string &
s =
"",
209 std::cout <<
s << (
s !=
"" ?
" " :
"") <<
"FunctorizedFactor2(" 210 << keyFormatter(this->
key1()) <<
", " 211 << keyFormatter(this->
key2()) <<
")" << std::endl;
213 std::cout <<
" noise model sigmas: " << noiseModel_->sigmas().transpose()
220 return e && Base::equals(other,
tol) &&
227 friend class boost::serialization::access;
228 template <
class ARCHIVE>
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_);
238 template <
typename R,
typename T1,
typename T2>
240 :
public Testable<FunctorizedFactor2<R, T1, T2>> {};
248 template <
typename T1,
typename T2,
typename R,
typename FUNC>
void print(const Matrix &A, const string &s, ostream &stream)
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 ¶ms, 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
FunctorizedFactor2< R, T1, T2 > MakeFunctorizedFactor2(Key key1, Key key2, const R &z, const SharedNoiseModel &model, const FUNC func)
const Symbol key1('v', 1)
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.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
FunctorizedFactor< R, T > MakeFunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, const FUNC func)
static SmartStereoProjectionParams params
FunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, const std::function< R(T, boost::optional< Matrix & >)> func)
Non-linear factor base classes.
Vector evaluateError(const T1 ¶ms1, const T2 ¶ms2, 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
~FunctorizedFactor() override
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.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel
SharedNoiseModel noiseModel_
noise model
~FunctorizedFactor2() override