27 #include <boost/shared_ptr.hpp> 86 typedef std::map<Key, size_t>
Dims;
101 template<
class CONTAINER>
108 template<
typename ITERATOR>
125 size_t size()
const {
return values_.size(); }
128 size_t dim(
Key j)
const {
return at(j).rows(); }
138 iterator item = find(j);
140 throw std::out_of_range(
151 const_iterator item = find(j);
153 throw std::out_of_range(
176 iterator
insert(
const std::pair<Key, Vector>& key_value);
182 template<
class... Args>
184 #if ! defined(GTSAM_USE_TBB) || defined (TBB_GREATER_EQUAL_2020) 185 return values_.emplace(std::piecewise_construct, std::forward_as_tuple(j), std::forward_as_tuple(
args...));
187 return values_.insert(std::make_pair(j,
Vector(std::forward<Args>(
args)...)));
196 return insert(std::make_pair(j, value));
208 #ifdef TBB_GREATER_EQUAL_2020 209 return values_.emplace(j, value);
211 return values_.insert(std::make_pair(j, value));
218 throw std::invalid_argument(
"Requested variable '" +
220 "', is not in this VectorValues.");
226 iterator
begin() {
return values_.begin(); }
227 const_iterator
begin()
const {
return values_.begin(); }
228 iterator
end() {
return values_.end(); }
229 const_iterator
end()
const {
return values_.end(); }
241 const_iterator
find(
Key j)
const {
return values_.find(j); }
247 void print(
const std::string&
str =
"VectorValues",
261 template <
typename CONTAINER>
265 items.reserve(keys.end() - keys.begin());
268 totalDim += v->size();
274 for (
const Vector*
v : items) {
275 result.segment(pos,
v->size()) = *
v;
283 Vector vector(
const Dims& dims)
const;
304 double squaredNorm()
const;
357 friend class boost::serialization::access;
358 template<
class ARCHIVE>
360 ar & BOOST_SERIALIZATION_NVP(values_);
void print(const Matrix &A, const string &s, ostream &stream)
constexpr int last(int, int result)
iterator insert(Key j, const Vector &value)
VectorValues(const CONTAINER &c)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Values::iterator iterator
Iterator over vector values.
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator*=(half &a, const half &b)
double dot(const V1 &a, const V2 &b)
Vector & operator[](Key j)
const_iterator find(Key j) const
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Values::value_type value_type
Typedef to pair<Key, Vector>
iterator end()
Iterator over variables.
std::map< Key, size_t > Dims
Keyed vector dimensions.
Point2 operator*(double s, const Point2 &p)
multiply with scalar
static const KeyFormatter DefaultKeyFormatter
ptrdiff_t DenseIndex
The index type for Eigen objects.
const KeyFormatter & formatter
graph add(boost::make_shared< UnaryFactor >(1, 0.0, 0.0, unaryNoise))
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Included from all GTSAM files.
ConcurrentMap< Key, Vector > Values
Collection of Vectors making up a VectorValues.
boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::iterator > iterator
Mutable forward iterator, with value type KeyValuePair.
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
constexpr int first(int i)
Implementation details for constexpr functions.
VectorValues(ITERATOR first, ITERATOR last)
Values values_
Vectors making up this VectorValues.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const_iterator begin() const
Iterator over variables.
const Vector & operator[](Key j) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_iterator > const_iterator
Const forward iterator, with value type ConstKeyValuePair.
value_type KeyValuePair
Typedef to pair<Key, Vector>
BinarySumExpression< T > operator-(const Expression< T > &e1, const Expression< T > &e2)
Construct an expression that subtracts one expression from another.
Values::const_iterator const_iterator
Const iterator over vector values.
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half & operator+=(half &a, const half &b)
Maps global variable indices to slot indices.
VectorValues(const VectorValues &c)
A thin wrapper around std::vector that uses a custom allocator.
typedef and functions to augment Eigen's VectorXd
Vector vector(const CONTAINER &keys) const
void unsafe_erase(typename Base::iterator position)
BinarySumExpression< T > operator+(const Expression< T > &e1, const Expression< T > &e2)
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
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 scale
const_iterator end() const
Iterator over variables.
std::pair< VectorValues::iterator, bool > emplace(Key j, Args &&...args)
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
iterator begin()
Iterator over variables.
void serialize(ARCHIVE &ar, const unsigned int)
const Vector & at(Key j) const
std::uint64_t Key
Integer nonlinear key type.