31 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 32 #include <boost/serialization/base_object.hpp> 35 #include <type_traits> 49 #define OptionalNone static_cast<Matrix*>(nullptr) 89 template<
typename CONTAINER>
129 virtual size_t dim()
const = 0;
144 virtual std::shared_ptr<GaussianFactor>
145 linearize(
const Values& c)
const = 0;
155 throw std::runtime_error(
"NonlinearFactor::clone(): Attempting to clone factor with no clone() implemented!");
164 virtual shared_ptr rekey(
const std::map<Key,Key>& rekey_mapping)
const;
170 virtual shared_ptr rekey(
const KeyVector& new_keys)
const;
220 template<
typename CONTAINER>
222 Base(keys), noiseModel_(noiseModel) {}
233 void print(
const std::string&
s =
"",
237 bool equals(
const NonlinearFactor&
f,
double tol = 1
e-9)
const override;
240 size_t dim()
const override {
241 return noiseModel_->dim();
264 return unwhitenedError(x, &H);
281 double weight(
const Values& c)
const;
296 std::shared_ptr<GaussianFactor> linearize(
const Values& x)
const override;
305 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 307 friend class boost::serialization::access;
308 template<
class ARCHIVE>
309 void serialize(ARCHIVE & ar,
const unsigned int ) {
310 ar & boost::serialization::make_nvp(
"NonlinearFactor",
311 boost::serialization::base_object<Base>(*
this));
312 ar & BOOST_SERIALIZATION_NVP(noiseModel_);
332 template <
typename,
typename...>
334 template <
typename T1>
339 template <
typename T1,
typename T2>
344 template <
typename T1,
typename T2,
typename T3>
350 template <
typename T1,
typename T2,
typename T3,
typename T4>
357 template <
typename T1,
typename T2,
typename T3,
typename T4,
typename T5>
365 template <
typename T1,
typename T2,
typename T3,
typename T4,
typename T5,
366 typename T6,
typename... TExtra>
430 template <
class... ValueTypes>
436 enum {
N =
sizeof...(ValueTypes) };
447 template <
typename From,
typename To>
452 using IndexIsValid =
typename std::enable_if<(I >= 1) && (
I <=
N),
455 template <
typename Container>
457 typename std::decay<decltype(*std::declval<Container>().begin())>::
type;
458 template <
typename Container>
465 template <
typename Ret,
typename ...Args>
469 template<
typename Arg>
472 template<
typename Arg>
473 using IsNullpointer = std::is_same<typename std::decay_t<Arg>, std::nullptr_t>;
479 template <
typename Ret,
typename ...Args>
488 template <
typename T =
void>
493 template <
typename T>
500 template <
typename T =
void>
523 template <
int I,
typename = IndexIsVal
id<I>>
525 typename std::tuple_element<
I - 1, std::tuple<ValueTypes...>>
::type;
553 template <
typename CONTAINER = std::initializer_list<Key>,
554 typename = IsContainerOfKeys<CONTAINER>>
556 :
Base(noiseModel, keys) {
557 if (keys.size() !=
N) {
558 throw std::invalid_argument(
559 "NoiseModelFactorN: wrong number of keys given");
583 static_assert(I <=
N,
"Index out of bounds");
639 virtual Vector evaluateError(
const ValueTypes&...
x,
650 return evaluateError(x..., (&H)...);
671 template <
typename... OptionalJacArgs,
typename = IndexIsValid<
sizeof...(OptionalJacArgs) + 1>>
673 OptionalJacArgs&&... H)
const {
674 return evaluateError(x..., (&H)...);
681 template <
typename... OptionalJacArgs,
typename = IndexIsValid<
sizeof...(OptionalJacArgs) + 1>>
683 OptionalJacArgs&&... H)
const {
687 return evaluateError(x...,
688 std::forward<OptionalJacArgs>(H)..., static_cast<OptionalMatrixType>(
OptionalNone));
705 if (this->active(x)) {
707 return evaluateError(x.
at<ValueTypes>(keys_[
Indices])...,
710 return evaluateError(x.
at<ValueTypes>(keys_[
Indices])...);
713 return Vector::Zero(this->dim());
717 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 719 friend class boost::serialization::access;
720 template <
class ARCHIVE>
721 void serialize(ARCHIVE& ar,
const unsigned int ) {
722 ar& boost::serialization::make_nvp(
723 "NoiseModelFactor", boost::serialization::base_object<Base>(*
this));
736 static_assert(I <=
N,
"Index out of bounds");
741 static_assert(I <=
N,
"Index out of bounds");
746 static_assert(I <=
N,
"Index out of bounds");
751 static_assert(I <=
N,
"Index out of bounds");
756 static_assert(I <=
N,
"Index out of bounds");
764 #define NoiseModelFactor1 NoiseModelFactorN 765 #define NoiseModelFactor2 NoiseModelFactorN 766 #define NoiseModelFactor3 NoiseModelFactorN 767 #define NoiseModelFactor4 NoiseModelFactorN 768 #define NoiseModelFactor5 NoiseModelFactorN 769 #define NoiseModelFactor6 NoiseModelFactorN void print(const Matrix &A, const string &s, ostream &stream)
std::is_same< typename std::decay_t< Arg >, Matrix *> IsMatrixPointer
NoiseModelFactorN(const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
std::vector< Matrix > * OptionalMatrixVecType
size_t dim() const override
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
A non-templated config holding any types of Manifold-group elements.
std::string serialize(const T &input)
serializes to a string
typename std::enable_if< std::is_convertible< From, To >::value, void >::type IsConvertible
const ValueType at(Key j) const
std::is_same< typename std::decay_t< Arg >, std::nullptr_t > IsNullpointer
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
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
typename std::decay< decltype(*std::declval< Container >().begin())>::type ContainerElementType
static const KeyFormatter DefaultKeyFormatter
Vector unwhitenedError(gtsam::index_sequence< Indices... >, const Values &x, OptionalMatrixVecType H=nullptr) const
Vector unwhitenedError(const Values &x, std::vector< Matrix > &H) const
static const Similarity3 T4(R, P, s)
~NoiseModelFactor() override
Vector evaluateError(const ValueTypes &... x) const
const SharedNoiseModel & noiseModel() const
access to the noise model
Matrix * OptionalMatrixType
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
NoiseModelFactor(const SharedNoiseModel &noiseModel, const CONTAINER &keys)
static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
NoiseModelFactorN(const SharedNoiseModel &noiseModel, CONTAINER keys)
std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret > AreAllMatrixPtrs
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Vector evaluateError(const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
std::shared_ptr< This > shared_ptr
~NoiseModelFactorN() override
virtual Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const =0
SharedNoiseModel noiseModel_
NoiseModelFactorN()
Default Constructor for I/O.
virtual bool active(const Values &) const
IsConvertible< ContainerElementType< Container >, Key > IsContainerOfKeys
Matrix * OptionalMatrixTypeT
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
std::shared_ptr< This > shared_ptr
typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type ValueType
virtual bool sendable() const
static const Similarity3 T5(R, P, 10)
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
std::vector< size_t > Indices
typename std::enable_if<(I >=1) &&(I<=N), void >::type IndexIsValid
Special class for optional Jacobian arguments.
std::enable_if_t<(... &&std::is_convertible< Args, Matrix &>::value), Ret > AreAllMatrixRefs
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
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
virtual shared_ptr clone() const
NoiseModelFactor(const SharedNoiseModel &noiseModel)
NonlinearFactor(const CONTAINER &keys)
std::uint64_t Key
Integer nonlinear key type.
noiseModel::Base::shared_ptr SharedNoiseModel
The base class for all factors.