Deprecated some more methods
							parent
							
								
									23d4c0fd9f
								
							
						
					
					
						commit
						4319bece1e
					
				
							
								
								
									
										39
									
								
								gtsam.h
								
								
								
								
							
							
						
						
									
										39
									
								
								gtsam.h
								
								
								
								
							|  | @ -127,13 +127,13 @@ namespace std { | |||
|         void pop_back();*/ | ||||
|     }; | ||||
|     //typedef std::vector
 | ||||
|    | ||||
| 
 | ||||
|     #include<list> | ||||
|     template<T> | ||||
|     class list | ||||
|     { | ||||
|      | ||||
|      | ||||
| 
 | ||||
| 
 | ||||
|     }; | ||||
| 
 | ||||
| } | ||||
|  | @ -360,17 +360,6 @@ class Point3 { | |||
| 
 | ||||
|   // Group
 | ||||
|   static gtsam::Point3 identity(); | ||||
|   gtsam::Point3 inverse() const; | ||||
|   gtsam::Point3 compose(const gtsam::Point3& p2) const; | ||||
|   gtsam::Point3 between(const gtsam::Point3& p2) const; | ||||
| 
 | ||||
|   // Manifold
 | ||||
|   gtsam::Point3 retract(Vector v) const; | ||||
|   Vector localCoordinates(const gtsam::Point3& p) const; | ||||
| 
 | ||||
|   // Lie Group
 | ||||
|   static gtsam::Point3 Expmap(Vector v); | ||||
|   static Vector Logmap(const gtsam::Point3& p); | ||||
| 
 | ||||
|   // Standard Interface
 | ||||
|   Vector vector() const; | ||||
|  | @ -1069,7 +1058,7 @@ class SymbolicBayesTree { | |||
|     void clear(); | ||||
|     void deleteCachedShortcuts(); | ||||
|     size_t numCachedSeparatorMarginals() const; | ||||
|    | ||||
| 
 | ||||
|   gtsam::SymbolicConditional* marginalFactor(size_t key) const; | ||||
|   gtsam::SymbolicFactorGraph* joint(size_t key1, size_t key2) const; | ||||
|   gtsam::SymbolicBayesNet* jointBayesNet(size_t key1, size_t key2) const; | ||||
|  | @ -1079,19 +1068,19 @@ class SymbolicBayesTree { | |||
| //   BayesTreeClique();
 | ||||
| //   BayesTreeClique(CONDITIONAL* conditional);
 | ||||
| // //  BayesTreeClique(const std::pair<typename ConditionalType::shared_ptr, typename ConditionalType::FactorType::shared_ptr>& result) : Base(result) {}
 | ||||
| // 
 | ||||
| //
 | ||||
| //   bool equals(const This& other, double tol) const;
 | ||||
| //   void print(string s) const;
 | ||||
| //   void printTree() const; // Default indent of ""
 | ||||
| //   void printTree(string indent) const;
 | ||||
| //   size_t numCachedSeparatorMarginals() const;
 | ||||
| // 
 | ||||
| //
 | ||||
| //   CONDITIONAL* conditional() const;
 | ||||
| //   bool isRoot() const;
 | ||||
| //   size_t treeSize() const;
 | ||||
| // //  const std::list<derived_ptr>& children() const { return children_; }
 | ||||
| // //  derived_ptr parent() const { return parent_.lock(); }
 | ||||
| // 
 | ||||
| //
 | ||||
| //   // FIXME: need wrapped versions graphs, BayesNet
 | ||||
| // //  BayesNet<ConditionalType> shortcut(derived_ptr root, Eliminate function) const;
 | ||||
| // //  FactorGraph<FactorType> marginal(derived_ptr root, Eliminate function) const;
 | ||||
|  | @ -1345,7 +1334,7 @@ virtual class JacobianFactor : gtsam::GaussianFactor { | |||
| 
 | ||||
|   void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; | ||||
|   gtsam::JacobianFactor whiten() const; | ||||
|    | ||||
| 
 | ||||
|   pair<gtsam::GaussianConditional*, gtsam::JacobianFactor*> eliminate(const gtsam::Ordering& keys) const; | ||||
| 
 | ||||
|   void setModel(bool anyConstrained, const Vector& sigmas); | ||||
|  | @ -1422,7 +1411,7 @@ class GaussianFactorGraph { | |||
|   gtsam::GaussianFactorGraph clone() const; | ||||
|   gtsam::GaussianFactorGraph negate() const; | ||||
| 
 | ||||
|   // Optimizing and linear algebra  
 | ||||
|   // Optimizing and linear algebra
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimize(const gtsam::Ordering& ordering) const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|  | @ -1511,7 +1500,7 @@ virtual class GaussianBayesNet { | |||
|     //Constructors
 | ||||
|   GaussianBayesNet(); | ||||
|   GaussianBayesNet(const gtsam::GaussianConditional* conditional); | ||||
|    | ||||
| 
 | ||||
|   // Testable
 | ||||
|   void print(string s) const; | ||||
|   bool equals(const gtsam::GaussianBayesNet& other, double tol) const; | ||||
|  | @ -1527,7 +1516,7 @@ virtual class GaussianBayesNet { | |||
|   gtsam::GaussianConditional* back() const; | ||||
|   void push_back(gtsam::GaussianConditional* conditional); | ||||
|   void push_back(const gtsam::GaussianBayesNet& bayesNet); | ||||
|    | ||||
| 
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimize(gtsam::VectorValues& solutionForMissing) const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|  | @ -1551,7 +1540,7 @@ virtual class GaussianBayesTree { | |||
|   bool empty() const; | ||||
|   size_t numCachedSeparatorMarginals() const; | ||||
|   void saveGraph(string s) const; | ||||
|    | ||||
| 
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|   gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; | ||||
|  | @ -1833,7 +1822,7 @@ class Values { | |||
| 
 | ||||
|   /// Fixed size versions, for n in 1..9
 | ||||
|   Vector atFixed(size_t j, size_t n); | ||||
|    | ||||
| 
 | ||||
|   /// version for double
 | ||||
|   void insertDouble(size_t j, double c); | ||||
|   double atDouble(size_t j) const; | ||||
|  | @ -2004,7 +1993,7 @@ virtual class NonlinearOptimizerParams { | |||
|   void setVerbosity(string s); | ||||
| 
 | ||||
|   string getLinearSolverType() const; | ||||
|    | ||||
| 
 | ||||
|   void setLinearSolverType(string solver); | ||||
|   void setOrdering(const gtsam::Ordering& ordering); | ||||
|   void setIterativeParams(gtsam::IterativeOptimizationParameters* params); | ||||
|  |  | |||
|  | @ -1,6 +1,6 @@ | |||
| /* ----------------------------------------------------------------------------
 | ||||
| 
 | ||||
|  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | ||||
|  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | ||||
|  * Atlanta, Georgia 30332-0415 | ||||
|  * All Rights Reserved | ||||
|  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | ||||
|  | @ -75,6 +75,7 @@ double Point3::distance(const Point3 &p2, OptionalJacobian<1, 3> H1, | |||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 | ||||
| Point3 Point3::add(const Point3 &q, OptionalJacobian<3,3> H1, | ||||
|     OptionalJacobian<3,3> H2) const { | ||||
|   if (H1) *H1 = I_3x3; | ||||
|  | @ -82,13 +83,13 @@ Point3 Point3::add(const Point3 &q, OptionalJacobian<3,3> H1, | |||
|   return *this + q; | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| Point3 Point3::sub(const Point3 &q, OptionalJacobian<3,3> H1, | ||||
|     OptionalJacobian<3,3> H2) const { | ||||
|   if (H1) *H1 = I_3x3; | ||||
|   if (H2) *H2 = I_3x3; | ||||
|   return *this - q; | ||||
| } | ||||
| #endif | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| Point3 Point3::cross(const Point3 &q, OptionalJacobian<3, 3> H_p, OptionalJacobian<3, 3> H_q) const { | ||||
|  |  | |||
|  | @ -107,11 +107,6 @@ namespace gtsam { | |||
|     double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none, | ||||
|                     OptionalJacobian<1, 3> H2 = boost::none) const; | ||||
| 
 | ||||
|     /** @deprecated The following function has been deprecated, use distance above */ | ||||
|     inline double dist(const Point3& p2) const { | ||||
|       return (p2 - *this).norm(); | ||||
|     } | ||||
| 
 | ||||
|     /** Distance of the point from the origin, with Jacobian */ | ||||
|     double norm(OptionalJacobian<1,3> H = boost::none) const; | ||||
| 
 | ||||
|  | @ -145,14 +140,6 @@ namespace gtsam { | |||
|     /// get z
 | ||||
|     inline double z() const {return z_;} | ||||
| 
 | ||||
|     /** add two points, add(this,q) is same as this + q */ | ||||
|     Point3 add (const Point3 &q, | ||||
|           OptionalJacobian<3, 3> H1=boost::none, OptionalJacobian<3, 3> H2=boost::none) const; | ||||
| 
 | ||||
|     /** subtract two points, sub(this,q) is same as this - q */ | ||||
|     Point3 sub (const Point3 &q, | ||||
|           OptionalJacobian<3,3> H1=boost::none, OptionalJacobian<3,3> H2=boost::none) const; | ||||
| 
 | ||||
|     /// @}
 | ||||
| 
 | ||||
|     /// Output stream operator
 | ||||
|  | @ -168,7 +155,12 @@ namespace gtsam { | |||
|     Point3 retract(const Vector3& v) const { return compose(Point3(v));} | ||||
|     static Vector3 Logmap(const Point3& p) { return p.vector();} | ||||
|     static Point3 Expmap(const Vector3& v) { return Point3(v);} | ||||
|     /// @}
 | ||||
|     inline double dist(const Point3& p2) const { return (p2 - *this).norm(); } | ||||
|     Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, | ||||
|                OptionalJacobian<3, 3> H2 = boost::none) const; | ||||
|     Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none, | ||||
|                OptionalJacobian<3, 3> H2 = boost::none) const; | ||||
|   /// @}
 | ||||
| #endif | ||||
| 
 | ||||
|   private: | ||||
|  |  | |||
							
								
								
									
										39
									
								
								gtsampy.h
								
								
								
								
							
							
						
						
									
										39
									
								
								gtsampy.h
								
								
								
								
							|  | @ -127,13 +127,13 @@ namespace std { | |||
|         void pop_back();*/ | ||||
|     }; | ||||
|     //typedef std::vector
 | ||||
|    | ||||
| 
 | ||||
|     #include<list> | ||||
|     template<T> | ||||
|     class list | ||||
|     { | ||||
|      | ||||
|      | ||||
| 
 | ||||
| 
 | ||||
|     }; | ||||
| 
 | ||||
| } | ||||
|  | @ -360,17 +360,6 @@ class Point3 { | |||
| 
 | ||||
|   // Group
 | ||||
|   static gtsam::Point3 identity(); | ||||
|   gtsam::Point3 inverse() const; | ||||
|   gtsam::Point3 compose(const gtsam::Point3& p2) const; | ||||
|   gtsam::Point3 between(const gtsam::Point3& p2) const; | ||||
| 
 | ||||
|   // Manifold
 | ||||
|   gtsam::Point3 retract(Vector v) const; | ||||
|   Vector localCoordinates(const gtsam::Point3& p) const; | ||||
| 
 | ||||
|   // Lie Group
 | ||||
|   static gtsam::Point3 Expmap(Vector v); | ||||
|   static Vector Logmap(const gtsam::Point3& p); | ||||
| 
 | ||||
|   // Standard Interface
 | ||||
|   Vector vector() const; | ||||
|  | @ -1069,7 +1058,7 @@ class SymbolicBayesTree { | |||
|     void clear(); | ||||
|     void deleteCachedShortcuts(); | ||||
|     size_t numCachedSeparatorMarginals() const; | ||||
|    | ||||
| 
 | ||||
|   gtsam::SymbolicConditional* marginalFactor(size_t key) const; | ||||
|   gtsam::SymbolicFactorGraph* joint(size_t key1, size_t key2) const; | ||||
|   gtsam::SymbolicBayesNet* jointBayesNet(size_t key1, size_t key2) const; | ||||
|  | @ -1079,19 +1068,19 @@ class SymbolicBayesTree { | |||
| //   BayesTreeClique();
 | ||||
| //   BayesTreeClique(CONDITIONAL* conditional);
 | ||||
| // //  BayesTreeClique(const std::pair<typename ConditionalType::shared_ptr, typename ConditionalType::FactorType::shared_ptr>& result) : Base(result) {}
 | ||||
| // 
 | ||||
| //
 | ||||
| //   bool equals(const This& other, double tol) const;
 | ||||
| //   void print(string s) const;
 | ||||
| //   void printTree() const; // Default indent of ""
 | ||||
| //   void printTree(string indent) const;
 | ||||
| //   size_t numCachedSeparatorMarginals() const;
 | ||||
| // 
 | ||||
| //
 | ||||
| //   CONDITIONAL* conditional() const;
 | ||||
| //   bool isRoot() const;
 | ||||
| //   size_t treeSize() const;
 | ||||
| // //  const std::list<derived_ptr>& children() const { return children_; }
 | ||||
| // //  derived_ptr parent() const { return parent_.lock(); }
 | ||||
| // 
 | ||||
| //
 | ||||
| //   // FIXME: need wrapped versions graphs, BayesNet
 | ||||
| // //  BayesNet<ConditionalType> shortcut(derived_ptr root, Eliminate function) const;
 | ||||
| // //  FactorGraph<FactorType> marginal(derived_ptr root, Eliminate function) const;
 | ||||
|  | @ -1345,7 +1334,7 @@ virtual class JacobianFactor : gtsam::GaussianFactor { | |||
| 
 | ||||
|   void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const; | ||||
|   gtsam::JacobianFactor whiten() const; | ||||
|    | ||||
| 
 | ||||
|   pair<gtsam::GaussianConditional*, gtsam::JacobianFactor*> eliminate(const gtsam::Ordering& keys) const; | ||||
| 
 | ||||
|   void setModel(bool anyConstrained, const Vector& sigmas); | ||||
|  | @ -1422,7 +1411,7 @@ class GaussianFactorGraph { | |||
|   gtsam::GaussianFactorGraph clone() const; | ||||
|   gtsam::GaussianFactorGraph negate() const; | ||||
| 
 | ||||
|   // Optimizing and linear algebra  
 | ||||
|   // Optimizing and linear algebra
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimize(const gtsam::Ordering& ordering) const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|  | @ -1511,7 +1500,7 @@ virtual class GaussianBayesNet { | |||
|     //Constructors
 | ||||
|   GaussianBayesNet(); | ||||
|   GaussianBayesNet(const gtsam::GaussianConditional* conditional); | ||||
|    | ||||
| 
 | ||||
|   // Testable
 | ||||
|   void print(string s) const; | ||||
|   bool equals(const gtsam::GaussianBayesNet& other, double tol) const; | ||||
|  | @ -1527,7 +1516,7 @@ virtual class GaussianBayesNet { | |||
|   gtsam::GaussianConditional* back() const; | ||||
|   void push_back(gtsam::GaussianConditional* conditional); | ||||
|   void push_back(const gtsam::GaussianBayesNet& bayesNet); | ||||
|    | ||||
| 
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimize(gtsam::VectorValues& solutionForMissing) const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|  | @ -1551,7 +1540,7 @@ virtual class GaussianBayesTree { | |||
|   bool empty() const; | ||||
|   size_t numCachedSeparatorMarginals() const; | ||||
|   void saveGraph(string s) const; | ||||
|    | ||||
| 
 | ||||
|   gtsam::VectorValues optimize() const; | ||||
|   gtsam::VectorValues optimizeGradientSearch() const; | ||||
|   gtsam::VectorValues gradient(const gtsam::VectorValues& x0) const; | ||||
|  | @ -1833,7 +1822,7 @@ class Values { | |||
| 
 | ||||
|   /// Fixed size versions, for n in 1..9
 | ||||
|   Vector atFixed(size_t j, size_t n); | ||||
|    | ||||
| 
 | ||||
|   /// version for double
 | ||||
|   void insertDouble(size_t j, double c); | ||||
|   double atDouble(size_t j) const; | ||||
|  | @ -2004,7 +1993,7 @@ virtual class NonlinearOptimizerParams { | |||
|   void setVerbosity(string s); | ||||
| 
 | ||||
|   string getLinearSolverType() const; | ||||
|    | ||||
| 
 | ||||
|   void setLinearSolverType(string solver); | ||||
|   void setOrdering(const gtsam::Ordering& ordering); | ||||
|   void setIterativeParams(gtsam::IterativeOptimizationParameters* params); | ||||
|  |  | |||
|  | @ -1,6 +1,6 @@ | |||
| /* ----------------------------------------------------------------------------
 | ||||
| 
 | ||||
|  * GTSAM Copyright 2010, Georgia Tech Research Corporation,  | ||||
|  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | ||||
|  * Atlanta, Georgia 30332-0415 | ||||
|  * All Rights Reserved | ||||
|  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | ||||
|  | @ -36,16 +36,13 @@ class_<Point3>("Point3") | |||
|   .def(init<const Vector3 &>()) | ||||
|   .def("identity", &Point3::identity) | ||||
|   .staticmethod("identity") | ||||
|   .def("add", &Point3::add) | ||||
|   .def("cross", &Point3::cross) | ||||
|   .def("dist", &Point3::dist) | ||||
|   .def("distance", &Point3::distance) | ||||
|   .def("dot", &Point3::dot) | ||||
|   .def("equals", &Point3::equals, equals_overloads(args("q","tol"))) | ||||
|   .def("norm", &Point3::norm) | ||||
|   .def("normalize", &Point3::normalize) | ||||
|   .def("print", &Point3::print, print_overloads(args("s"))) | ||||
|   .def("sub", &Point3::sub) | ||||
|   .def("vector", &Point3::vector) | ||||
|   .def("x", &Point3::x) | ||||
|   .def("y", &Point3::y) | ||||
|  | @ -61,4 +58,4 @@ class_<Point3>("Point3") | |||
|   .def(self == self) | ||||
| ; | ||||
| 
 | ||||
| } | ||||
| } | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue