update gtsam:: namespace in gtsam.i

release/4.3a0
Varun Agrawal 2024-06-28 16:17:47 -04:00
parent 2ea9d1bcf3
commit 0b31728cb7
1 changed files with 14 additions and 14 deletions

View File

@ -161,31 +161,31 @@ class FactorIndices {
namespace utilities { namespace utilities {
#include <gtsam/nonlinear/utilities.h> #include <gtsam/nonlinear/utilities.h>
gtsam::KeyList createKeyList(Vector I); gtsam::KeyList createKeyList(gtsam::Vector I);
gtsam::KeyList createKeyList(string s, Vector I); gtsam::KeyList createKeyList(string s, gtsam::Vector I);
gtsam::KeyVector createKeyVector(Vector I); gtsam::KeyVector createKeyVector(gtsam::Vector I);
gtsam::KeyVector createKeyVector(string s, Vector I); gtsam::KeyVector createKeyVector(string s, gtsam::Vector I);
gtsam::KeySet createKeySet(Vector I); gtsam::KeySet createKeySet(gtsam::Vector I);
gtsam::KeySet createKeySet(string s, Vector I); gtsam::KeySet createKeySet(string s, gtsam::Vector I);
Matrix extractPoint2(const gtsam::Values& values); gtsam::Matrix extractPoint2(const gtsam::Values& values);
Matrix extractPoint3(const gtsam::Values& values); gtsam::Matrix extractPoint3(const gtsam::Values& values);
gtsam::Values allPose2s(gtsam::Values& values); gtsam::Values allPose2s(gtsam::Values& values);
Matrix extractPose2(const gtsam::Values& values); gtsam::Matrix extractPose2(const gtsam::Values& values);
gtsam::Values allPose3s(gtsam::Values& values); gtsam::Values allPose3s(gtsam::Values& values);
Matrix extractPose3(const gtsam::Values& values); gtsam::Matrix extractPose3(const gtsam::Values& values);
Matrix extractVectors(const gtsam::Values& values, char c); gtsam::Matrix extractVectors(const gtsam::Values& values, char c);
void perturbPoint2(gtsam::Values& values, double sigma, int seed = 42u); void perturbPoint2(gtsam::Values& values, double sigma, int seed = 42u);
void perturbPose2(gtsam::Values& values, double sigmaT, double sigmaR, void perturbPose2(gtsam::Values& values, double sigmaT, double sigmaR,
int seed = 42u); int seed = 42u);
void perturbPoint3(gtsam::Values& values, double sigma, int seed = 42u); void perturbPoint3(gtsam::Values& values, double sigma, int seed = 42u);
void insertBackprojections(gtsam::Values& values, void insertBackprojections(gtsam::Values& values,
const gtsam::PinholeCamera<gtsam::Cal3_S2>& c, const gtsam::PinholeCamera<gtsam::Cal3_S2>& c,
Vector J, Matrix Z, double depth); gtsam::Vector J, gtsam::Matrix Z, double depth);
void insertProjectionFactors( void insertProjectionFactors(
gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, gtsam::NonlinearFactorGraph& graph, size_t i, gtsam::Vector J, gtsam::Matrix Z,
const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K,
const gtsam::Pose3& body_P_sensor = gtsam::Pose3()); const gtsam::Pose3& body_P_sensor = gtsam::Pose3());
Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, gtsam::Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& values); const gtsam::Values& values);
gtsam::Values localToWorld(const gtsam::Values& local, gtsam::Values localToWorld(const gtsam::Values& local,
const gtsam::Pose2& base); const gtsam::Pose2& base);