Go to the documentation of this file.
32 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
33 #include <boost/serialization/base_object.hpp>
36 #include <type_traits>
50 #define OptionalNone static_cast<gtsam::Matrix*>(nullptr)
90 template<
typename CONTAINER>
130 virtual size_t dim()
const = 0;
145 virtual std::shared_ptr<GaussianFactor>
146 linearize(
const Values&
c)
const = 0;
156 throw std::runtime_error(
"NonlinearFactor::clone(): Attempting to clone factor with no clone() implemented!");
165 virtual shared_ptr rekey(
const std::map<Key,Key>& rekey_mapping)
const;
171 virtual shared_ptr rekey(
const KeyVector& new_keys)
const;
221 template<
typename CONTAINER>
223 Base(
keys), noiseModel_(noiseModel) {}
234 void print(
const std::string&
s =
"",
241 size_t dim()
const override {
242 return noiseModel_->dim();
265 return unwhitenedError(
x, &
H);
282 double weight(
const Values&
c)
const;
297 std::shared_ptr<GaussianFactor> linearize(
const Values&
x)
const override;
306 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
308 friend class boost::serialization::access;
309 template<
class ARCHIVE>
310 void serialize(ARCHIVE & ar,
const unsigned int ) {
311 ar & boost::serialization::make_nvp(
"NonlinearFactor",
312 boost::serialization::base_object<Base>(*
this));
313 ar & BOOST_SERIALIZATION_NVP(noiseModel_);
333 template <
typename,
typename...>
335 template <
typename T1>
340 template <
typename T1,
typename T2>
345 template <
typename T1,
typename T2,
typename T3>
351 template <
typename T1,
typename T2,
typename T3,
typename T4>
358 template <
typename T1,
typename T2,
typename T3,
typename T4,
typename T5>
366 template <
typename T1,
typename T2,
typename T3,
typename T4,
typename T5,
367 typename T6,
typename... TExtra>
431 template <
class... ValueTypes>
437 inline constexpr
static auto N =
sizeof...(ValueTypes);
448 template <
typename From,
typename To>
456 template <
typename Container>
458 typename std::decay<decltype(*std::declval<Container>().begin())>::
type;
459 template <
typename Container>
466 template <
typename Ret,
typename ...Args>
470 template<
typename Arg>
473 template<
typename Arg>
474 using IsNullpointer = std::is_same<typename std::decay_t<Arg>, std::nullptr_t>;
480 template <
typename Ret,
typename ...Args>
489 template <
typename T =
void>
494 template <
typename T>
501 template <
typename T =
void>
524 template <
int I,
typename = IndexIsVal
id<I>>
526 typename std::tuple_element<
I - 1, std::tuple<ValueTypes...>>
::type;
554 template <
typename CONTAINER = std::initializer_list<Key>,
555 typename = IsContainerOfKeys<CONTAINER>>
558 if (
keys.size() !=
N) {
559 throw std::invalid_argument(
560 "NoiseModelFactorN: wrong number of keys given");
584 static_assert(
I <=
N,
"Index out of bounds");
641 OptionalMatrixTypeT<ValueTypes>...
H)
const = 0;
672 template <
typename... OptionalJacArgs,
typename =
IndexIsValid<
sizeof...(OptionalJacArgs) + 1>>
674 OptionalJacArgs&&...
H)
const {
682 template <
typename... OptionalJacArgs,
typename =
IndexIsValid<
sizeof...(OptionalJacArgs) + 1>>
684 OptionalJacArgs&&...
H)
const {
714 return Vector::Zero(this->
dim());
718 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
720 friend class boost::serialization::access;
721 template <
class ARCHIVE>
722 void serialize(ARCHIVE& ar,
const unsigned int ) {
723 ar& boost::serialization::make_nvp(
724 "NoiseModelFactor", boost::serialization::base_object<Base>(*
this));
737 static_assert(
I <=
N,
"Index out of bounds");
742 static_assert(
I <=
N,
"Index out of bounds");
747 static_assert(
I <=
N,
"Index out of bounds");
752 static_assert(
I <=
N,
"Index out of bounds");
757 static_assert(
I <=
N,
"Index out of bounds");
765 #define NoiseModelFactor1 NoiseModelFactorN
766 #define NoiseModelFactor2 NoiseModelFactorN
767 #define NoiseModelFactor3 NoiseModelFactorN
768 #define NoiseModelFactor4 NoiseModelFactorN
769 #define NoiseModelFactor5 NoiseModelFactorN
770 #define NoiseModelFactor6 NoiseModelFactorN
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
std::shared_ptr< This > shared_ptr
size_t dim() const override
Array< double, 1, 3 > e(1./3., 0.5, 2.)
std::is_same< typename std::decay_t< Arg >, Matrix * > IsMatrixPointer
Vector evaluateError(const ValueTypes &... x) const
virtual bool sendable() const
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const =0
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
typename std::enable_if<(I >=1) &&(I<=N), void >::type IndexIsValid
static const Pose3 T3(Rot3::Rodrigues(-90, 0, 0), Point3(1, 2, 3))
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
std::shared_ptr< This > shared_ptr
SharedNoiseModel noiseModel_
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
virtual bool active(const Values &) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
The base class for all factors.
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Vector unwhitenedError(gtsam::index_sequence< Indices... >, const Values &x, OptionalMatrixVecType H=nullptr) const
constexpr static auto N
N is the number of variables (N-way factor)
typename std::decay< decltype(*std::declval< Container >().begin())>::type ContainerElementType
typename std::enable_if< std::is_convertible< From, To >::value, void >::type IsConvertible
void print(const Matrix &A, const string &s, ostream &stream)
static const Similarity3 T4(R, P, s)
NoiseModelFactorN(const SharedNoiseModel &noiseModel, CONTAINER keys)
NonlinearFactor(const CONTAINER &keys)
const SharedNoiseModel & noiseModel() const
access to the noise model
static const Similarity3 T6(Rot3(), Point3(1, 1, 0), 2)
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret > AreAllMatrixPtrs
std::is_same< typename std::decay_t< Arg >, std::nullptr_t > IsNullpointer
static const Similarity3 T5(R, P, 10)
Special class for optional Jacobian arguments.
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
noiseModel::Base::shared_ptr SharedNoiseModel
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
std::vector< Matrix > * OptionalMatrixVecType
NoiseModelFactorN(const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
KeyVector keys_
The keys involved in this factor.
NoiseModelFactor(const SharedNoiseModel &noiseModel, const CONTAINER &keys)
Matrix * OptionalMatrixTypeT
const KeyVector & keys() const
Access the factor's involved variable keys.
NoiseModelFactorN()
Default Constructor for I/O.
Matrix * OptionalMatrixType
~NoiseModelFactorN() override
Vector evaluateError(const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
std::vector< size_t > Indices
IsConvertible< ContainerElementType< Container >, Key > IsContainerOfKeys
typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type ValueType
std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret > AreAllMatrixRefs
std::uint64_t Key
Integer nonlinear key type.
virtual shared_ptr clone() const
typename std::enable_if< B, T >::type enable_if_t
from cpp_future import (convenient aliases from C++14/17)
virtual Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const =0
NoiseModelFactor(const SharedNoiseModel &noiseModel)
~NoiseModelFactor() override
A non-templated config holding any types of Manifold-group elements.
gtsam
Author(s):
autogenerated on Thu Dec 19 2024 04:02:02