Param name mismatches
							parent
							
								
									a61ce2afd9
								
							
						
					
					
						commit
						66f5ba0f49
					
				|  | @ -93,7 +93,7 @@ virtual class Value { | |||
|   // No constructors because this is an abstract class | ||||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   size_t dim() const; | ||||
|  |  | |||
|  | @ -45,7 +45,7 @@ virtual class DiscreteFactor : gtsam::Factor { | |||
|   void print(string s = "DiscreteFactor\n", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::DiscreteFactor& other, double tol = 1e-9) const; | ||||
|   bool equals(const gtsam::DiscreteFactor& lf, double tol = 1e-9) const; | ||||
|   double operator()(const gtsam::DiscreteValues& values) const; | ||||
| }; | ||||
| 
 | ||||
|  | @ -142,7 +142,7 @@ virtual class DiscreteConditional : gtsam::DecisionTreeFactor { | |||
|   size_t sample(size_t value) const; | ||||
|   size_t sample() const; | ||||
|   void sampleInPlace(gtsam::DiscreteValues @parentsValues) const; | ||||
|   size_t argmax(const gtsam::DiscreteValues& parents) const; | ||||
|   size_t argmax(const gtsam::DiscreteValues& parentsValues) const; | ||||
| 
 | ||||
|   // Markdown and HTML | ||||
|   string markdown(const gtsam::KeyFormatter& keyFormatter = | ||||
|  | @ -226,7 +226,7 @@ class DiscreteBayesNet { | |||
|   void print(string s = "DiscreteBayesNet\n", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::DiscreteBayesNet& other, double tol = 1e-9) const; | ||||
|   bool equals(const gtsam::DiscreteBayesNet& bn, double tol = 1e-9) const; | ||||
| 
 | ||||
|   // Standard interface. | ||||
|   double logProbability(const gtsam::DiscreteValues& values) const; | ||||
|  |  | |||
|  | @ -73,12 +73,12 @@ class StereoPoint2 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::StereoPoint2& point, double tol) const; | ||||
|   bool equals(const gtsam::StereoPoint2& q, double tol) const; | ||||
| 
 | ||||
|   // Group | ||||
|   static gtsam::StereoPoint2 Identity(); | ||||
|   gtsam::StereoPoint2 inverse() const; | ||||
|   gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p2) const; | ||||
|   gtsam::StereoPoint2 compose(const gtsam::StereoPoint2& p1) const; | ||||
|   gtsam::StereoPoint2 between(const gtsam::StereoPoint2& p2) const; | ||||
| 
 | ||||
|   // Operator Overloads | ||||
|  | @ -90,10 +90,10 @@ class StereoPoint2 { | |||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::StereoPoint2 retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::StereoPoint2& p) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::StereoPoint2& t2) const; | ||||
| 
 | ||||
|   // Lie Group | ||||
|   static gtsam::StereoPoint2 Expmap(gtsam::Vector v); | ||||
|   static gtsam::StereoPoint2 Expmap(gtsam::Vector d); | ||||
|   static gtsam::Vector Logmap(const gtsam::StereoPoint2& p); | ||||
| 
 | ||||
|   // Standard Interface | ||||
|  | @ -154,7 +154,7 @@ class Rot2 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "theta") const; | ||||
|   bool equals(const gtsam::Rot2& rot, double tol) const; | ||||
|   bool equals(const gtsam::Rot2& R, double tol) const; | ||||
| 
 | ||||
