#include <simulated2DOriented.h>
Public Member Functions | |
void | insertPoint (Key j, const Point2 &p) |
insert a landmark More... | |
void | insertPose (Key i, const Pose2 &p) |
insert a pose More... | |
int | nrPoints () const |
nr of landmarks More... | |
int | nrPoses () const |
nr of poses More... | |
Point2 | point (Key j) const |
get a landmark More... | |
Pose2 | pose (Key i) const |
get a pose More... | |
Values () | |
Public Member Functions inherited from gtsam::Values | |
void | clear () |
template<class ValueType > | |
size_t | count () const |
size_t | dim () const |
std::map< Key, size_t > | dims () const |
void | erase (Key j) |
template<class ValueType > | |
std::map< Key, ValueType > | extract (const std::function< bool(Key)> &filterFcn=&_truePredicate< Key >) const |
void | insert (Key j, const Value &val) |
void | insert (const Values &values) |
template<typename ValueType > | |
void | insert (Key j, const ValueType &val) |
void | insert_or_assign (Key j, const Value &val) |
If key j exists, update value, else perform an insert. More... | |
void | insert_or_assign (const Values &values) |
template<typename ValueType > | |
void | insert_or_assign (Key j, const ValueType &val) |
Templated version to insert_or_assign a variable with the given j. More... | |
void | insertDouble (Key j, double c) |
version for double More... | |
KeyVector | keys () const |
KeySet | keySet () const |
Values & | operator= (const Values &rhs) |
void | swap (Values &other) |
template<typename ValueType > | |
void | update (Key j, const ValueType &val) |
void | update (Key j, const Value &val) |
template<typename T > | |
void | update (Key j, const T &val) |
void | update (const Values &values) |
VectorValues | zeroVectors () const |
Values ()=default | |
Values (const Values &other) | |
Values (Values &&other) | |
Values (std::initializer_list< ConstKeyValuePair > init) | |
Values (const Values &other, const VectorValues &delta) | |
void | print (const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const |
bool | equals (const Values &other, double tol=1e-9) const |
template<typename ValueType > | |
const ValueType | at (Key j) const |
double | atDouble (size_t key) const |
version for double More... | |
const Value & | at (Key j) const |
bool | exists (Key j) const |
template<typename ValueType > | |
const ValueType * | exists (Key j) const |
size_t | size () const |
bool | empty () const |
deref_iterator | begin () const |
deref_iterator | end () const |
deref_iterator | find (Key j) const |
deref_iterator | lower_bound (Key j) const |
deref_iterator | upper_bound (Key j) const |
Values | retract (const VectorValues &delta) const |
void | retractMasked (const VectorValues &delta, const KeySet &mask) |
VectorValues | localCoordinates (const Values &cp) const |
Private Attributes | |
int | nrPoints_ |
int | nrPoses_ |
Additional Inherited Members | |
Public Types inherited from gtsam::Values | |
typedef std::shared_ptr< const Values > | const_shared_ptr |
A const shared_ptr to this class. More... | |
typedef std::shared_ptr< Values > | shared_ptr |
A shared_ptr to this class. More... | |
typedef KeyValuePair | value_type |
Specialized Values structure with syntactic sugar for compatibility with matlab
Definition at line 34 of file simulated2DOriented.h.
|
inline |
Definition at line 37 of file simulated2DOriented.h.
insert a landmark
Definition at line 46 of file simulated2DOriented.h.
insert a pose
Definition at line 40 of file simulated2DOriented.h.
|
inline |
nr of landmarks
Definition at line 52 of file simulated2DOriented.h.
|
inline |
nr of poses
Definition at line 51 of file simulated2DOriented.h.
get a landmark
Definition at line 55 of file simulated2DOriented.h.
get a pose
Definition at line 54 of file simulated2DOriented.h.
|
private |
Definition at line 35 of file simulated2DOriented.h.
|
private |
Definition at line 35 of file simulated2DOriented.h.