Fast creation of large key sets from within MATLAB
parent
8806c15b36
commit
87c386d77f
1
gtsam.h
1
gtsam.h
|
@ -2375,6 +2375,7 @@ namespace utilities {
|
|||
void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K);
|
||||
void insertProjectionFactors(gtsam::NonlinearFactorGraph& graph, size_t i, Vector J, Matrix Z, const gtsam::noiseModel::Base* model, const gtsam::Cal3_S2* K, const gtsam::Pose3& body_P_sensor);
|
||||
Matrix reprojectionErrors(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& values);
|
||||
gtsam::KeySet createKeySet(string s, Vector I);
|
||||
|
||||
} //\namespace utilities
|
||||
|
||||
|
|
8
matlab.h
8
matlab.h
|
@ -151,6 +151,14 @@ namespace gtsam {
|
|||
return errors;
|
||||
}
|
||||
|
||||
// Create a Keyset from indices
|
||||
FastSet<Key> createKeySet(string s, const Vector& I) {
|
||||
FastSet<Key> set;
|
||||
char c = s[0];
|
||||
for(int i=0;i<I.size();i++)
|
||||
set.insert(symbol(c,I[i]));
|
||||
return set;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -186,3 +186,4 @@
|
|||
% utilities.insertBackprojections - Insert a number of initial point values by backprojecting
|
||||
% utilities.insertProjectionFactors - Insert multiple projection factors for a single pose key
|
||||
% utilities.reprojectionErrors - Calculate the errors of all projection factors in a graph
|
||||
% utilities.createKeySet - Create keys from indices
|
||||
|
|
Loading…
Reference in New Issue