|   // Group | ||||
|   static gtsam::Rot2 Identity(); | ||||
|  | @ -173,15 +173,15 @@ class Rot2 { | |||
| 
 | ||||
|   // Lie Group | ||||
|   static gtsam::Rot2 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Vector Logmap(const gtsam::Rot2& p); | ||||
|   static gtsam::Vector Logmap(const gtsam::Rot2& r); | ||||
|   gtsam::Rot2 expmap(gtsam::Vector v); | ||||
|   gtsam::Vector logmap(const gtsam::Rot2& p); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Group Action on Point2 | ||||
|   gtsam::Point2 rotate(const gtsam::Point2& point) const; | ||||
|   gtsam::Point2 unrotate(const gtsam::Point2& point) const; | ||||
|   gtsam::Point2 rotate(const gtsam::Point2& p) const; | ||||
|   gtsam::Point2 unrotate(const gtsam::Point2& p) const; | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   static gtsam::Rot2 relativeBearing( | ||||
|  | @ -356,7 +356,7 @@ class Rot3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::Rot3& rot, double tol) const; | ||||
|   bool equals(const gtsam::Rot3& p, double tol) const; | ||||
| 
 | ||||
|   // Group | ||||
|   static gtsam::Rot3 Identity(); | ||||
|  | @ -375,11 +375,11 @@ class Rot3 { | |||
| 
 | ||||
|   // Lie group | ||||
|   static gtsam::Rot3 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Vector Logmap(const gtsam::Rot3& p); | ||||
|   static gtsam::Vector Logmap(const gtsam::Rot3& R); | ||||
|   gtsam::Rot3 expmap(const gtsam::Vector& v); | ||||
|   gtsam::Vector logmap(const gtsam::Rot3& p); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Group Action on Point3 | ||||
|   gtsam::Point3 rotate(const gtsam::Point3& p) const; | ||||
|  | @ -445,9 +445,9 @@ class Pose2 { | |||
|   gtsam::Vector localCoordinates(const gtsam::Pose2& p, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2) const; | ||||
| 
 | ||||
|   // Lie Group | ||||
|   static gtsam::Pose2 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Pose2 Expmap(gtsam::Vector xi); | ||||
|   static gtsam::Vector Logmap(const gtsam::Pose2& p); | ||||
|   static gtsam::Pose2 Expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::Pose2 Expmap(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::Vector Logmap(const gtsam::Pose2& p, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   gtsam::Pose2 expmap(gtsam::Vector v); | ||||
|   gtsam::Pose2 expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2); | ||||
|  | @ -457,11 +457,11 @@ class Pose2 { | |||
|   static gtsam::Matrix LogmapDerivative(const gtsam::Pose2& v); | ||||
|   gtsam::Matrix AdjointMap() const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi) const; | ||||
|   static gtsam::Matrix adjointMap_(gtsam::Vector v); | ||||
|   static gtsam::Matrix adjointMap_(gtsam::Vector xi); | ||||
|   static gtsam::Vector adjoint_(gtsam::Vector xi, gtsam::Vector y); | ||||
|   static gtsam::Vector adjointTranspose(gtsam::Vector xi, gtsam::Vector y); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Group Actions on Point2 | ||||
|   gtsam::Point2 transformFrom(const gtsam::Point2& p) const; | ||||
|  | @ -515,8 +515,8 @@ class Pose3 { | |||
|   gtsam::Pose3 between(const gtsam::Pose3& pose, | ||||
|                        Eigen::Ref<Eigen::MatrixXd> H1, | ||||
|                        Eigen::Ref<Eigen::MatrixXd> H2) const; | ||||
|   gtsam::Pose3 slerp(double t, const gtsam::Pose3& pose) const; | ||||
|   gtsam::Pose3 slerp(double t, const gtsam::Pose3& pose, | ||||
|   gtsam::Pose3 slerp(double t, const gtsam::Pose3& other) const; | ||||
|   gtsam::Pose3 slerp(double t, const gtsam::Pose3& other, | ||||
|                            Eigen::Ref<Eigen::MatrixXd> Hx, | ||||
|                            Eigen::Ref<Eigen::MatrixXd> Hy) const; | ||||
| 
 | ||||
|  | @ -530,20 +530,20 @@ class Pose3 { | |||
|   gtsam::Vector localCoordinates(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hxi) const; | ||||
| 
 | ||||
|   // Lie Group | ||||
|   static gtsam::Pose3 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Pose3 Expmap(gtsam::Vector xi); | ||||
|   static gtsam::Vector Logmap(const gtsam::Pose3& p); | ||||
|   static gtsam::Pose3 Expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::Vector Logmap(const gtsam::Pose3& p, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::Pose3 Expmap(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> Hxi); | ||||
|   static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hpose); | ||||
|   gtsam::Pose3 expmap(gtsam::Vector v); | ||||
|   gtsam::Pose3 expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2); | ||||
|   gtsam::Vector logmap(const gtsam::Pose3& p); | ||||
|   gtsam::Vector logmap(const gtsam::Pose3& p, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2); | ||||
|   gtsam::Matrix AdjointMap() const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi) const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> H_this, | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi_b) const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi_b, Eigen::Ref<Eigen::MatrixXd> H_this, | ||||
|                  Eigen::Ref<Eigen::MatrixXd> H_xib) const; | ||||
|   gtsam::Vector AdjointTranspose(gtsam::Vector xi) const; | ||||
|   gtsam::Vector AdjointTranspose(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> H_this, | ||||
|   gtsam::Vector AdjointTranspose(gtsam::Vector x) const; | ||||
|   gtsam::Vector AdjointTranspose(gtsam::Vector x, Eigen::Ref<Eigen::MatrixXd> H_this, | ||||
|                           Eigen::Ref<Eigen::MatrixXd> H_x) const; | ||||
|   static gtsam::Matrix adjointMap(gtsam::Vector xi); | ||||
|   static gtsam::Vector adjoint(gtsam::Vector xi, gtsam::Vector y); | ||||
|  | @ -553,7 +553,7 @@ class Pose3 { | |||
|   static gtsam::Matrix ExpmapDerivative(gtsam::Vector xi); | ||||
|   static gtsam::Matrix LogmapDerivative(const gtsam::Pose3& xi); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Group Action on Point3 | ||||
|   gtsam::Point3 transformFrom(const gtsam::Point3& point) const; | ||||
|  | @ -576,10 +576,10 @@ class Pose3 { | |||
|   double y() const; | ||||
|   double z() const; | ||||
|   gtsam::Matrix matrix() const; | ||||
|   gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose) const; | ||||
|   gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& aTb) const; | ||||
|   gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hself, | ||||
|                                  Eigen::Ref<Eigen::MatrixXd> HaTb) const; | ||||
|   gtsam::Pose3 transformPoseTo(const gtsam::Pose3& pose) const; | ||||
|   gtsam::Pose3 transformPoseTo(const gtsam::Pose3& wTb) const; | ||||
|   gtsam::Pose3 transformPoseTo(const gtsam::Pose3& pose, Eigen::Ref<Eigen::MatrixXd> Hself, | ||||
|                                Eigen::Ref<Eigen::MatrixXd> HwTb) const; | ||||
|   double range(const gtsam::Point3& point); | ||||
|  | @ -621,7 +621,7 @@ class Unit3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::Unit3& pose, double tol) const; | ||||
|   bool equals(const gtsam::Unit3& s, double tol) const; | ||||
| 
 | ||||
|   // Other functionality | ||||
|   gtsam::Matrix basis() const; | ||||
|  | @ -667,13 +667,13 @@ class EssentialMatrix { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::EssentialMatrix& pose, double tol) const; | ||||
|   bool equals(const gtsam::EssentialMatrix& other, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   static size_t Dim(); | ||||
|   size_t dim() const; | ||||
|   gtsam::EssentialMatrix retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::EssentialMatrix& s) const; | ||||
|   gtsam::EssentialMatrix retract(gtsam::Vector xi) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::EssentialMatrix& other) const; | ||||
| 
 | ||||
|   // Other methods: | ||||
|   gtsam::Rot3 rotation() const; | ||||
|  | @ -691,7 +691,7 @@ virtual class Cal3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "Cal3") const; | ||||
|   bool equals(const gtsam::Cal3& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3& K, double tol) const; | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   double fx() const; | ||||
|  | @ -720,13 +720,13 @@ virtual class Cal3_S2 : gtsam::Cal3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "Cal3_S2") const; | ||||
|   bool equals(const gtsam::Cal3_S2& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3_S2& K, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   static size_t Dim(); | ||||
|   size_t dim() const; | ||||
|   gtsam::Cal3_S2 retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3_S2& c) const; | ||||
|   gtsam::Cal3_S2 retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3_S2& T2) const; | ||||
| 
 | ||||
