#include <simulated2D.h>
Public Types | |
typedef gtsam::Values | Base |
base class More... | |
typedef boost::shared_ptr< Point2 > | sharedPoint |
shortcut to shared Point type More... | |
Public Types inherited from gtsam::Values | |
typedef boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_iterator > | const_iterator |
Const forward iterator, with value type ConstKeyValuePair. More... | |
typedef boost::transform_iterator< boost::function1< ConstKeyValuePair, const ConstKeyValuePtrPair & >, KeyValueMap::const_reverse_iterator > | const_reverse_iterator |
Const reverse iterator, with value type ConstKeyValuePair. More... | |
typedef boost::shared_ptr< const Values > | const_shared_ptr |
A const shared_ptr to this class. More... | |
typedef boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::iterator > | iterator |
Mutable forward iterator, with value type KeyValuePair. More... | |
typedef boost::transform_iterator< boost::function1< KeyValuePair, const KeyValuePtrPair & >, KeyValueMap::reverse_iterator > | reverse_iterator |
Mutable reverse iterator, with value type KeyValuePair. More... | |
typedef boost::shared_ptr< Values > | shared_ptr |
A shared_ptr to this class. More... | |
typedef KeyValuePair | value_type |
Public Member Functions | |
void | insertPoint (Key j, const Point2 &p) |
Insert a point. More... | |
void | insertPose (Key i, const Point2 &p) |
Insert a pose. More... | |
int | nrPoints () const |
Number of points. More... | |
int | nrPoses () const |
Number of poses. More... | |
Point2 | point (Key j) const |
Return point j. More... | |
Point2 | pose (Key i) const |
Return pose i. More... | |
Values () | |
Constructor. More... | |
Values (const Base &base) | |
Copy constructor. More... | |
Public Member Functions inherited from gtsam::Values | |
template<typename ValueType > | |
const ValueType | at (Key j) const |
const Value & | at (Key j) const |
double | atDouble (size_t key) const |
version for double More... | |
const_iterator | begin () const |
iterator | begin () |
void | clear () |
template<class ValueType > | |
size_t | count () const |
size_t | dim () const |
bool | empty () const |
const_iterator | end () const |
iterator | end () |
void | erase (Key j) |
bool | exists (Key j) const |
template<typename ValueType > | |
boost::optional< const ValueType & > | exists (Key j) const |
Filtered< Value > | filter (const boost::function< bool(Key)> &filterFcn) |
template<class ValueType > | |
Filtered< ValueType > | filter (const boost::function< bool(Key)> &filterFcn=&_truePredicate< Key >) |
ConstFiltered< Value > | filter (const boost::function< bool(Key)> &filterFcn) const |
template<class ValueType > | |
ConstFiltered< ValueType > | filter (const boost::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const |
iterator | find (Key j) |
const_iterator | find (Key j) const |
void | insert (Key j, const Value &val) |
void | insert (const Values &values) |
template<typename ValueType > | |
void | insert (Key j, const ValueType &val) |
void | insertDouble (Key j, double c) |
version for double More... | |
KeyVector | keys () const |
iterator | lower_bound (Key j) |
const_iterator | lower_bound (Key j) const |
Values & | operator= (const Values &rhs) |
const_reverse_iterator | rbegin () const |
reverse_iterator | rbegin () |
const_reverse_iterator | rend () const |
reverse_iterator | rend () |
size_t | size () const |
void | swap (Values &other) |
std::pair< iterator, bool > | tryInsert (Key j, const Value &value) |
void | update (Key j, const Value &val) |
template<typename T > | |
void | update (Key j, const T &val) |
void | update (const Values &values) |
template<typename ValueType > | |
void | update (Key j, const ValueType &val) |
iterator | upper_bound (Key j) |
const_iterator | upper_bound (Key j) const |
Values () | |
Values (const Values &other) | |
Values (Values &&other) | |
Values (std::initializer_list< ConstKeyValuePair > init) | |
Values (const Values &other, const VectorValues &delta) | |
template<class ValueType > | |
Values (const Filtered< ValueType > &view) | |
template<class ValueType > | |
Values (const ConstFiltered< ValueType > &view) | |
template<class ValueType > | |
Values (const Values::Filtered< ValueType > &view) | |
template<class ValueType > | |
Values (const Values::ConstFiltered< ValueType > &view) | |
VectorValues | zeroVectors () const |
void | print (const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
bool | equals (const Values &other, double tol=1e-9) const |
Values | retract (const VectorValues &delta) const |
VectorValues | localCoordinates (const Values &cp) const |
Private Attributes | |
int | nrPoints_ |
int | nrPoses_ |
Custom Values class that holds poses and points, mainly used as a convenience for MATLAB wrapper
Definition at line 36 of file simulated2D.h.
typedef gtsam::Values simulated2D::Values::Base |
base class
Definition at line 41 of file simulated2D.h.
typedef boost::shared_ptr<Point2> simulated2D::Values::sharedPoint |
shortcut to shared Point type
Definition at line 42 of file simulated2D.h.
|
inline |
Constructor.
Definition at line 45 of file simulated2D.h.
|
inline |
Copy constructor.
Definition at line 49 of file simulated2D.h.
Insert a point.
Definition at line 60 of file simulated2D.h.
Insert a pose.
Definition at line 54 of file simulated2D.h.
|
inline |
Number of points.
Definition at line 71 of file simulated2D.h.
|
inline |
Number of poses.
Definition at line 66 of file simulated2D.h.
Return point j.
Definition at line 81 of file simulated2D.h.
Return pose i.
Definition at line 76 of file simulated2D.h.
|
private |
Definition at line 38 of file simulated2D.h.
|
private |
Definition at line 38 of file simulated2D.h.