Contains generic global functions designed particularly for the matlab interface. More...
#include <gtsam/inference/Symbol.h>
#include <gtsam/slam/ProjectionFactor.h>
#include <gtsam/linear/Sampler.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <exception>
Go to the source code of this file.
Namespaces | |
gtsam | |
traits | |
gtsam::utilities | |
Functions | |
Values | gtsam::utilities::allPose2s (const Values &values) |
Extract all Pose3 values. More... | |
Values | gtsam::utilities::allPose3s (const Values &values) |
Extract all Pose3 values. More... | |
FastList< Key > | gtsam::utilities::createKeyList (const Vector &I) |
FastList< Key > | gtsam::utilities::createKeyList (std::string s, const Vector &I) |
KeySet | gtsam::utilities::createKeySet (const Vector &I) |
KeySet | gtsam::utilities::createKeySet (std::string s, const Vector &I) |
KeyVector | gtsam::utilities::createKeyVector (const Vector &I) |
KeyVector | gtsam::utilities::createKeyVector (std::string s, const Vector &I) |
Matrix | gtsam::utilities::extractPoint2 (const Values &values) |
Extract all Point2 values into a single matrix [x y]. More... | |
Matrix | gtsam::utilities::extractPoint3 (const Values &values) |
Extract all Point3 values into a single matrix [x y z]. More... | |
Matrix | gtsam::utilities::extractPose2 (const Values &values) |
Extract all Pose2 values into a single matrix [x y theta]. More... | |
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]. More... | |
Matrix | gtsam::utilities::extractVectors (const Values &values, char c) |
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... | |
Values | gtsam::utilities::localToWorld (const Values &local, const Pose2 &base, const KeyVector user_keys=KeyVector()) |
Convert from local to world coordinates. More... | |
void | gtsam::utilities::perturbPoint2 (Values &values, double sigma, int32_t seed=42u) |
Perturb all Point2 values using normally distributed noise. More... | |
void | gtsam::utilities::perturbPoint3 (Values &values, double sigma, int32_t seed=42u) |
Perturb all Point3 values using normally distributed noise. More... | |
void | gtsam::utilities::perturbPose2 (Values &values, double sigmaT, double sigmaR, int32_t seed=42u) |
Perturb all Pose2 values using normally distributed noise. More... | |
Matrix | gtsam::utilities::reprojectionErrors (const NonlinearFactorGraph &graph, const Values &values) |
Calculate the errors of all projection factors in a graph. More... | |
Contains generic global functions designed particularly for the matlab interface.
Definition in file nonlinear/utilities.h.