gtsam 4.2.0
gtsam
|
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]. | |
Matrix | gtsam::utilities::extractVectors (const Values &values, char c) |
Extract all Vector values with a given symbol character into an mxn matrix, where m is the number of symbols that match the character and n is the dimension of the variables. More... | |
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. | |
Contains generic global functions designed particularly for the matlab interface.
Matrix gtsam::utilities::extractVectors | ( | const Values & | values, |
char | c | ||
) |
Extract all Vector values with a given symbol character into an mxn matrix, where m is the number of symbols that match the character and n is the dimension of the variables.
If not all variables have dimension n, then a runtime error will be thrown. The order of returned values are sorted by the symbol. For example, calling extractVector(values, 'x'), where values contains 200 variables x1, x2, ..., x200 of type Vector each 5-dimensional, will return a 200x5 matrix with row i containing xi.
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.
values | The values dict to insert the backprojections to. |
camera | The camera model. |
J | Vector of key indices. |
Z | 2*J matrix of pixel values. |
depth | Initial depth value. |
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.
graph | The nonlinear factor graph to add the factors to. |
i | Camera key. |
J | Vector of key indices. |
Z | 2*J matrix of pixel values. |
model | Factor noise model. |
K | Calibration matrix. |
body_P_sensor | Pose of the camera sensor in the body frame. |