|   // Action on Point2 | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p) const; | ||||
|  | @ -779,13 +779,13 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { | |||
|   Cal3DS2(gtsam::Vector v); | ||||
| 
 | ||||
|   // Testable | ||||
|   bool equals(const gtsam::Cal3DS2& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3DS2& K, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   size_t dim() const; | ||||
|   static size_t Dim(); | ||||
|   gtsam::Cal3DS2 retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3DS2& c) const; | ||||
|   gtsam::Cal3DS2 retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3DS2& T2) const; | ||||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
|  | @ -802,7 +802,7 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { | |||
|   Cal3Unified(gtsam::Vector v); | ||||
| 
 | ||||
|   // Testable | ||||
|   bool equals(const gtsam::Cal3Unified& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3Unified& K, double tol) const; | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   double xi() const; | ||||
|  | @ -812,8 +812,8 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { | |||
|   // Manifold | ||||
|   size_t dim() const; | ||||
|   static size_t Dim(); | ||||
|   gtsam::Cal3Unified retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Unified& c) const; | ||||
|   gtsam::Cal3Unified retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Unified& T2) const; | ||||
| 
 | ||||
|   // Action on Point2 | ||||
|   // Note: the signature of this functions differ from the functions | ||||
|  | @ -841,11 +841,11 @@ virtual class Cal3Fisheye : gtsam::Cal3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "Cal3Fisheye") const; | ||||
|   bool equals(const gtsam::Cal3Fisheye& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3Fisheye& K, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::Cal3Fisheye retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; | ||||
|   gtsam::Cal3Fisheye retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Fisheye& T2) const; | ||||
| 
 | ||||
|   // Action on Point2 | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p) const; | ||||
|  | @ -875,12 +875,12 @@ virtual class Cal3_S2Stereo   : gtsam::Cal3{ | |||
|   Cal3_S2Stereo(gtsam::Vector v); | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::Cal3_S2Stereo retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const; | ||||
|   gtsam::Cal3_S2Stereo retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3_S2Stereo& T2) const; | ||||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::Cal3_S2Stereo& K, double tol) const; | ||||
|   bool equals(const gtsam::Cal3_S2Stereo& other, double tol) const; | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   double baseline() const; | ||||
|  | @ -895,15 +895,15 @@ virtual class Cal3f : gtsam::Cal3 { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::Cal3f& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3f& K, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::Cal3f retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3f& c) const; | ||||
|   gtsam::Cal3f retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3f& T2) const; | ||||
| 
 | ||||
