gtsam 4.1.1
gtsam
utilities.h File Reference

Contains generic global functions designed particularly for the matlab interface. More...

Go to the source code of this file.

Namespaces

namespace  gtsam
 Global functions in a separate testing namespace.
 

Functions

FastList< Key > gtsam::utilities::createKeyList (const Vector &I)
 
FastList< Key > gtsam::utilities::createKeyList (std::string s, const Vector &I)
 
KeyVector gtsam::utilities::createKeyVector (const Vector &I)
 
KeyVector gtsam::utilities::createKeyVector (std::string s, const Vector &I)
 
KeySet gtsam::utilities::createKeySet (const Vector &I)
 
KeySet gtsam::utilities::createKeySet (std::string s, const Vector &I)
 
Matrix gtsam::utilities::extractPoint2 (const Values &values)
 Extract all Point2 values into a single matrix [x y].
 
Matrix gtsam::utilities::extractPoint3 (const Values &values)
 Extract all Point3 values into a single matrix [x y z].
 
Values gtsam::utilities::allPose2s (const Values &values)
 Extract all Pose3 values.
 
Matrix gtsam::utilities::extractPose2 (const Values &values)
 Extract all Pose2 values into a single matrix [x y theta].
 
Values gtsam::utilities::allPose3s (const Values &values)
 Extract all Pose3 values.
 
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].
 
void gtsam::utilities::perturbPoint2 (Values &values, double sigma, int32_t seed=42u)
 Perturb all Point2 values using normally distributed noise.
 
void gtsam::utilities::perturbPose2 (Values &values, double sigmaT, double sigmaR, int32_t seed=42u)
 Perturb all Pose2 values using normally distributed noise.
 
void gtsam::utilities::perturbPoint3 (Values &values, double sigma, int32_t seed=42u)
 Perturb all Point3 values using normally distributed noise.
 
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. More...
 
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. More...
 
Matrix gtsam::utilities::reprojectionErrors (const NonlinearFactorGraph &graph, const Values &values)
 Calculate the errors of all projection factors in a graph.
 
Values gtsam::utilities::localToWorld (const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector())
 Convert from local to world coordinates.
 

Detailed Description

Contains generic global functions designed particularly for the matlab interface.

Author
Stephen Williams

Function Documentation

◆ insertBackprojections()

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.

Parameters
valuesThe values dict to insert the backprojections to.
cameraThe camera model.
JVector of key indices.
Z2*J matrix of pixel values.
depthInitial depth value.

◆ insertProjectionFactors()

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.

Parameters
graphThe nonlinear factor graph to add the factors to.
iCamera key.
JVector of key indices.
Z2*J matrix of pixel values.
modelFactor noise model.
KCalibration matrix.
body_P_sensorPose of the camera sensor in the body frame.