Public Types | Public Member Functions | Private Attributes | List of all members
simulated2D::Values Class Reference

#include <simulated2D.h>

Inheritance diagram for simulated2D::Values:
Inheritance graph
[legend]

Public Types

typedef gtsam::Values Base
 base class More...
 
typedef std::shared_ptr< Point2sharedPoint
 shortcut to shared Point type More...
 
- Public Types inherited from gtsam::Values
typedef std::shared_ptr< const Valuesconst_shared_ptr
 A const shared_ptr to this class. More...
 
typedef std::shared_ptr< Valuesshared_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
void clear ()
 
template<class ValueType >
size_t count () const
 
size_t dim () const
 
std::map< Key, size_tdims () 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
 
Valuesoperator= (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 Valueat (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_
 

Detailed Description

Custom Values class that holds poses and points, mainly used as a convenience for MATLAB wrapper

Definition at line 37 of file simulated2D.h.

Member Typedef Documentation

◆ Base

typedef gtsam::Values simulated2D::Values::Base

base class

Definition at line 42 of file simulated2D.h.

◆ sharedPoint

typedef std::shared_ptr<Point2> simulated2D::Values::sharedPoint

shortcut to shared Point type

Definition at line 43 of file simulated2D.h.

Constructor & Destructor Documentation

◆ Values() [1/2]

simulated2D::Values::Values ( )
inline

Constructor.

Definition at line 46 of file simulated2D.h.

◆ Values() [2/2]

simulated2D::Values::Values ( const Base base)
inline

Copy constructor.

Definition at line 50 of file simulated2D.h.

Member Function Documentation

◆ insertPoint()

void simulated2D::Values::insertPoint ( Key  j,
const Point2 p 
)
inline

Insert a point.

Definition at line 61 of file simulated2D.h.

◆ insertPose()

void simulated2D::Values::insertPose ( Key  i,
const Point2 p 
)
inline

Insert a pose.

Definition at line 55 of file simulated2D.h.

◆ nrPoints()

int simulated2D::Values::nrPoints ( ) const
inline

Number of points.

Definition at line 72 of file simulated2D.h.

◆ nrPoses()

int simulated2D::Values::nrPoses ( ) const
inline

Number of poses.

Definition at line 67 of file simulated2D.h.

◆ point()

Point2 simulated2D::Values::point ( Key  j) const
inline

Return point j.

Definition at line 82 of file simulated2D.h.

◆ pose()

Point2 simulated2D::Values::pose ( Key  i) const
inline

Return pose i.

Definition at line 77 of file simulated2D.h.

Member Data Documentation

◆ nrPoints_

int simulated2D::Values::nrPoints_
private

Definition at line 39 of file simulated2D.h.

◆ nrPoses_

int simulated2D::Values::nrPoses_
private

Definition at line 39 of file simulated2D.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:29