Public Types | Public Member Functions | Static Public Member Functions | List of all members
gtsam::FixedVector< N > Class Template Reference

#include <FixedVector.h>

Inheritance diagram for gtsam::FixedVector< N >:
Inheritance graph
[legend]

Public Types

typedef Eigen::Matrix< double, N, 1 > Base
 
- Public Types inherited from Eigen::Matrix< double, N, 1 >
enum  
 
typedef PlainObjectBase< MatrixBase
 Base class typedef. More...
 
typedef Base::PlainObject PlainObject
 
- Public Types inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
enum  
 
enum  
 
typedef Eigen::Map< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols >, AlignedMax > AlignedMapType
 
typedef internal::dense_xpr_base< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::type Base
 
typedef Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > DenseType
 
typedef Eigen::Map< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols >, Unaligned > MapType
 
typedef internal::packet_traits< Scalar >::type PacketScalar
 
typedef NumTraits< Scalar >::Real RealScalar
 
typedef internal::traits< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::Scalar Scalar
 
typedef internal::traits< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::StorageKind StorageKind
 
enum  
 

Public Member Functions

bool equals (const FixedVector &other, double tol=1e-9) const
 
template<size_t M>
bool equals (const FixedVector< M > &other, double tol=1e-9) const
 
 FixedVector ()
 
 FixedVector (const double *values)
 
 FixedVector (const FixedVector &v)
 
 FixedVector (const Vector &v)
 
void print (const std::string &name="") const
 
- Public Member Functions inherited from Eigen::Matrix< double, N, 1 >
EIGEN_DEVICE_FUNC Basebase ()
 
const EIGEN_DEVICE_FUNC Basebase () const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScalarcoeffRef (Index index)
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE ScalarcoeffRef (Index index) const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScalarcoeffRef (Index rowId, Index colId)
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE ScalarcoeffRef (Index rowId, Index colId) const
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index innerStride () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix ()
 Default constructor. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const EigenBase< OtherDerived > &other)
 Copy constructor for generic expressions. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const Matrix &other)
 Copy constructor. More...
 