|   // Action on Point2 | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p) const; | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& p, | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& pi) const; | ||||
|   gtsam::Point2 calibrate(const gtsam::Point2& pi, | ||||
|                           Eigen::Ref<Eigen::MatrixXd> Dcal, | ||||
|                           Eigen::Ref<Eigen::MatrixXd> Dp) const; | ||||
|   gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; | ||||
|  | @ -929,11 +929,11 @@ virtual class Cal3Bundler : gtsam::Cal3f { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::Cal3Bundler& rhs, double tol) const; | ||||
|   bool equals(const gtsam::Cal3Bundler& K, double tol) const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::Cal3Bundler retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Bundler& c) const; | ||||
|   gtsam::Cal3Bundler retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::Cal3Bundler& T2) const; | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   double k1() const; | ||||
|  | @ -1020,7 +1020,7 @@ class CalibratedCamera { | |||
|   gtsam::Point2 project(const gtsam::Point3& point, | ||||
|                         Eigen::Ref<Eigen::MatrixXd> Dcamera, | ||||
|                         Eigen::Ref<Eigen::MatrixXd> Dpoint); | ||||
|   gtsam::Point3 backproject(const gtsam::Point2& p, double depth) const; | ||||
|   gtsam::Point3 backproject(const gtsam::Point2& pn, double depth) const; | ||||
|   gtsam::Point3 backproject(const gtsam::Point2& p, double depth, | ||||
|                             Eigen::Ref<Eigen::MatrixXd> Dresult_dpose, | ||||
|                             Eigen::Ref<Eigen::MatrixXd> Dresult_dp, | ||||
|  | @ -1139,7 +1139,7 @@ class PinholePose { | |||
| 
 | ||||
|   // Manifold | ||||
|   This retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const This& T2) const; | ||||
|   gtsam::Vector localCoordinates(const This& p) const; | ||||
|   size_t dim() const; | ||||
|   static size_t Dim(); | ||||
| 
 | ||||
|  | @ -1191,11 +1191,11 @@ class Similarity2 { | |||
| 
 | ||||
|   // Lie group | ||||
|   static gtsam::Similarity2 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Vector Logmap(const gtsam::Similarity2& p); | ||||
|   static gtsam::Vector Logmap(const gtsam::Similarity2& S); | ||||
|   gtsam::Similarity2 expmap(const gtsam::Vector& v); | ||||
|   gtsam::Vector logmap(const gtsam::Similarity2& p); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   bool equals(const gtsam::Similarity2& sim, double tol) const; | ||||
|  | @ -1223,11 +1223,11 @@ class Similarity3 { | |||
| 
 | ||||
|   // Lie group | ||||
|   static gtsam::Similarity3 Expmap(gtsam::Vector v); | ||||
|   static gtsam::Vector Logmap(const gtsam::Similarity3& p); | ||||
|   static gtsam::Vector Logmap(const gtsam::Similarity3& s); | ||||
|   gtsam::Similarity3 expmap(const gtsam::Vector& v); | ||||
|   gtsam::Vector logmap(const gtsam::Similarity3& p); | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // Standard Interface | ||||
|   bool equals(const gtsam::Similarity3& sim, double tol) const; | ||||
|  | @ -1263,14 +1263,14 @@ class StereoCamera { | |||
|   gtsam::Cal3_S2Stereo calibration() const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::StereoCamera retract(gtsam::Vector d) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::StereoCamera& T2) const; | ||||
|   gtsam::StereoCamera retract(gtsam::Vector v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::StereoCamera& t2) const; | ||||
|   size_t dim() const; | ||||
|   static size_t Dim(); | ||||
| 
 | ||||
|   // Transformations and measurement functions | ||||
|   gtsam::StereoPoint2 project(const gtsam::Point3& point) const; | ||||
|   gtsam::Point3 backproject(const gtsam::StereoPoint2& p) const; | ||||
|   gtsam::Point3 backproject(const gtsam::StereoPoint2& z) const; | ||||
| 
 | ||||
|   // project with Jacobian | ||||
|   gtsam::StereoPoint2 project2(const gtsam::Point3& point, | ||||
|  | @ -1443,10 +1443,10 @@ class BearingRange { | |||
|   BearingRange(const BEARING& b, const RANGE& r); | ||||
|   BEARING bearing() const; | ||||
|   RANGE range() const; | ||||
|   static This Measure(const POSE& pose, const POINT& point); | ||||
|   static BEARING MeasureBearing(const POSE& pose, const POINT& point); | ||||
|   static RANGE MeasureRange(const POSE& pose, const POINT& point); | ||||
|   void print(string s = "") const; | ||||
|   static This Measure(const POSE& a1, const POINT& a2); | ||||
|   static BEARING MeasureBearing(const POSE& a1, const POINT& a2); | ||||
|   static RANGE MeasureRange(const POSE& a1, const POINT& a2); | ||||
|   void print(string str = "") const; | ||||
| }; | ||||
| 
 | ||||
| typedef gtsam::BearingRange<gtsam::Pose2, gtsam::Point2, gtsam::Rot2, double> | ||||
|  |  | |||
|  | @ -39,7 +39,7 @@ virtual class HybridFactor : gtsam::Factor { | |||
|   void print(string s = "HybridFactor\n", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::HybridFactor& other, double tol = 1e-9) const; | ||||
|   bool equals(const gtsam::HybridFactor& lf, double tol = 1e-9) const; | ||||
| 
 | ||||
|   // Standard interface: | ||||
|   double error(const gtsam::HybridValues& values) const; | ||||
|  | @ -145,7 +145,7 @@ class HybridBayesNet { | |||
|   const gtsam::HybridConditional* at(size_t i) const; | ||||
| 
 | ||||
|   // Standard interface: | ||||
|   double logProbability(const gtsam::HybridValues& values) const; | ||||
|   double logProbability(const gtsam::HybridValues& x) const; | ||||
|   double evaluate(const gtsam::HybridValues& values) const; | ||||
|   double error(const gtsam::HybridValues& values) const; | ||||
| 
 | ||||
|  | @ -163,7 +163,7 @@ class HybridBayesNet { | |||
|   void print(string s = "HybridBayesNet\n", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::HybridBayesNet& other, double tol = 1e-9) const; | ||||
|   bool equals(const gtsam::HybridBayesNet& fg, double tol = 1e-9) const; | ||||
| 
 | ||||
|   string dot( | ||||
|       const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter, | ||||
|  |  | |||
|  | @ -143,7 +143,7 @@ class Ordering { | |||
|   template < | ||||
|       FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, | ||||
|                       gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph, gtsam::HybridGaussianFactorGraph}> | ||||
|   static gtsam::Ordering Natural(const FACTOR_GRAPH& graph); | ||||
|   static gtsam::Ordering Natural(const FACTOR_GRAPH& fg); | ||||
| 
 | ||||
|   template < | ||||
|       FACTOR_GRAPH = {gtsam::NonlinearFactorGraph, gtsam::DiscreteFactorGraph, | ||||
|  | @ -159,7 +159,7 @@ class Ordering { | |||
|   // Testable | ||||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::Ordering& ord, double tol) const; | ||||
|   bool equals(const gtsam::Ordering& other, double tol) const; | ||||
| 
 | ||||
|   // Standard interface | ||||
|   size_t size() const; | ||||
|  |  | |||
|  | @ -313,7 +313,7 @@ namespace gtsam { | |||
|      *  the dense elimination function specified in \c function (default EliminatePreferCholesky), | ||||
|      *  followed by back-substitution in the Bayes tree resulting from elimination.  Is equivalent | ||||
|      *  to calling graph.eliminateMultifrontal()->optimize(). */ | ||||
|     VectorValues optimize(const Ordering&, | ||||
|     VectorValues optimize(const Ordering& ordering, | ||||
|       const Eliminate& function = EliminationTraitsType::DefaultEliminate) const; | ||||
| 
 | ||||
|     /**
 | ||||
|  |  | |||
|  | @ -276,7 +276,7 @@ class VectorValues { | |||
|   VectorValues(const gtsam::VectorValues& first, const gtsam::VectorValues& second); | ||||
| 
 | ||||
|   //Named Constructors | ||||
|   static gtsam::VectorValues Zero(const gtsam::VectorValues& model); | ||||
|   static gtsam::VectorValues Zero(const gtsam::VectorValues& other); | ||||
| 
 | ||||
|   //Standard Interface | ||||
|   size_t size() const; | ||||
|  | @ -285,7 +285,7 @@ class VectorValues { | |||
|   void print(string s = "VectorValues", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::VectorValues& expected, double tol) const; | ||||
|   bool equals(const gtsam::VectorValues& x, double tol) const; | ||||
|   void insert(size_t j, gtsam::Vector value); | ||||
|   gtsam::Vector vector() const; | ||||
|   gtsam::Vector vector(const gtsam::KeyVector& keys) const; | ||||
|  | @ -300,10 +300,10 @@ class VectorValues { | |||
|   void addInPlace(const gtsam::VectorValues& c); | ||||
|   gtsam::VectorValues subtract(const gtsam::VectorValues& c) const; | ||||
|   gtsam::VectorValues scale(double a) const; | ||||
|   void scaleInPlace(double a); | ||||
|   void scaleInPlace(double alpha); | ||||
| 
 | ||||
|   bool hasSameStructure(const gtsam::VectorValues& other)  const; | ||||
|   double dot(const gtsam::VectorValues& V) const; | ||||
|   double dot(const gtsam::VectorValues& v) const; | ||||
|   double norm() const; | ||||
|   double squaredNorm() const; | ||||
| 
 | ||||
|  | @ -419,7 +419,7 @@ class GaussianFactorGraph { | |||
|   // From FactorGraph | ||||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::GaussianFactorGraph& lfgraph, double tol) const; | ||||
|   bool equals(const gtsam::GaussianFactorGraph& fg, double tol) const; | ||||
|   size_t size() const; | ||||
|   gtsam::GaussianFactor* at(size_t idx) const; | ||||
|   gtsam::KeySet keys() const; | ||||
|  | @ -441,9 +441,9 @@ class GaussianFactorGraph { | |||
|       gtsam::Vector b, const gtsam::noiseModel::Diagonal* model); | ||||
| 
 | ||||
|   // error and probability | ||||
|   double error(const gtsam::VectorValues& c) const; | ||||
|   double error(const gtsam::VectorValues& x) const; | ||||
|   double probPrime(const gtsam::VectorValues& c) const; | ||||
|   void printErrors(const gtsam::VectorValues& c, string str = "GaussianFactorGraph: ", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; | ||||
|   void printErrors(const gtsam::VectorValues& x, string str = "GaussianFactorGraph: ", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const; | ||||
| 
 | ||||
|   gtsam::GaussianFactorGraph clone() const; | ||||
|   gtsam::GaussianFactorGraph negate() const; | ||||
|  | @ -553,7 +553,7 @@ virtual class GaussianConditional : gtsam::JacobianFactor { | |||
|   double negLogConstant() const; | ||||
|   double logProbability(const gtsam::VectorValues& x) const; | ||||
|   double evaluate(const gtsam::VectorValues& x) const; | ||||
|   double error(const gtsam::VectorValues& x) const; | ||||
|   double error(const gtsam::VectorValues& c) const; | ||||
|   gtsam::Key firstFrontalKey() const; | ||||
|   gtsam::VectorValues solve(const gtsam::VectorValues& parents) const; | ||||
|   gtsam::JacobianFactor* likelihood( | ||||
|  | @ -609,7 +609,7 @@ virtual class GaussianBayesNet { | |||
|   // Testable | ||||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::GaussianBayesNet& other, double tol) const; | ||||
|   bool equals(const gtsam::GaussianBayesNet& bn, double tol) const; | ||||
|   size_t size() const; | ||||
| 
 | ||||
|   void push_back(gtsam::GaussianConditional* conditional); | ||||
|  |  | |||
|  | @ -85,7 +85,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation | |||
|   void print(const std::string& s = "Preintegrated Measurements: ") const; | ||||
| 
 | ||||
|   /// equals
 | ||||
|   bool equals(const PreintegratedAhrsMeasurements&, double tol = 1e-9) const; | ||||
|   bool equals(const PreintegratedAhrsMeasurements& expected, double tol = 1e-9) const; | ||||
| 
 | ||||
|   /// Reset integrated quantities to zero
 | ||||
|   void resetIntegration(); | ||||
|  |  | |||
|  | @ -46,7 +46,7 @@ class NavState { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::NavState& expected, double tol) const; | ||||
|   bool equals(const gtsam::NavState& other, double tol) const; | ||||
| 
 | ||||
|   // Access | ||||
|   gtsam::Rot3 attitude() const; | ||||
|  | @ -55,22 +55,22 @@ class NavState { | |||
|   gtsam::Pose3 pose() const; | ||||
| 
 | ||||
|   // Manifold | ||||
|   gtsam::NavState retract(const gtsam::Vector& x) const; | ||||
|   gtsam::NavState retract(const gtsam::Vector& v) const; | ||||
|   gtsam::Vector localCoordinates(const gtsam::NavState& g) const; | ||||
| 
 | ||||
|   // Lie Group | ||||
|   static gtsam::NavState Expmap(gtsam::Vector v); | ||||
|   static gtsam::Vector Logmap(const gtsam::NavState& p); | ||||
|   static gtsam::NavState Expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::Vector Logmap(const gtsam::NavState& p, Eigen::Ref<Eigen::MatrixXd> H); | ||||
|   static gtsam::NavState Expmap(gtsam::Vector xi, Eigen::Ref<Eigen::MatrixXd> Hxi); | ||||
|   static gtsam::Vector Logmap(const gtsam::NavState& pose, Eigen::Ref<Eigen::MatrixXd> Hpose); | ||||
|   gtsam::NavState expmap(gtsam::Vector v); | ||||
|   gtsam::NavState expmap(gtsam::Vector v, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2); | ||||
|   gtsam::Vector logmap(const gtsam::NavState& p); | ||||
|   gtsam::Vector logmap(const gtsam::NavState& p, Eigen::Ref<Eigen::MatrixXd> H1, Eigen::Ref<Eigen::MatrixXd> H2); | ||||
|   gtsam::Matrix AdjointMap() const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi) const; | ||||
|   gtsam::Vector Adjoint(gtsam::Vector xi_b) const; | ||||
|   static gtsam::Matrix Hat(const gtsam::Vector& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& xi); | ||||
|   static gtsam::Vector Vee(const gtsam::Matrix& X); | ||||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
|  | @ -82,7 +82,7 @@ virtual class PreintegratedRotationParams { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::PreintegratedRotationParams& expected, double tol); | ||||
|   bool equals(const gtsam::PreintegratedRotationParams& other, double tol); | ||||
| 
 | ||||
|   void setGyroscopeCovariance(gtsam::Matrix cov); | ||||
|   void setOmegaCoriolis(gtsam::Vector omega); | ||||
|  | @ -114,7 +114,7 @@ class PreintegratedRotation { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::PreintegratedRotation& expected, double tol) const; | ||||
|   bool equals(const gtsam::PreintegratedRotation& other, double tol) const; | ||||
| 
 | ||||
|   // enabling serialization functionality | ||||
|   void serialize() const; | ||||
|  | @ -133,7 +133,7 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::PreintegrationParams& expected, double tol); | ||||
|   bool equals(const gtsam::PreintegrationParams& other, double tol); | ||||
| 
 | ||||
|   void setAccelerometerCovariance(gtsam::Matrix cov); | ||||
|   void setIntegrationCovariance(gtsam::Matrix cov); | ||||
|  | @ -221,7 +221,7 @@ virtual class PreintegrationCombinedParams : gtsam::PreintegrationParams { | |||
| 
 | ||||
|   // Testable | ||||
|   void print(string s = "") const; | ||||
|   bool equals(const gtsam::PreintegrationCombinedParams& expected, double tol); | ||||
|   bool equals(const gtsam::PreintegrationCombinedParams& other, double tol); | ||||
| 
 | ||||
|   void setBiasAccCovariance(gtsam::Matrix cov); | ||||
|   void setBiasOmegaCovariance(gtsam::Matrix cov); | ||||
|  |  | |||
|  | @ -139,7 +139,7 @@ public: | |||
|    * when the constraint is *NOT* fulfilled. | ||||
|    * @return true if the constraint is active | ||||
|    */ | ||||
|   virtual bool active(const Values& /*c*/) const { return true; } | ||||
|   virtual bool active(const Values& c) const { return true; } | ||||
| 
 | ||||
|   /** linearize to a GaussianFactor */ | ||||
|   virtual std::shared_ptr<GaussianFactor> | ||||
|  |  | |||
|  | @ -50,7 +50,7 @@ class NonlinearFactorGraph { | |||
|   void print(string s = "NonlinearFactorGraph: ", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::NonlinearFactorGraph& fg, double tol) const; | ||||
|   bool equals(const gtsam::NonlinearFactorGraph& other, double tol) const; | ||||
|   size_t size() const; | ||||
|   bool empty() const; | ||||
|   void remove(size_t i); | ||||
|  | @ -107,7 +107,7 @@ class NonlinearFactorGraph { | |||
|   gtsam::Ordering orderingCOLAMD() const; | ||||
|   // Ordering* orderingCOLAMDConstrained(const gtsam::Values& c, const | ||||
|   // std::map<gtsam::Key,int>& constraints) const; | ||||
|   gtsam::GaussianFactorGraph* linearize(const gtsam::Values& values) const; | ||||
|   gtsam::GaussianFactorGraph* linearize(const gtsam::Values& linearizationPoint) const; | ||||
|   gtsam::NonlinearFactorGraph clone() const; | ||||
| 
 | ||||
|   string dot( | ||||
|  | @ -129,7 +129,7 @@ virtual class NonlinearFactor : gtsam::Factor { | |||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   // NonlinearFactor | ||||
|   bool equals(const gtsam::NonlinearFactor& other, double tol) const; | ||||
|   bool equals(const gtsam::NonlinearFactor& f, double tol) const; | ||||
|   double error(const gtsam::Values& c) const; | ||||
|   double error(const gtsam::HybridValues& c) const; | ||||
|   size_t dim() const; | ||||
|  | @ -141,11 +141,11 @@ virtual class NonlinearFactor : gtsam::Factor { | |||
| 
 | ||||
| #include <gtsam/nonlinear/NonlinearFactor.h> | ||||
| virtual class NoiseModelFactor : gtsam::NonlinearFactor { | ||||
|   bool equals(const gtsam::NoiseModelFactor& other, double tol) const; | ||||
|   bool equals(const gtsam::NoiseModelFactor& f, double tol) const; | ||||
|   gtsam::noiseModel::Base* noiseModel() const; | ||||
|   gtsam::NoiseModelFactor* cloneWithNewNoiseModel(gtsam::noiseModel::Base* newNoise) const; | ||||
|   gtsam::Vector unwhitenedError(const gtsam::Values& x) const; | ||||
|   gtsam::Vector whitenedError(const gtsam::Values& x) const; | ||||
|   gtsam::Vector whitenedError(const gtsam::Values& c) const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/nonlinear/Marginals.h> | ||||
|  | @ -216,7 +216,7 @@ virtual class LinearContainerFactor : gtsam::NonlinearFactor { | |||
| #include <gtsam/nonlinear/NonlinearOptimizerParams.h> | ||||
| virtual class NonlinearOptimizerParams { | ||||
|   NonlinearOptimizerParams(); | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   int getMaxIterations() const; | ||||
|   double getRelativeErrorTol() const; | ||||
|  | @ -228,7 +228,7 @@ virtual class NonlinearOptimizerParams { | |||
|   void setRelativeErrorTol(double value); | ||||
|   void setAbsoluteErrorTol(double value); | ||||
|   void setErrorTol(double value); | ||||
|   void setVerbosity(string s); | ||||
|   void setVerbosity(string src); | ||||
| 
 | ||||
|   string getLinearSolverType() const; | ||||
|   void setLinearSolverType(string solver); | ||||
|  | @ -404,14 +404,14 @@ virtual class LevenbergMarquardtOptimizer : gtsam::NonlinearOptimizer { | |||
|                                   gtsam::LevenbergMarquardtParams()); | ||||
| 
 | ||||
|   double lambda() const; | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/nonlinear/ISAM2.h> | ||||
| class ISAM2GaussNewtonParams { | ||||
|   ISAM2GaussNewtonParams(double _wildfireThreshold = 0.001); | ||||
| 
 | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   /** Getters and Setters for all properties */ | ||||
|   double getWildfireThreshold() const; | ||||
|  | @ -421,7 +421,7 @@ class ISAM2GaussNewtonParams { | |||
| class ISAM2DoglegParams { | ||||
|   ISAM2DoglegParams(); | ||||
| 
 | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   /** Getters and Setters for all properties */ | ||||
|   double getWildfireThreshold() const; | ||||
|  | @ -457,13 +457,13 @@ class ISAM2ThresholdMap { | |||
| class ISAM2Params { | ||||
|   ISAM2Params(); | ||||
| 
 | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   /** Getters and Setters for all properties */ | ||||
|   void setOptimizationParams( | ||||
|       const gtsam::ISAM2GaussNewtonParams& gauss_newton__params); | ||||
|   void setOptimizationParams(const gtsam::ISAM2DoglegParams& dogleg_params); | ||||
|   void setRelinearizeThreshold(double threshold); | ||||
|   void setOptimizationParams(const gtsam::ISAM2DoglegParams& optimizationParams); | ||||
|   void setRelinearizeThreshold(double relinearizeThreshold); | ||||
|   void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& threshold_map); | ||||
|   string getFactorization() const; | ||||
|   void setFactorization(string factorization); | ||||
|  | @ -493,7 +493,7 @@ class ISAM2Clique { | |||
| class ISAM2Result { | ||||
|   ISAM2Result(); | ||||
| 
 | ||||
|   void print(string s = "") const; | ||||
|   void print(string str = "") const; | ||||
| 
 | ||||
|   /** Getters and Setters for all properties */ | ||||
|   size_t getVariablesRelinearized() const; | ||||
|  | @ -542,7 +542,7 @@ class ISAM2 { | |||
|                             const gtsam::Values& newTheta, | ||||
|                             const gtsam::ISAM2UpdateParams& updateParams); | ||||
| 
 | ||||
|   double error(const gtsam::VectorValues& values) const; | ||||
|   double error(const gtsam::VectorValues& x) const; | ||||
| 
 | ||||
|   gtsam::Values getLinearizationPoint() const; | ||||
|   bool valueExists(gtsam::Key key) const; | ||||
|  | @ -717,7 +717,7 @@ virtual class FixedLagSmoother { | |||
| virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother { | ||||
|   BatchFixedLagSmoother(); | ||||
|   BatchFixedLagSmoother(double smootherLag); | ||||
|   BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params); | ||||
|   BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& parameters); | ||||
| 
 | ||||
|   void print(string s = "BatchFixedLagSmoother:\n") const; | ||||
| 
 | ||||
|  | @ -735,7 +735,7 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother { | |||
| virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother { | ||||
|   IncrementalFixedLagSmoother(); | ||||
|   IncrementalFixedLagSmoother(double smootherLag); | ||||
|   IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params); | ||||
|   IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& parameters); | ||||
| 
 | ||||
|   void print(string s = "IncrementalFixedLagSmoother:\n") const; | ||||
| 
 | ||||
|  |  | |||
|  | @ -49,7 +49,7 @@ class Values { | |||
|   void update(const gtsam::Values& values); | ||||
|   void insert_or_assign(const gtsam::Values& values); | ||||
|   void erase(size_t j); | ||||
|   void swap(gtsam::Values& values); | ||||
|   void swap(gtsam::Values& other); | ||||
| 
 | ||||
|   bool exists(size_t j) const; | ||||
|   gtsam::KeyVector keys() const; | ||||
|  |  | |||
|  | @ -34,7 +34,7 @@ virtual class SfmTrack : gtsam::SfmTrack2d { | |||
|   void serialize() const; | ||||
| 
 | ||||
|   // enabling function to compare objects | ||||
|   bool equals(const gtsam::SfmTrack& expected, double tol) const; | ||||
|   bool equals(const gtsam::SfmTrack& sfmTrack, double tol) const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/nonlinear/NonlinearFactorGraph.h> | ||||
|  | @ -67,7 +67,7 @@ class SfmData { | |||
|   void serialize() const; | ||||
| 
 | ||||
|   // enabling function to compare objects | ||||
|   bool equals(const gtsam::SfmData& expected, double tol) const; | ||||
|   bool equals(const gtsam::SfmData& sfmData, double tol) const; | ||||
| }; | ||||
| 
 | ||||
| gtsam::SfmData readBal(string filename); | ||||
|  |  | |||
|  | @ -309,7 +309,7 @@ virtual class EssentialMatrixConstraint : gtsam::NoiseModelFactor { | |||
|                             const gtsam::noiseModel::Base *model); | ||||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::EssentialMatrixConstraint& other, double tol) const; | ||||
|   bool equals(const gtsam::EssentialMatrixConstraint& expected, double tol) const; | ||||
|   gtsam::Vector evaluateError(const gtsam::Pose3& p1, const gtsam::Pose3& p2) const; | ||||
|   const gtsam::EssentialMatrix& measured() const; | ||||
| }; | ||||
|  | @ -407,14 +407,14 @@ gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model, | |||
| template <T = {gtsam::Rot2, gtsam::Rot3, gtsam::SO3, gtsam::SO4, gtsam::Pose2, gtsam::Pose3}> | ||||
| virtual class FrobeniusFactor : gtsam::NoiseModelFactor { | ||||
|   FrobeniusFactor(size_t key1, size_t key2); | ||||
|   FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model); | ||||
|   FrobeniusFactor(size_t j1, size_t j2, gtsam::noiseModel::Base* model); | ||||
| 
 | ||||
|   gtsam::Vector evaluateError(const T& T1, const T& T2); | ||||
| }; | ||||
| 
 | ||||
| template <T = {gtsam::Rot2, gtsam::Rot3, gtsam::SO3, gtsam::SO4, gtsam::Pose2, gtsam::Pose3}> | ||||
| virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { | ||||
|   FrobeniusBetweenFactor(size_t key1, size_t key2, const T& T12); | ||||
|   FrobeniusBetweenFactor(size_t j1, size_t j2, const T& T12); | ||||
|   FrobeniusBetweenFactor(size_t key1, size_t key2, const T& T12, | ||||
|                          gtsam::noiseModel::Base* model); | ||||
| 
 | ||||
|  |  | |||
|  | @ -15,7 +15,7 @@ virtual class SymbolicFactor : gtsam::Factor { | |||
|   SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5); | ||||
|   SymbolicFactor(size_t j1, size_t j2, size_t j3, size_t j4, size_t j5, | ||||
|                  size_t j6); | ||||
|   static gtsam::SymbolicFactor FromKeys(const gtsam::KeyVector& js); | ||||
|   static gtsam::SymbolicFactor FromKeys(const gtsam::KeyVector& keys); | ||||
| 
 | ||||
|   // From Factor | ||||
|   void print(string s = "SymbolicFactor", | ||||
|  | @ -35,7 +35,7 @@ virtual class SymbolicFactorGraph { | |||
|   void print(string s = "SymbolicFactorGraph", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; | ||||
|   bool equals(const gtsam::SymbolicFactorGraph& fg, double tol) const; | ||||
|   size_t size() const; | ||||
|   bool exists(size_t idx) const; | ||||
| 
 | ||||
|  | @ -101,7 +101,7 @@ virtual class SymbolicConditional : gtsam::SymbolicFactor { | |||
|   // Testable | ||||
|   void print(string s = "", const gtsam::KeyFormatter& keyFormatter = | ||||
|                                 gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::SymbolicConditional& other, double tol) const; | ||||
|   bool equals(const gtsam::SymbolicConditional& c, double tol) const; | ||||
| 
 | ||||
|   // Standard interface | ||||
|   gtsam::Key firstFrontalKey() const; | ||||
|  | @ -117,7 +117,7 @@ class SymbolicBayesNet { | |||
|   void print(string s = "SymbolicBayesNet", | ||||
|              const gtsam::KeyFormatter& keyFormatter = | ||||
|                  gtsam::DefaultKeyFormatter) const; | ||||
|   bool equals(const gtsam::SymbolicBayesNet& other, double tol) const; | ||||
|   bool equals(const gtsam::SymbolicBayesNet& bn, double tol) const; | ||||
| 
 | ||||
|   // Standard interface | ||||
|   size_t size() const; | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue