Functions
gtsam::utilities Namespace Reference

Functions

Values allPose2s (const Values &values)
 Extract all Pose3 values. More...
 
Values allPose3s (const Values &values)
 Extract all Pose3 values. More...
 
FastList< KeycreateKeyList (const Vector &I)
 
FastList< KeycreateKeyList (std::string s, const Vector &I)
 
KeySet createKeySet (const Vector &I)
 
KeySet createKeySet (std::string s, const Vector &I)
 
KeyVector createKeyVector (const Vector &I)
 
KeyVector createKeyVector (std::string s, const Vector &I)
 
Matrix extractPoint2 (const Values &values)
 Extract all Point2 values into a single matrix [x y]. More...
 
Matrix extractPoint3 (const Values &values)
 Extract all Point3 values into a single matrix [x y z]. More...
 
Matrix extractPose2 (const Values &values)
 Extract all Pose2 values into a single matrix [x y theta]. More...
 
Matrix extractPose3 (const Values &values)
 Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z]. More...
 
void insertBackprojections (Values &values, const PinholeCamera< Cal3_S2 > &camera, const Vector &J, const Matrix &Z, double depth)
 Insert a number of initial point values by backprojecting. More...
 
void insertProjectionFactors (NonlinearFactorGraph &graph, Key i, const Vector &J, const Matrix &Z, const SharedNoiseModel &model, const Cal3_S2::shared_ptr K, const Pose3 &body_P_sensor=Pose3())
 Insert multiple projection factors for a single pose key. More...
 
Values localToWorld (const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
 Convert from local to world coordinates. More...
 
void perturbPoint2 (Values &values, double sigma, int32_t seed=42u)
 Perturb all Point2 values using normally distributed noise. More...
 
void perturbPoint3 (Values &values, double sigma, int32_t seed=42u)
 Perturb all Point3 values using normally distributed noise. More...
 
void perturbPose2 (Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
 Perturb all Pose2 values using normally distributed noise. More...
 
Matrix reprojectionErrors (const NonlinearFactorGraph &graph, const Values &values)
 Calculate the errors of all projection factors in a graph. More...
 

Function Documentation

Values gtsam::utilities::allPose2s ( const Values values)

Extract all Pose3 values.

Definition at line 111 of file nonlinear/utilities.h.

Values gtsam::utilities::allPose3s ( const Values values)

Extract all Pose3 values.

Definition at line 126 of file nonlinear/utilities.h.

FastList<Key> gtsam::utilities::createKeyList ( const Vector I)

Definition at line 40 of file nonlinear/utilities.h.

FastList<Key> gtsam::utilities::createKeyList ( std::string  s,
const Vector I 
)

Definition at line 48 of file nonlinear/utilities.h.

KeySet gtsam::utilities::createKeySet ( const Vector I)

Definition at line 74 of file nonlinear/utilities.h.

KeySet gtsam::utilities::createKeySet ( std::string  s,
const Vector I 
)

Definition at line 82 of file nonlinear/utilities.h.

KeyVector gtsam::utilities::createKeyVector ( const Vector I)

Definition at line 57 of file nonlinear/utilities.h.

KeyVector gtsam::utilities::createKeyVector ( std::string  s,
const Vector I 
)

Definition at line 65 of file nonlinear/utilities.h.

Matrix gtsam::utilities::extractPoint2 ( const Values values)

Extract all Point2 values into a single matrix [x y].

Definition at line 91 of file nonlinear/utilities.h.

Matrix gtsam::utilities::extractPoint3 ( const Values values)

Extract all Point3 values into a single matrix [x y z].

Definition at line 101 of file nonlinear/utilities.h.

Matrix gtsam::utilities::extractPose2 ( const Values values)

Extract all Pose2 values into a single matrix [x y theta].

Definition at line 116 of file nonlinear/utilities.h.

Matrix gtsam::utilities::extractPose3 ( const Values values)

Extract all Pose3 values into a single matrix [r11 r12 r13 r21 r22 r23 r31 r32 r33 x y z].

Definition at line 131 of file nonlinear/utilities.h.

void gtsam::utilities::insertBackprojections ( Values values,
const PinholeCamera< Cal3_S2 > &  camera,
const Vector J,
const Matrix Z,
double  depth 
)

Insert a number of initial point values by backprojecting.

Definition at line 177 of file nonlinear/utilities.h.

void gtsam::utilities::insertProjectionFactors ( NonlinearFactorGraph graph,
Key  i,
const Vector J,
const Matrix Z,
const SharedNoiseModel model,
const Cal3_S2::shared_ptr  K,
const Pose3 body_P_sensor = Pose3() 
)

Insert multiple projection factors for a single pose key.

Definition at line 192 of file nonlinear/utilities.h.

Values gtsam::utilities::localToWorld ( const Values local,
const Pose2 base,
const KeyVector  user_keys = KeyVector() 
)

Convert from local to world coordinates.

Definition at line 229 of file nonlinear/utilities.h.

void gtsam::utilities::perturbPoint2 ( Values values,
double  sigma,
int32_t  seed = 42u 
)

Perturb all Point2 values using normally distributed noise.

Definition at line 146 of file nonlinear/utilities.h.

void gtsam::utilities::perturbPoint3 ( Values values,
double  sigma,
int32_t  seed = 42u 
)

Perturb all Point3 values using normally distributed noise.

Definition at line 167 of file nonlinear/utilities.h.

void gtsam::utilities::perturbPose2 ( Values values,
double  sigmaT,
double  sigmaR,
int32_t  seed = 42u 
)

Perturb all Pose2 values using normally distributed noise.

Definition at line 156 of file nonlinear/utilities.h.

Matrix gtsam::utilities::reprojectionErrors ( const NonlinearFactorGraph graph,
const Values values 
)

Calculate the errors of all projection factors in a graph.

Definition at line 208 of file nonlinear/utilities.h.



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:59:10