gtsam_unstable.i 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787
  1. /**
  2. * Matlab toolbox interface definition for gtsam_unstable
  3. */
  4. // specify the classes from gtsam we are using
  5. virtual class gtsam::Value;
  6. class gtsam::Vector6;
  7. class gtsam::Point2;
  8. class gtsam::Point2Vector;
  9. class gtsam::Rot2;
  10. class gtsam::Pose2;
  11. class gtsam::Point3;
  12. class gtsam::SO3;
  13. class gtsam::SO4;
  14. class gtsam::SOn;
  15. class gtsam::Rot3;
  16. class gtsam::Pose3;
  17. virtual class gtsam::noiseModel::Base;
  18. virtual class gtsam::noiseModel::Gaussian;
  19. virtual class gtsam::noiseModel::Isotropic;
  20. virtual class gtsam::imuBias::ConstantBias;
  21. virtual class gtsam::NonlinearFactor;
  22. virtual class gtsam::NoiseModelFactor;
  23. virtual class gtsam::NoiseModelFactor2;
  24. virtual class gtsam::NoiseModelFactor3;
  25. virtual class gtsam::NoiseModelFactor4;
  26. virtual class gtsam::GaussianFactor;
  27. virtual class gtsam::HessianFactor;
  28. virtual class gtsam::JacobianFactor;
  29. class gtsam::Cal3_S2;
  30. class gtsam::Cal3DS2;
  31. class gtsam::GaussianFactorGraph;
  32. class gtsam::NonlinearFactorGraph;
  33. class gtsam::Ordering;
  34. class gtsam::Values;
  35. class gtsam::Key;
  36. class gtsam::VectorValues;
  37. class gtsam::KeyList;
  38. class gtsam::KeySet;
  39. class gtsam::KeyVector;
  40. class gtsam::LevenbergMarquardtParams;
  41. class gtsam::ISAM2Params;
  42. class gtsam::GaussianDensity;
  43. class gtsam::LevenbergMarquardtOptimizer;
  44. namespace gtsam {
  45. #include <gtsam_unstable/base/Dummy.h>
  46. class Dummy {
  47. Dummy();
  48. void print(string s) const;
  49. unsigned char dummyTwoVar(unsigned char a) const;
  50. };
  51. #include <gtsam_unstable/dynamics/PoseRTV.h>
  52. class PoseRTV {
  53. PoseRTV();
  54. PoseRTV(Vector rtv);
  55. PoseRTV(const gtsam::Point3& pt, const gtsam::Rot3& rot, const Vector& vel);
  56. PoseRTV(const gtsam::Rot3& rot, const gtsam::Point3& pt, const Vector& vel);
  57. PoseRTV(const gtsam::Pose3& pose, const Vector& vel);
  58. PoseRTV(const gtsam::Pose3& pose);
  59. PoseRTV(double roll, double pitch, double yaw, double x, double y, double z, double vx, double vy, double vz);
  60. // testable
  61. bool equals(const gtsam::PoseRTV& other, double tol) const;
  62. void print(string s) const;
  63. // access
  64. gtsam::Point3 translation() const;
  65. gtsam::Rot3 rotation() const;
  66. Vector velocity() const;
  67. gtsam::Pose3 pose() const;
  68. // Vector interfaces
  69. Vector vector() const;
  70. Vector translationVec() const;
  71. Vector velocityVec() const;
  72. // manifold/Lie
  73. static size_t Dim();
  74. size_t dim() const;
  75. gtsam::PoseRTV retract(Vector v) const;
  76. Vector localCoordinates(const gtsam::PoseRTV& p) const;
  77. static gtsam::PoseRTV Expmap(Vector v);
  78. static Vector Logmap(const gtsam::PoseRTV& p);
  79. gtsam::PoseRTV inverse() const;
  80. gtsam::PoseRTV compose(const gtsam::PoseRTV& p) const;
  81. gtsam::PoseRTV between(const gtsam::PoseRTV& p) const;
  82. // measurement
  83. double range(const gtsam::PoseRTV& other) const;
  84. gtsam::PoseRTV transformed_from(const gtsam::Pose3& trans) const;
  85. // IMU/dynamics
  86. gtsam::PoseRTV planarDynamics(double vel_rate, double heading_rate, double max_accel, double dt) const;
  87. gtsam::PoseRTV flyingDynamics(double pitch_rate, double heading_rate, double lift_control, double dt) const;
  88. gtsam::PoseRTV generalDynamics(Vector accel, Vector gyro, double dt) const;
  89. Vector imuPrediction(const gtsam::PoseRTV& x2, double dt) const;
  90. gtsam::Point3 translationIntegration(const gtsam::PoseRTV& x2, double dt) const;
  91. Vector translationIntegrationVec(const gtsam::PoseRTV& x2, double dt) const;
  92. void serializable() const; // enabling serialization functionality
  93. };
  94. #include <gtsam_unstable/geometry/Pose3Upright.h>
  95. class Pose3Upright {
  96. Pose3Upright();
  97. Pose3Upright(const gtsam::Pose3Upright& other);
  98. Pose3Upright(const gtsam::Rot2& bearing, const gtsam::Point3& t);
  99. Pose3Upright(double x, double y, double z, double theta);
  100. Pose3Upright(const gtsam::Pose2& pose, double z);
  101. void print(string s) const;
  102. bool equals(const gtsam::Pose3Upright& pose, double tol) const;
  103. double x() const;
  104. double y() const;
  105. double z() const;
  106. double theta() const;
  107. gtsam::Point2 translation2() const;
  108. gtsam::Point3 translation() const;
  109. gtsam::Rot2 rotation2() const;
  110. gtsam::Rot3 rotation() const;
  111. gtsam::Pose2 pose2() const;
  112. gtsam::Pose3 pose() const;
  113. size_t dim() const;
  114. gtsam::Pose3Upright retract(Vector v) const;
  115. Vector localCoordinates(const gtsam::Pose3Upright& p2) const;
  116. static gtsam::Pose3Upright identity();
  117. gtsam::Pose3Upright inverse() const;
  118. gtsam::Pose3Upright compose(const gtsam::Pose3Upright& p2) const;
  119. gtsam::Pose3Upright between(const gtsam::Pose3Upright& p2) const;
  120. static gtsam::Pose3Upright Expmap(Vector xi);
  121. static Vector Logmap(const gtsam::Pose3Upright& p);
  122. void serializable() const; // enabling serialization functionality
  123. }; // \class Pose3Upright
  124. #include <gtsam_unstable/geometry/BearingS2.h>
  125. class BearingS2 {
  126. BearingS2();
  127. BearingS2(double azimuth_double, double elevation_double);
  128. BearingS2(const gtsam::Rot2& azimuth, const gtsam::Rot2& elevation);
  129. gtsam::Rot2 azimuth() const;
  130. gtsam::Rot2 elevation() const;
  131. static gtsam::BearingS2 fromDownwardsObservation(const gtsam::Pose3& A, const gtsam::Point3& B);
  132. static gtsam::BearingS2 fromForwardObservation(const gtsam::Pose3& A, const gtsam::Point3& B);
  133. void print(string s) const;
  134. bool equals(const gtsam::BearingS2& x, double tol) const;
  135. size_t dim() const;
  136. gtsam::BearingS2 retract(Vector v) const;
  137. Vector localCoordinates(const gtsam::BearingS2& p2) const;
  138. void serializable() const; // enabling serialization functionality
  139. };
  140. #include <gtsam_unstable/geometry/SimWall2D.h>
  141. class SimWall2D {
  142. SimWall2D();
  143. SimWall2D(const gtsam::Point2& a, const gtsam::Point2& b);
  144. SimWall2D(double ax, double ay, double bx, double by);
  145. void print(string s) const;
  146. bool equals(const gtsam::SimWall2D& other, double tol) const;
  147. gtsam::Point2 a() const;
  148. gtsam::Point2 b() const;
  149. gtsam::SimWall2D scale(double s) const;
  150. double length() const;
  151. gtsam::Point2 midpoint() const;
  152. bool intersects(const gtsam::SimWall2D& wall) const;
  153. // bool intersects(const gtsam::SimWall2D& wall, boost::optional<gtsam::Point2&> pt=boost::none) const;
  154. gtsam::Point2 norm() const;
  155. gtsam::Rot2 reflection(const gtsam::Point2& init, const gtsam::Point2& intersection) const;
  156. };
  157. #include <gtsam_unstable/geometry/SimPolygon2D.h>
  158. class SimPolygon2D {
  159. static void seedGenerator(size_t seed);
  160. static gtsam::SimPolygon2D createTriangle(const gtsam::Point2& pA, const gtsam::Point2& pB, const gtsam::Point2& pC);
  161. static gtsam::SimPolygon2D createRectangle(const gtsam::Point2& p, double height, double width);
  162. static gtsam::SimPolygon2D randomTriangle(double side_len, double mean_side_len, double sigma_side_len,
  163. double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys);
  164. static gtsam::SimPolygon2D randomRectangle(double side_len, double mean_side_len, double sigma_side_len,
  165. double min_vertex_dist, double min_side_len, const gtsam::SimPolygon2DVector& existing_polys);
  166. gtsam::Point2 landmark(size_t i) const;
  167. size_t size() const;
  168. gtsam::Point2Vector vertices() const;
  169. bool equals(const gtsam::SimPolygon2D& p, double tol) const;
  170. void print(string s) const;
  171. gtsam::SimWall2DVector walls() const;
  172. bool contains(const gtsam::Point2& p) const;
  173. bool overlaps(const gtsam::SimPolygon2D& p) const;
  174. static bool anyContains(const gtsam::Point2& p, const gtsam::SimPolygon2DVector& obstacles);
  175. static bool anyOverlaps(const gtsam::SimPolygon2D& p, const gtsam::SimPolygon2DVector& obstacles);
  176. static bool insideBox(double s, const gtsam::Point2& p);
  177. static bool nearExisting(const gtsam::Point2Vector& S,
  178. const gtsam::Point2& p, double threshold);
  179. static gtsam::Point2 randomPoint2(double s);
  180. static gtsam::Rot2 randomAngle();
  181. static double randomDistance(double mu, double sigma);
  182. static double randomDistance(double mu, double sigma, double min_dist);
  183. static gtsam::Point2 randomBoundedPoint2(double boundary_size,
  184. const gtsam::Point2Vector& landmarks, double min_landmark_dist);
  185. static gtsam::Point2 randomBoundedPoint2(double boundary_size,
  186. const gtsam::Point2Vector& landmarks,
  187. const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist);
  188. static gtsam::Point2 randomBoundedPoint2(double boundary_size,
  189. const gtsam::SimPolygon2DVector& obstacles);
  190. static gtsam::Point2 randomBoundedPoint2(
  191. const gtsam::Point2& LL_corner, const gtsam::Point2& UR_corner,
  192. const gtsam::Point2Vector& landmarks,
  193. const gtsam::SimPolygon2DVector& obstacles, double min_landmark_dist);
  194. static gtsam::Pose2 randomFreePose(double boundary_size, const gtsam::SimPolygon2DVector& obstacles);
  195. };
  196. // std::vector<gtsam::SimWall2D>
  197. class SimWall2DVector
  198. {
  199. //Capacity
  200. size_t size() const;
  201. size_t max_size() const;
  202. void resize(size_t sz);
  203. size_t capacity() const;
  204. bool empty() const;
  205. void reserve(size_t n);
  206. //Element access
  207. gtsam::SimWall2D at(size_t n) const;
  208. gtsam::SimWall2D front() const;
  209. gtsam::SimWall2D back() const;
  210. //Modifiers
  211. void assign(size_t n, const gtsam::SimWall2D& u);
  212. void push_back(const gtsam::SimWall2D& x);
  213. void pop_back();
  214. };
  215. // std::vector<gtsam::SimPolygon2D>
  216. class SimPolygon2DVector
  217. {
  218. //Capacity
  219. size_t size() const;
  220. size_t max_size() const;
  221. void resize(size_t sz);
  222. size_t capacity() const;
  223. bool empty() const;
  224. void reserve(size_t n);
  225. //Element access
  226. gtsam::SimPolygon2D at(size_t n) const;
  227. gtsam::SimPolygon2D front() const;
  228. gtsam::SimPolygon2D back() const;
  229. //Modifiers
  230. void assign(size_t n, const gtsam::SimPolygon2D& u);
  231. void push_back(const gtsam::SimPolygon2D& x);
  232. void pop_back();
  233. };
  234. // Nonlinear factors from gtsam, for our Value types
  235. #include <gtsam/nonlinear/PriorFactor.h>
  236. template<T = {gtsam::PoseRTV}>
  237. virtual class PriorFactor : gtsam::NoiseModelFactor {
  238. PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
  239. void serializable() const; // enabling serialization functionality
  240. };
  241. #include <gtsam/slam/BetweenFactor.h>
  242. template<T = {gtsam::PoseRTV}>
  243. virtual class BetweenFactor : gtsam::NoiseModelFactor {
  244. BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
  245. void serializable() const; // enabling serialization functionality
  246. };
  247. #include <gtsam_unstable/slam/BetweenFactorEM.h>
  248. template<T = {gtsam::Pose2}>
  249. virtual class BetweenFactorEM : gtsam::NonlinearFactor {
  250. BetweenFactorEM(size_t key1, size_t key2, const T& relativePose,
  251. const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
  252. double prior_inlier, double prior_outlier);
  253. BetweenFactorEM(size_t key1, size_t key2, const T& relativePose,
  254. const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
  255. double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs);
  256. Vector whitenedError(const gtsam::Values& x);
  257. Vector unwhitenedError(const gtsam::Values& x);
  258. Vector calcIndicatorProb(const gtsam::Values& x);
  259. gtsam::Pose2 measured(); // TODO: figure out how to output a template instead
  260. void set_flag_bump_up_near_zero_probs(bool flag);
  261. bool get_flag_bump_up_near_zero_probs() const;
  262. void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph);
  263. void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
  264. Matrix get_model_inlier_cov();
  265. Matrix get_model_outlier_cov();
  266. void serializable() const; // enabling serialization functionality
  267. };
  268. #include <gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h>
  269. template<T = {gtsam::Pose2}>
  270. virtual class TransformBtwRobotsUnaryFactorEM : gtsam::NonlinearFactor {
  271. TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB,
  272. const gtsam::Values& valA, const gtsam::Values& valB,
  273. const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
  274. double prior_inlier, double prior_outlier);
  275. TransformBtwRobotsUnaryFactorEM(size_t key, const T& relativePose, size_t keyA, size_t keyB,
  276. const gtsam::Values& valA, const gtsam::Values& valB,
  277. const gtsam::noiseModel::Gaussian* model_inlier, const gtsam::noiseModel::Gaussian* model_outlier,
  278. double prior_inlier, double prior_outlier, bool flag_bump_up_near_zero_probs, bool start_with_M_step);
  279. Vector whitenedError(const gtsam::Values& x);
  280. Vector unwhitenedError(const gtsam::Values& x);
  281. Vector calcIndicatorProb(const gtsam::Values& x);
  282. void setValAValB(const gtsam::Values valA, const gtsam::Values valB);
  283. void updateNoiseModels(const gtsam::Values& values, const gtsam::NonlinearFactorGraph& graph);
  284. void updateNoiseModels_givenCovs(const gtsam::Values& values, Matrix cov1, Matrix cov2, Matrix cov12);
  285. Matrix get_model_inlier_cov();
  286. Matrix get_model_outlier_cov();
  287. void serializable() const; // enabling serialization functionality
  288. };
  289. #include <gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h>
  290. template<T = {gtsam::Pose2}>
  291. virtual class TransformBtwRobotsUnaryFactor : gtsam::NonlinearFactor {
  292. TransformBtwRobotsUnaryFactor(size_t key, const T& relativePose, size_t keyA, size_t keyB,
  293. const gtsam::Values& valA, const gtsam::Values& valB,
  294. const gtsam::noiseModel::Gaussian* model);
  295. Vector whitenedError(const gtsam::Values& x);
  296. Vector unwhitenedError(const gtsam::Values& x);
  297. void setValAValB(const gtsam::Values valA, const gtsam::Values valB);
  298. void serializable() const; // enabling serialization functionality
  299. };
  300. #include <gtsam_unstable/slam/SmartRangeFactor.h>
  301. virtual class SmartRangeFactor : gtsam::NoiseModelFactor {
  302. SmartRangeFactor(double s);
  303. void addRange(size_t key, double measuredRange);
  304. gtsam::Point2 triangulate(const gtsam::Values& x) const;
  305. //void print(string s) const;
  306. };
  307. #include <gtsam/sam/RangeFactor.h>
  308. template<POSE, POINT>
  309. virtual class RangeFactor : gtsam::NoiseModelFactor {
  310. RangeFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel);
  311. void serializable() const; // enabling serialization functionality
  312. };
  313. typedef gtsam::RangeFactor<gtsam::PoseRTV, gtsam::PoseRTV> RangeFactorRTV;
  314. #include <gtsam_unstable/geometry/Event.h>
  315. class Event {
  316. Event();
  317. Event(double t, const gtsam::Point3& p);
  318. Event(double t, double x, double y, double z);
  319. double time() const;
  320. gtsam::Point3 location() const;
  321. double height() const;
  322. void print(string s) const;
  323. };
  324. class TimeOfArrival {
  325. TimeOfArrival();
  326. TimeOfArrival(double speed);
  327. double measure(const gtsam::Event& event, const gtsam::Point3& sensor) const;
  328. };
  329. #include <gtsam_unstable/slam/TOAFactor.h>
  330. virtual class TOAFactor : gtsam::NonlinearFactor {
  331. // For now, because of overload issues, we only expose constructor with known sensor coordinates:
  332. TOAFactor(size_t key1, gtsam::Point3 sensor, double measured,
  333. const gtsam::noiseModel::Base* noiseModel);
  334. static void InsertEvent(size_t key, const gtsam::Event& event, gtsam::Values* values);
  335. };
  336. #include <gtsam/nonlinear/NonlinearEquality.h>
  337. template<T = {gtsam::PoseRTV}>
  338. virtual class NonlinearEquality : gtsam::NoiseModelFactor {
  339. // Constructor - forces exact evaluation
  340. NonlinearEquality(size_t j, const T& feasible);
  341. // Constructor - allows inexact evaluation
  342. NonlinearEquality(size_t j, const T& feasible, double error_gain);
  343. void serializable() const; // enabling serialization functionality
  344. };
  345. #include <gtsam_unstable/dynamics/IMUFactor.h>
  346. template<POSE = {gtsam::PoseRTV}>
  347. virtual class IMUFactor : gtsam::NoiseModelFactor {
  348. /** Standard constructor */
  349. IMUFactor(Vector accel, Vector gyro,
  350. double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
  351. /** Full IMU vector specification */
  352. IMUFactor(Vector imu_vector,
  353. double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
  354. Vector gyro() const;
  355. Vector accel() const;
  356. Vector z() const;
  357. size_t key1() const;
  358. size_t key2() const;
  359. };
  360. #include <gtsam_unstable/dynamics/FullIMUFactor.h>
  361. template<POSE = {gtsam::PoseRTV}>
  362. virtual class FullIMUFactor : gtsam::NoiseModelFactor {
  363. /** Standard constructor */
  364. FullIMUFactor(Vector accel, Vector gyro,
  365. double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
  366. /** Single IMU vector - imu = [accel, gyro] */
  367. FullIMUFactor(Vector imu,
  368. double dt, size_t key1, size_t key2, const gtsam::noiseModel::Base* model);
  369. Vector gyro() const;
  370. Vector accel() const;
  371. Vector z() const;
  372. size_t key1() const;
  373. size_t key2() const;
  374. };
  375. #include <gtsam_unstable/dynamics/DynamicsPriors.h>
  376. virtual class DHeightPrior : gtsam::NonlinearFactor {
  377. DHeightPrior(size_t key, double height, const gtsam::noiseModel::Base* model);
  378. };
  379. virtual class DRollPrior : gtsam::NonlinearFactor {
  380. /** allows for explicit roll parameterization - uses canonical coordinate */
  381. DRollPrior(size_t key, double wx, const gtsam::noiseModel::Base* model);
  382. /** Forces roll to zero */
  383. DRollPrior(size_t key, const gtsam::noiseModel::Base* model);
  384. };
  385. virtual class VelocityPrior : gtsam::NonlinearFactor {
  386. VelocityPrior(size_t key, Vector vel, const gtsam::noiseModel::Base* model);
  387. };
  388. virtual class DGroundConstraint : gtsam::NonlinearFactor {
  389. // Primary constructor allows for variable height of the "floor"
  390. DGroundConstraint(size_t key, double height, const gtsam::noiseModel::Base* model);
  391. // Fully specify vector - use only for debugging
  392. DGroundConstraint(size_t key, Vector constraint, const gtsam::noiseModel::Base* model);
  393. };
  394. #include <gtsam_unstable/dynamics/VelocityConstraint3.h>
  395. virtual class VelocityConstraint3 : gtsam::NonlinearFactor {
  396. /** Standard constructor */
  397. VelocityConstraint3(size_t key1, size_t key2, size_t velKey, double dt);
  398. Vector evaluateError(const double& x1, const double& x2, const double& v) const;
  399. };
  400. #include <gtsam_unstable/dynamics/Pendulum.h>
  401. virtual class PendulumFactor1 : gtsam::NonlinearFactor {
  402. /** Standard constructor */
  403. PendulumFactor1(size_t k1, size_t k, size_t velKey, double dt);
  404. Vector evaluateError(const double& qk1, const double& qk, const double& v) const;
  405. };
  406. #include <gtsam_unstable/dynamics/Pendulum.h>
  407. virtual class PendulumFactor2 : gtsam::NonlinearFactor {
  408. /** Standard constructor */
  409. PendulumFactor2(size_t vk1, size_t vk, size_t qKey, double dt, double L, double g);
  410. Vector evaluateError(const double& vk1, const double& vk, const double& q) const;
  411. };
  412. virtual class PendulumFactorPk : gtsam::NonlinearFactor {
  413. /** Standard constructor */
  414. PendulumFactorPk(size_t pk, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);
  415. Vector evaluateError(const double& pk, const double& qk, const double& qk1) const;
  416. };
  417. virtual class PendulumFactorPk1 : gtsam::NonlinearFactor {
  418. /** Standard constructor */
  419. PendulumFactorPk1(size_t pk1, size_t qk, size_t qk1, double h, double m, double r, double g, double alpha);
  420. Vector evaluateError(const double& pk1, const double& qk, const double& qk1) const;
  421. };
  422. #include <gtsam_unstable/dynamics/SimpleHelicopter.h>
  423. virtual class Reconstruction : gtsam::NoiseModelFactor {
  424. Reconstruction(size_t gKey1, size_t gKey, size_t xiKey, double h);
  425. Vector evaluateError(const gtsam::Pose3& gK1, const gtsam::Pose3& gK, Vector xiK) const;
  426. };
  427. virtual class DiscreteEulerPoincareHelicopter : gtsam::NoiseModelFactor {
  428. DiscreteEulerPoincareHelicopter(size_t xiKey, size_t xiKey_1, size_t gKey,
  429. double h, Matrix Inertia, Vector Fu, double m);
  430. Vector evaluateError(Vector xiK, Vector xiK_1, const gtsam::Pose3& gK) const;
  431. };
  432. //*************************************************************************
  433. // nonlinear
  434. //*************************************************************************
  435. #include <gtsam_unstable/nonlinear/FixedLagSmoother.h>
  436. class FixedLagSmootherKeyTimestampMapValue {
  437. FixedLagSmootherKeyTimestampMapValue(size_t key, double timestamp);
  438. FixedLagSmootherKeyTimestampMapValue(const gtsam::FixedLagSmootherKeyTimestampMapValue& other);
  439. };
  440. class FixedLagSmootherKeyTimestampMap {
  441. FixedLagSmootherKeyTimestampMap();
  442. FixedLagSmootherKeyTimestampMap(const gtsam::FixedLagSmootherKeyTimestampMap& other);
  443. // Note: no print function
  444. // common STL methods
  445. size_t size() const;
  446. bool empty() const;
  447. void clear();
  448. double at(const size_t key) const;
  449. void insert(const gtsam::FixedLagSmootherKeyTimestampMapValue& value);
  450. };
  451. class FixedLagSmootherResult {
  452. size_t getIterations() const;
  453. size_t getNonlinearVariables() const;
  454. size_t getLinearVariables() const;
  455. double getError() const;
  456. };
  457. #include <gtsam_unstable/nonlinear/FixedLagSmoother.h>
  458. virtual class FixedLagSmoother {
  459. void print(string s) const;
  460. bool equals(const gtsam::FixedLagSmoother& rhs, double tol) const;
  461. gtsam::FixedLagSmootherKeyTimestampMap timestamps() const;
  462. double smootherLag() const;
  463. gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps);
  464. gtsam::Values calculateEstimate() const;
  465. };
  466. #include <gtsam_unstable/nonlinear/BatchFixedLagSmoother.h>
  467. virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
  468. BatchFixedLagSmoother();
  469. BatchFixedLagSmoother(double smootherLag);
  470. BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
  471. gtsam::LevenbergMarquardtParams params() const;
  472. template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
  473. gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
  474. Vector, Matrix}>
  475. VALUE calculateEstimate(size_t key) const;
  476. };
  477. #include <gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h>
  478. virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
  479. IncrementalFixedLagSmoother();
  480. IncrementalFixedLagSmoother(double smootherLag);
  481. IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
  482. gtsam::ISAM2Params params() const;
  483. };
  484. #include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
  485. virtual class ConcurrentFilter {
  486. void print(string s) const;
  487. bool equals(const gtsam::ConcurrentFilter& rhs, double tol) const;
  488. };
  489. virtual class ConcurrentSmoother {
  490. void print(string s) const;
  491. bool equals(const gtsam::ConcurrentSmoother& rhs, double tol) const;
  492. };
  493. // Synchronize function
  494. void synchronize(gtsam::ConcurrentFilter& filter, gtsam::ConcurrentSmoother& smoother);
  495. #include <gtsam_unstable/nonlinear/ConcurrentBatchFilter.h>
  496. class ConcurrentBatchFilterResult {
  497. size_t getIterations() const;
  498. size_t getLambdas() const;
  499. size_t getNonlinearVariables() const;
  500. size_t getLinearVariables() const;
  501. double getError() const;
  502. };
  503. virtual class ConcurrentBatchFilter : gtsam::ConcurrentFilter {
  504. ConcurrentBatchFilter();
  505. ConcurrentBatchFilter(const gtsam::LevenbergMarquardtParams& parameters);
  506. gtsam::NonlinearFactorGraph getFactors() const;
  507. gtsam::Values getLinearizationPoint() const;
  508. gtsam::Ordering getOrdering() const;
  509. gtsam::VectorValues getDelta() const;
  510. gtsam::ConcurrentBatchFilterResult update();
  511. gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors);
  512. gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
  513. gtsam::ConcurrentBatchFilterResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyList& keysToMove);
  514. gtsam::Values calculateEstimate() const;
  515. };
  516. #include <gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h>
  517. class ConcurrentBatchSmootherResult {
  518. size_t getIterations() const;
  519. size_t getLambdas() const;
  520. size_t getNonlinearVariables() const;
  521. size_t getLinearVariables() const;
  522. double getError() const;
  523. };
  524. virtual class ConcurrentBatchSmoother : gtsam::ConcurrentSmoother {
  525. ConcurrentBatchSmoother();
  526. ConcurrentBatchSmoother(const gtsam::LevenbergMarquardtParams& parameters);
  527. gtsam::NonlinearFactorGraph getFactors() const;
  528. gtsam::Values getLinearizationPoint() const;
  529. gtsam::Ordering getOrdering() const;
  530. gtsam::VectorValues getDelta() const;
  531. gtsam::ConcurrentBatchSmootherResult update();
  532. gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors);
  533. gtsam::ConcurrentBatchSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta);
  534. gtsam::Values calculateEstimate() const;
  535. };
  536. //*************************************************************************
  537. // slam
  538. //*************************************************************************
  539. #include <gtsam_unstable/slam/RelativeElevationFactor.h>
  540. virtual class RelativeElevationFactor: gtsam::NoiseModelFactor {
  541. RelativeElevationFactor();
  542. RelativeElevationFactor(size_t poseKey, size_t pointKey, double measured,
  543. const gtsam::noiseModel::Base* model);
  544. double measured() const;
  545. //void print(string s) const;
  546. };
  547. #include <gtsam_unstable/slam/DummyFactor.h>
  548. virtual class DummyFactor : gtsam::NonlinearFactor {
  549. DummyFactor(size_t key1, size_t dim1, size_t key2, size_t dim2);
  550. };
  551. #include <gtsam_unstable/slam/InvDepthFactorVariant1.h>
  552. virtual class InvDepthFactorVariant1 : gtsam::NoiseModelFactor {
  553. InvDepthFactorVariant1(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
  554. };
  555. #include <gtsam_unstable/slam/InvDepthFactorVariant2.h>
  556. virtual class InvDepthFactorVariant2 : gtsam::NoiseModelFactor {
  557. InvDepthFactorVariant2(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::Point3& referencePoint, const gtsam::noiseModel::Base* model);
  558. };
  559. #include <gtsam_unstable/slam/InvDepthFactorVariant3.h>
  560. virtual class InvDepthFactorVariant3a : gtsam::NoiseModelFactor {
  561. InvDepthFactorVariant3a(size_t poseKey, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
  562. };
  563. virtual class InvDepthFactorVariant3b : gtsam::NoiseModelFactor {
  564. InvDepthFactorVariant3b(size_t poseKey1, size_t poseKey2, size_t landmarkKey, const gtsam::Point2& measured, const gtsam::Cal3_S2* K, const gtsam::noiseModel::Base* model);
  565. };
  566. #include <gtsam_unstable/slam/Mechanization_bRn2.h>
  567. class Mechanization_bRn2 {
  568. Mechanization_bRn2();
  569. Mechanization_bRn2(gtsam::Rot3& initial_bRn, Vector initial_x_g,
  570. Vector initial_x_a);
  571. Vector b_g(double g_e);
  572. gtsam::Rot3 bRn();
  573. Vector x_g();
  574. Vector x_a();
  575. static gtsam::Mechanization_bRn2 initialize(Matrix U, Matrix F, double g_e);
  576. gtsam::Mechanization_bRn2 correct(Vector dx) const;
  577. gtsam::Mechanization_bRn2 integrate(Vector u, double dt) const;
  578. //void print(string s) const;
  579. };
  580. #include <gtsam_unstable/slam/AHRS.h>
  581. class AHRS {
  582. AHRS(Matrix U, Matrix F, double g_e);
  583. pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> initialize(double g_e);
  584. pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> integrate(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector u, double dt);
  585. pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aid(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, bool Farrel);
  586. pair<gtsam::Mechanization_bRn2, gtsam::GaussianDensity*> aidGeneral(const gtsam::Mechanization_bRn2& mech, gtsam::GaussianDensity* state, Vector f, Vector f_expected, const gtsam::Rot3& increment);
  587. //void print(string s) const;
  588. };
  589. // Tectonic SAM Factors
  590. #include <gtsam_unstable/slam/TSAMFactors.h>
  591. //typedef gtsam::NoiseModelFactor2<gtsam::Pose2, gtsam::Point2> NLPosePose;
  592. virtual class DeltaFactor : gtsam::NoiseModelFactor {
  593. DeltaFactor(size_t i, size_t j, const gtsam::Point2& measured,
  594. const gtsam::noiseModel::Base* noiseModel);
  595. //void print(string s) const;
  596. };
  597. //typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
  598. // gtsam::Point2> NLPosePosePosePoint;
  599. virtual class DeltaFactorBase : gtsam::NoiseModelFactor {
  600. DeltaFactorBase(size_t b1, size_t i, size_t b2, size_t j,
  601. const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel);
  602. //void print(string s) const;
  603. };
  604. //typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Pose2, gtsam::Pose2,
  605. // gtsam::Pose2> NLPosePosePosePose;
  606. virtual class OdometryFactorBase : gtsam::NoiseModelFactor {
  607. OdometryFactorBase(size_t b1, size_t i, size_t b2, size_t j,
  608. const gtsam::Pose2& measured, const gtsam::noiseModel::Base* noiseModel);
  609. //void print(string s) const;
  610. };
  611. #include <gtsam/geometry/Cal3DS2.h>
  612. #include <gtsam_unstable/slam/ProjectionFactorPPP.h>
  613. template<POSE, LANDMARK, CALIBRATION>
  614. virtual class ProjectionFactorPPP : gtsam::NoiseModelFactor {
  615. ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
  616. size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k);
  617. ProjectionFactorPPP(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
  618. size_t poseKey, size_t transformKey, size_t pointKey, const CALIBRATION* k, bool throwCheirality, bool verboseCheirality);
  619. gtsam::Point2 measured() const;
  620. CALIBRATION* calibration() const;
  621. bool verboseCheirality() const;
  622. bool throwCheirality() const;
  623. // enabling serialization functionality
  624. void serialize() const;
  625. };
  626. typedef gtsam::ProjectionFactorPPP<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCal3_S2;
  627. typedef gtsam::ProjectionFactorPPP<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCal3DS2;
  628. #include <gtsam_unstable/slam/ProjectionFactorPPPC.h>
  629. template<POSE, LANDMARK, CALIBRATION>
  630. virtual class ProjectionFactorPPPC : gtsam::NoiseModelFactor {
  631. ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
  632. size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey);
  633. ProjectionFactorPPPC(const gtsam::Point2& measured, const gtsam::noiseModel::Base* noiseModel,
  634. size_t poseKey, size_t transformKey, size_t pointKey, size_t calibKey, bool throwCheirality, bool verboseCheirality);
  635. gtsam::Point2 measured() const;
  636. bool verboseCheirality() const;
  637. bool throwCheirality() const;
  638. // enabling serialization functionality
  639. void serialize() const;
  640. };
  641. typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3_S2> ProjectionFactorPPPCCal3_S2;
  642. typedef gtsam::ProjectionFactorPPPC<gtsam::Pose3, gtsam::Point3, gtsam::Cal3DS2> ProjectionFactorPPPCCal3DS2;
  643. } //\namespace gtsam