EIGEN_DEVICE_FUNC Matrix (const RotationBase< OtherDerived, ColsAtCompileTime > &r)
 Constructs a Dim x Dim rotation matrix from the rotation r. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const Scalar &x, const Scalar &y, const Scalar &z)
 Constructs an initialized 3D vector with given coefficients. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const Scalar &x, const Scalar &y, const Scalar &z, const Scalar &w)
 Constructs an initialized 4D vector with given coefficients. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const T &x)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (const T0 &x, const T1 &y)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix (internal::constructor_without_unaligned_array_assert)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrixoperator= (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrixoperator= (const EigenBase< OtherDerived > &other)
 Copies the generic expression other into *this. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrixoperator= (const Matrix &other)
 Assigns matrices to each other. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrixoperator= (const ReturnByValue< OtherDerived > &func)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Storage, _MaxRows, _MaxCols > & operator= (const RotationBase< OtherDerived, ColsAtCompileTime > &r)
 Set a Dim x Dim rotation matrix from the rotation r. More...
 
EIGEN_DEVICE_FUNC Matrixoperator= (const RotationBase< OtherDerived, ColsAtCompileTime > &r)
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index outerStride () const EIGEN_NOEXCEPT
 
- Public Member Functions inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
EIGEN_DEVICE_FUNC Basebase ()
 
const EIGEN_DEVICE_FUNC Basebase () const
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalarcoeff (Index index) const
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalarcoeff (Index rowId, Index colId) const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScalarcoeffRef (Index index)
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE ScalarcoeffRef (Index index) const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScalarcoeffRef (Index rowId, Index colId)
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE ScalarcoeffRef (Index rowId, Index colId) const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize (Index rows, Index cols)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize (Index rows, NoChange_t)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize (Index size)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize (NoChange_t, Index cols)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResizeLike (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalardata ()
 
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalardata () const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & lazyAssign (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & operator= (const EigenBase< OtherDerived > &other)
 Copies the generic expression other into *this. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & operator= (const PlainObjectBase &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & operator= (const ReturnByValue< OtherDerived > &func)
 
EIGEN_STRONG_INLINE PacketScalar packet (Index index) const
 
EIGEN_STRONG_INLINE PacketScalar packet (Index rowId, Index colId) const
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize (Index rows, Index cols)
 
EIGEN_DEVICE_FUNC void resize (Index rows, NoChange_t)
 
EIGEN_DEVICE_FUNC void resize (Index size)
 
EIGEN_DEVICE_FUNC void resize (NoChange_t, Index cols)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resizeLike (const EigenBase< OtherDerived > &_other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows () const EIGEN_NOEXCEPT
 
EIGEN_STRONG_INLINE void writePacket (Index index, const PacketScalar &val)
 
EIGEN_STRONG_INLINE void writePacket (Index rowId, Index colId, const PacketScalar &val)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setConstant (Index size, const Scalar &val)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setConstant (Index rows, Index cols, const Scalar &val)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setConstant (NoChange_t, Index cols, const Scalar &val)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setConstant (Index rows, NoChange_t, const Scalar &val)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero (Index size)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero (Index rows, Index cols)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero (NoChange_t, Index cols)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setZero (Index rows, NoChange_t)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setOnes (Index size)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setOnes (Index rows, Index cols)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setOnes (NoChange_t, Index cols)
 
EIGEN_DEVICE_FUNC Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setOnes (Index rows, NoChange_t)
 
Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setRandom (Index size)
 
Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setRandom (Index rows, Index cols)
 
Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setRandom (NoChange_t, Index cols)
 
Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & setRandom (Index rows, NoChange_t)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap (DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void swap (DenseBase< OtherDerived > const &other)
 

Static Public Member Functions

static FixedVector basis (size_t i)
 
static FixedVector delta (size_t i, double value)
 
static size_t dim ()
 
static FixedVector ones ()
 
static FixedVector repeat (double value)
 
static FixedVector zero ()
 
- Static Public Member Functions inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
static ConstMapType Map (const Scalar *data)
 
static MapType Map (Scalar *data)
 
static ConstMapType Map (const Scalar *data, Index size)
 
static MapType Map (Scalar *data, Index size)
 
static ConstMapType Map (const Scalar *data, Index rows, Index cols)
 
static MapType Map (Scalar *data, Index rows, Index cols)
 
static StridedConstMapType< Stride< Outer, Inner > >::type Map (const Scalar *data, const Stride< Outer, Inner > &stride)
 
static StridedMapType< Stride< Outer, Inner > >::type Map (Scalar *data, const Stride< Outer, Inner > &stride)
 
static StridedConstMapType< Stride< Outer, Inner > >::type Map (const Scalar *data, Index size, const Stride< Outer, Inner > &stride)
 
static StridedMapType< Stride< Outer, Inner > >::type Map (Scalar *data, Index size, const Stride< Outer, Inner > &stride)
 
static StridedConstMapType< Stride< Outer, Inner > >::type Map (const Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride)
 
static StridedMapType< Stride< Outer, Inner > >::type Map (Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride)
 
static ConstAlignedMapType MapAligned (const Scalar *data)
 
static AlignedMapType MapAligned (Scalar *data)
 
static ConstAlignedMapType MapAligned (const Scalar *data, Index size)
 
static AlignedMapType MapAligned (Scalar *data, Index size)
 
static ConstAlignedMapType MapAligned (const Scalar *data, Index rows, Index cols)
 
static AlignedMapType MapAligned (Scalar *data, Index rows, Index cols)
 
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type MapAligned (const Scalar *data, const Stride< Outer, Inner > &stride)
 
static StridedAlignedMapType< Stride< Outer, Inner > >::type MapAligned (Scalar *data, const Stride< Outer, Inner > &stride)
 
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type MapAligned (const Scalar *data, Index size, const Stride< Outer, Inner > &stride)
 
static StridedAlignedMapType< Stride< Outer, Inner > >::type MapAligned (Scalar *data, Index size, const Stride< Outer, Inner > &stride)
 
static StridedConstAlignedMapType< Stride< Outer, Inner > >::type MapAligned (const Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride)
 
static StridedAlignedMapType< Stride< Outer, Inner > >::type MapAligned (Scalar *data, Index rows, Index cols, const Stride< Outer, Inner > &stride)
 
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _check_template_params ()
 

Additional Inherited Members

- Public Attributes inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
const typedef Eigen::Map< const Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols >, AlignedMax > ConstAlignedMapType
 
const typedef Eigen::Map< const Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols >, Unaligned > ConstMapType
 
- Protected Member Functions inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase ()
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase (const EigenBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase (const PlainObjectBase &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase (const ReturnByValue< OtherDerived > &other)
 Copy constructor with in-place evaluation. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase (Index size, Index rows, Index cols)
 
EIGEN_DEVICE_FUNC PlainObjectBase (internal::constructor_without_unaligned_array_assert)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _resize_to_match (const EigenBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & _set (const DenseBase< OtherDerived > &other)
 Copies the value of the expression other into *this with automatic resizing. More...
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > & _set_noalias (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2 (Index rows, Index cols, typename internal::enable_if< Base::SizeAtCompileTime!=2, T0 >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2 (const T0 &val0, const T1 &val1, typename internal::enable_if< Base::SizeAtCompileTime==2, T0 >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init2 (const Index &val0, const Index &val1, typename internal::enable_if<(!internal::is_same< Index, Scalar >::value) &&(internal::is_same< T0, Index >::value) &&(internal::is_same< T1, Index >::value) &&Base::SizeAtCompileTime==2, T1 >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (Index size, typename internal::enable_if<(Base::SizeAtCompileTime!=1||!internal::is_convertible< T, Scalar >::value) &&((!internal::is_same< typename internal::traits< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::XprKind, ArrayXpr >::value||Base::SizeAtCompileTime==Dynamic)), T >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Scalar &val0, typename internal::enable_if< Base::SizeAtCompileTime==1 &&internal::is_convertible< T, Scalar >::value, T >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Index &val0, typename internal::enable_if<(!internal::is_same< Index, Scalar >::value) &&(internal::is_same< Index, T >::value) &&Base::SizeAtCompileTime==1 &&internal::is_convertible< T, Scalar >::value, T * >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Scalar *data)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const DenseBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const EigenBase< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const ReturnByValue< OtherDerived > &other)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const RotationBase< OtherDerived, ColsAtCompileTime > &r)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Scalar &val0, typename internal::enable_if< Base::SizeAtCompileTime!=Dynamic &&Base::SizeAtCompileTime!=1 &&internal::is_convertible< T, Scalar >::value &&internal::is_same< typename internal::traits< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::XprKind, ArrayXpr >::value, T >::type *=0)
 
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _init1 (const Index &val0, typename internal::enable_if<(!internal::is_same< Index, Scalar >::value) &&(internal::is_same< Index, T >::value) &&Base::SizeAtCompileTime!=Dynamic &&Base::SizeAtCompileTime!=1 &&internal::is_convertible< T, Scalar >::value &&internal::is_same< typename internal::traits< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >::XprKind, ArrayXpr >::value, T * >::type *=0)
 
- Protected Attributes inherited from Eigen::Matrix< double, N, 1 >
DenseStorage< Scalar, Base::MaxSizeAtCompileTime, Base::RowsAtCompileTime, Base::ColsAtCompileTime, Optionsm_storage
 
- Protected Attributes inherited from Eigen::PlainObjectBase< Matrix< double, _Rows, _Cols, _Options, _MaxRows, _MaxCols > >
DenseStorage< Scalar, Base::MaxSizeAtCompileTime, Base::RowsAtCompileTime, Base::ColsAtCompileTime, Optionsm_storage
 

Detailed Description

template<size_t N>
class gtsam::FixedVector< N >

Fixed size vectors - compatible with boost vectors, but with compile-type size checking.

Definition at line 30 of file FixedVector.h.

Member Typedef Documentation

◆ Base

template<size_t N>
typedef Eigen::Matrix<double, N, 1> gtsam::FixedVector< N >::Base

Definition at line 32 of file FixedVector.h.

Constructor & Destructor Documentation

◆ FixedVector() [1/4]

template<size_t N>
gtsam::FixedVector< N >::FixedVector ( )
inline

default constructor

Definition at line 35 of file FixedVector.h.

◆ FixedVector() [2/4]

template<size_t N>
gtsam::FixedVector< N >::FixedVector ( const FixedVector< N > &  v)
inline

copy constructors

Definition at line 38 of file FixedVector.h.

◆ FixedVector() [3/4]

template<size_t N>
gtsam::FixedVector< N >::FixedVector ( const Vector v)
inline

Convert from a variable-size vector to a fixed size vector

Definition at line 41 of file FixedVector.h.

◆ FixedVector() [4/4]

template<size_t N>
gtsam::FixedVector< N >::FixedVector ( const double *  values)
inline

Initialize with a C-style array

Definition at line 44 of file FixedVector.h.

Member Function Documentation

◆ basis()

template<size_t N>
static FixedVector gtsam::FixedVector< N >::basis ( size_t  i)
inlinestatic

Create basis vector, with one in spot i

Parameters
iindex of the one
Returns
basis vector

Definition at line 73 of file FixedVector.h.

◆ delta()

template<size_t N>
static FixedVector gtsam::FixedVector< N >::delta ( size_t  i,
double  value 
)
inlinestatic

Create basis vector of with a constant in spot i

Parameters
iindex of the one
valueis the value to insert into the vector
Returns
delta vector

Definition at line 63 of file FixedVector.h.

◆ dim()

template<size_t N>
static size_t gtsam::FixedVector< N >::dim ( )
inlinestatic

Definition at line 85 of file FixedVector.h.

◆ equals() [1/2]

template<size_t N>
bool gtsam::FixedVector< N >::equals ( const FixedVector< N > &  other,
double  tol = 1e-9 
) const
inline

Definition at line 94 of file FixedVector.h.

◆ equals() [2/2]

template<size_t N>
template<size_t M>
bool gtsam::FixedVector< N >::equals ( const FixedVector< M > &  other,
double  tol = 1e-9 
) const
inline

Definition at line 90 of file FixedVector.h.

◆ ones()

template<size_t N>
static FixedVector gtsam::FixedVector< N >::ones ( )
inlinestatic

Create vector initialized to ones

Definition at line 83 of file FixedVector.h.

◆ print()

template<size_t N>
void gtsam::FixedVector< N >::print ( const std::string &  name = "") const
inline

Definition at line 87 of file FixedVector.h.

◆ repeat()

template<size_t N>
static FixedVector gtsam::FixedVector< N >::repeat ( double  value)
inlinestatic

Create vector initialized to a constant value

Parameters
valueconstant value

Definition at line 52 of file FixedVector.h.

◆ zero()

template<size_t N>
static FixedVector gtsam::FixedVector< N >::zero ( )
inlinestatic

Create zero vector

Definition at line 78 of file FixedVector.h.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:17:15