diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 3cf78989c..3d816fc25 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -9,7 +9,7 @@ class Point2 { // Standard Constructors Point2(); Point2(double x, double y); - Point2(Vector v); + Point2(gtsam::Vector v); // Testable void print(string s = "") const; @@ -21,7 +21,7 @@ class Point2 { // Standard Interface double x() const; double y() const; - Vector vector() const; + gtsam::Vector vector() const; double distance(const gtsam::Point2& p2) const; double norm() const; @@ -83,21 +83,21 @@ class StereoPoint2 { // Operator Overloads gtsam::StereoPoint2 operator-() const; - // gtsam::StereoPoint2 operator+(Vector b) const; //TODO Mixed types not yet + // gtsam::StereoPoint2 operator+(gtsam::Vector b) const; //TODO Mixed types not yet // supported gtsam::StereoPoint2 operator+(const gtsam::StereoPoint2& p2) const; gtsam::StereoPoint2 operator-(const gtsam::StereoPoint2& p2) const; // Manifold - gtsam::StereoPoint2 retract(Vector v) const; - Vector localCoordinates(const gtsam::StereoPoint2& p) const; + gtsam::StereoPoint2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::StereoPoint2& p) const; // Lie Group - static gtsam::StereoPoint2 Expmap(Vector v); - static Vector Logmap(const gtsam::StereoPoint2& p); + static gtsam::StereoPoint2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::StereoPoint2& p); // Standard Interface - Vector vector() const; + gtsam::Vector vector() const; double uL() const; double uR() const; double v() const; @@ -111,7 +111,7 @@ class Point3 { // Standard Constructors Point3(); Point3(double x, double y, double z); - Point3(Vector v); + Point3(gtsam::Vector v); // Testable void print(string s = "") const; @@ -121,7 +121,7 @@ class Point3 { static gtsam::Point3 Identity(); // Standard Interface - Vector vector() const; + gtsam::Vector vector() const; double x() const; double y() const; double z() const; @@ -166,15 +166,15 @@ class Rot2 { gtsam::Rot2 operator*(const gtsam::Rot2& p2) const; // Manifold - gtsam::Rot2 retract(Vector v) const; - gtsam::Rot2 retract(Vector v, Eigen::Ref H1, Eigen::Ref H2) const; - Vector localCoordinates(const gtsam::Rot2& p) const; - Vector localCoordinates(const gtsam::Rot2& p, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Rot2 retract(gtsam::Vector v) const; + gtsam::Rot2 retract(gtsam::Vector v, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Vector localCoordinates(const gtsam::Rot2& p) const; + gtsam::Vector localCoordinates(const gtsam::Rot2& p, Eigen::Ref H1, Eigen::Ref H2) const; // Lie Group - static gtsam::Rot2 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot2& p); - Vector logmap(const gtsam::Rot2& p); + static gtsam::Rot2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Rot2& p); + gtsam::Vector logmap(const gtsam::Rot2& p); // Group Action on Point2 gtsam::Point2 rotate(const gtsam::Point2& point) const; @@ -188,7 +188,7 @@ class Rot2 { double degrees() const; double c() const; double s() const; - Matrix matrix() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -198,10 +198,10 @@ class Rot2 { class SO3 { // Standard Constructors SO3(); - SO3(Matrix R); - static gtsam::SO3 FromMatrix(Matrix R); - static gtsam::SO3 AxisAngle(const Vector axis, double theta); - static gtsam::SO3 ClosestTo(const Matrix M); + SO3(gtsam::Matrix R); + static gtsam::SO3 FromMatrix(gtsam::Matrix R); + static gtsam::SO3 AxisAngle(const gtsam::Vector axis, double theta); + static gtsam::SO3 ClosestTo(const gtsam::Matrix M); // Testable void print(string s = "") const; @@ -217,21 +217,21 @@ class SO3 { gtsam::SO3 operator*(const gtsam::SO3& R) const; // Manifold - gtsam::SO3 retract(Vector v) const; - Vector localCoordinates(const gtsam::SO3& R) const; - static gtsam::SO3 Expmap(Vector v); + gtsam::SO3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SO3& R) const; + static gtsam::SO3 Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; }; #include class SO4 { // Standard Constructors SO4(); - SO4(Matrix R); - static gtsam::SO4 FromMatrix(Matrix R); + SO4(gtsam::Matrix R); + static gtsam::SO4 FromMatrix(gtsam::Matrix R); // Testable void print(string s = "") const; @@ -247,21 +247,21 @@ class SO4 { gtsam::SO4 operator*(const gtsam::SO4& Q) const; // Manifold - gtsam::SO4 retract(Vector v) const; - Vector localCoordinates(const gtsam::SO4& Q) const; - static gtsam::SO4 Expmap(Vector v); + gtsam::SO4 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SO4& Q) const; + static gtsam::SO4 Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; }; #include class SOn { // Standard Constructors SOn(size_t n); - static gtsam::SOn FromMatrix(Matrix R); - static gtsam::SOn Lift(size_t n, Matrix R); + static gtsam::SOn FromMatrix(gtsam::Matrix R); + static gtsam::SOn Lift(size_t n, gtsam::Matrix R); // Testable void print(string s = "") const; @@ -277,13 +277,13 @@ class SOn { gtsam::SOn operator*(const gtsam::SOn& Q) const; // Manifold - gtsam::SOn retract(Vector v) const; - Vector localCoordinates(const gtsam::SOn& Q) const; - static gtsam::SOn Expmap(Vector v); + gtsam::SOn retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::SOn& Q) const; + static gtsam::SOn Expmap(gtsam::Vector v); // Other methods - Vector vec() const; - Matrix matrix() const; + gtsam::Vector vec() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -295,14 +295,14 @@ class Quaternion { double x() const; double y() const; double z() const; - Vector coeffs() const; + gtsam::Vector coeffs() const; }; #include class Rot3 { // Standard Constructors and Named Constructors Rot3(); - Rot3(Matrix R); + Rot3(gtsam::Matrix R); Rot3(const gtsam::Point3& col1, const gtsam::Point3& col2, const gtsam::Point3& col3); Rot3(double R11, double R12, double R13, double R21, double R22, double R23, @@ -313,7 +313,7 @@ class Rot3 { static gtsam::Rot3 Ry(double t); static gtsam::Rot3 Rz(double t); static gtsam::Rot3 RzRyRx(double x, double y, double z); - static gtsam::Rot3 RzRyRx(Vector xyz); + static gtsam::Rot3 RzRyRx(gtsam::Vector xyz); static gtsam::Rot3 Yaw( double t); // positive yaw is to right (as in aircraft heading) static gtsam::Rot3 Pitch( @@ -323,9 +323,9 @@ class Rot3 { static gtsam::Rot3 Ypr(double y, double p, double r); static gtsam::Rot3 Quaternion(double w, double x, double y, double z); static gtsam::Rot3 AxisAngle(const gtsam::Point3& axis, double angle); - static gtsam::Rot3 Rodrigues(Vector v); + static gtsam::Rot3 Rodrigues(gtsam::Vector v); static gtsam::Rot3 Rodrigues(double wx, double wy, double wz); - static gtsam::Rot3 ClosestTo(const Matrix M); + static gtsam::Rot3 ClosestTo(const gtsam::Matrix M); // Testable void print(string s = "") const; @@ -341,10 +341,10 @@ class Rot3 { gtsam::Rot3 operator*(const gtsam::Rot3& p2) const; // Manifold - // gtsam::Rot3 retractCayley(Vector v) const; // TODO, does not exist in both - // Matrix and Quaternion options - gtsam::Rot3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Rot3& p) const; + // gtsam::Rot3 retractCayley(gtsam::Vector v) const; // TODO, does not exist in both + // gtsam::Matrix and Quaternion options + gtsam::Rot3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Rot3& p) const; // Group Action on Point3 gtsam::Point3 rotate(const gtsam::Point3& p) const; @@ -358,21 +358,21 @@ class Rot3 { gtsam::Unit3 unrotate(const gtsam::Unit3& p) const; // Standard Interface - static gtsam::Rot3 Expmap(Vector v); - static Vector Logmap(const gtsam::Rot3& p); - Vector logmap(const gtsam::Rot3& p); - Matrix matrix() const; - Matrix transpose() const; + static gtsam::Rot3 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Rot3& p); + gtsam::Vector logmap(const gtsam::Rot3& p); + gtsam::Matrix matrix() const; + gtsam::Matrix transpose() const; gtsam::Point3 column(size_t index) const; - Vector xyz() const; - Vector ypr() const; - Vector rpy() const; + gtsam::Vector xyz() const; + gtsam::Vector ypr() const; + gtsam::Vector rpy() const; double roll() const; double pitch() const; double yaw() const; pair axisAngle() const; gtsam::Quaternion toQuaternion() const; - // Vector quaternion() const; // @deprecated, see https://github.com/borglab/gtsam/pull/1219 + // gtsam::Vector quaternion() const; // @deprecated, see https://github.com/borglab/gtsam/pull/1219 gtsam::Rot3 slerp(double t, const gtsam::Rot3& other) const; // enabling serialization functionality @@ -387,7 +387,7 @@ class Pose2 { Pose2(double x, double y, double theta); Pose2(double theta, const gtsam::Point2& t); Pose2(const gtsam::Rot2& r, const gtsam::Point2& t); - Pose2(Vector v); + Pose2(gtsam::Vector v); static std::optional Align(const gtsam::Point2Pairs& abPointPairs); static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); @@ -408,32 +408,32 @@ class Pose2 { gtsam::Pose2 operator*(const gtsam::Pose2& p2) const; // Manifold - gtsam::Pose2 retract(Vector v) const; - gtsam::Pose2 retract(Vector v, Eigen::Ref H1, Eigen::Ref H2) const; - Vector localCoordinates(const gtsam::Pose2& p) const; - Vector localCoordinates(const gtsam::Pose2& p, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Pose2 retract(gtsam::Vector v) const; + gtsam::Pose2 retract(gtsam::Vector v, Eigen::Ref H1, Eigen::Ref H2) const; + gtsam::Vector localCoordinates(const gtsam::Pose2& p) const; + gtsam::Vector localCoordinates(const gtsam::Pose2& p, Eigen::Ref H1, Eigen::Ref H2) const; // Lie Group - static gtsam::Pose2 Expmap(Vector v); - static Vector Logmap(const gtsam::Pose2& p); - Vector logmap(const gtsam::Pose2& p); - Vector logmap(const gtsam::Pose2& p, Eigen::Ref H); - static Matrix ExpmapDerivative(Vector v); - static Matrix LogmapDerivative(const gtsam::Pose2& v); - Matrix AdjointMap() const; - Vector Adjoint(Vector xi) const; - static Matrix adjointMap_(Vector v); - static Vector adjoint_(Vector xi, Vector y); - static Vector adjointTranspose(Vector xi, Vector y); - static Matrix wedge(double vx, double vy, double w); + static gtsam::Pose2 Expmap(gtsam::Vector v); + static gtsam::Vector Logmap(const gtsam::Pose2& p); + gtsam::Vector logmap(const gtsam::Pose2& p); + gtsam::Vector logmap(const gtsam::Pose2& p, Eigen::Ref H); + static gtsam::Matrix ExpmapDerivative(gtsam::Vector v); + 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::Vector adjoint_(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Vector adjointTranspose(gtsam::Vector xi, gtsam::Vector y); + static gtsam::Matrix wedge(double vx, double vy, double w); // Group Actions on Point2 gtsam::Point2 transformFrom(const gtsam::Point2& p) const; gtsam::Point2 transformTo(const gtsam::Point2& p) const; - // Matrix versions - Matrix transformFrom(const Matrix& points) const; - Matrix transformTo(const Matrix& points) const; + // gtsam::Matrix versions + gtsam::Matrix transformFrom(const gtsam::Matrix& points) const; + gtsam::Matrix transformTo(const gtsam::Matrix& points) const; // Standard Interface double x() const; @@ -445,7 +445,7 @@ class Pose2 { gtsam::Point2 translation(Eigen::Ref Hself) const; gtsam::Rot2 rotation() const; gtsam::Rot2 rotation(Eigen::Ref Hself) const; - Matrix matrix() const; + gtsam::Matrix matrix() const; // enabling serialization functionality void serialize() const; @@ -458,7 +458,7 @@ class Pose3 { Pose3(const gtsam::Pose3& other); Pose3(const gtsam::Rot3& r, const gtsam::Point3& t); Pose3(const gtsam::Pose2& pose2); - Pose3(Matrix mat); + Pose3(gtsam::Matrix mat); static std::optional Align(const gtsam::Point3Pairs& abPointPairs); static std::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); @@ -488,33 +488,33 @@ class Pose3 { gtsam::Pose3 operator*(const gtsam::Pose3& pose) const; // Manifold - gtsam::Pose3 retract(Vector v) const; - gtsam::Pose3 retract(Vector v, Eigen::Ref Hxi) const; - Vector localCoordinates(const gtsam::Pose3& pose) const; - Vector localCoordinates(const gtsam::Pose3& pose, Eigen::Ref Hxi) const; + gtsam::Pose3 retract(gtsam::Vector v) const; + gtsam::Pose3 retract(gtsam::Vector v, Eigen::Ref Hxi) const; + gtsam::Vector localCoordinates(const gtsam::Pose3& pose) const; + gtsam::Vector localCoordinates(const gtsam::Pose3& pose, Eigen::Ref Hxi) const; // Lie Group - static gtsam::Pose3 Expmap(Vector v); - static gtsam::Pose3 Expmap(Vector v, Eigen::Ref Hxi); - static Vector Logmap(const gtsam::Pose3& pose); - static Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref Hpose); - gtsam::Pose3 expmap(Vector v); - Vector logmap(const gtsam::Pose3& pose); - Matrix AdjointMap() const; - Vector Adjoint(Vector xi) const; - Vector Adjoint(Vector xi, Eigen::Ref H_this, + static gtsam::Pose3 Expmap(gtsam::Vector v); + static gtsam::Pose3 Expmap(gtsam::Vector v, Eigen::Ref Hxi); + static gtsam::Vector Logmap(const gtsam::Pose3& pose); + static gtsam::Vector Logmap(const gtsam::Pose3& pose, Eigen::Ref Hpose); + gtsam::Pose3 expmap(gtsam::Vector v); + gtsam::Vector logmap(const gtsam::Pose3& pose); + gtsam::Matrix AdjointMap() const; + gtsam::Vector Adjoint(gtsam::Vector xi) const; + gtsam::Vector Adjoint(gtsam::Vector xi, Eigen::Ref H_this, Eigen::Ref H_xib) const; - Vector AdjointTranspose(Vector xi) const; - Vector AdjointTranspose(Vector xi, Eigen::Ref H_this, + gtsam::Vector AdjointTranspose(gtsam::Vector xi) const; + gtsam::Vector AdjointTranspose(gtsam::Vector xi, Eigen::Ref H_this, Eigen::Ref H_x) const; - static Matrix adjointMap(Vector xi); - static Vector adjoint(Vector xi, Vector y); - static Matrix adjointMap_(Vector xi); - static Vector adjoint_(Vector xi, Vector y); - static Vector adjointTranspose(Vector xi, Vector y); - static Matrix ExpmapDerivative(Vector xi); - static Matrix LogmapDerivative(const gtsam::Pose3& xi); - static Matrix wedge(double wx, double wy, double wz, double vx, double vy, + static gtsam::Matrix adjointMap(gtsam::Vector xi); + static gtsam::Vector adjoint(gtsam::Vector xi, gtsam::Vector y); + 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 ExpmapDerivative(gtsam::Vector xi); + static gtsam::Matrix LogmapDerivative(const gtsam::Pose3& xi); + static gtsam::Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz); // Group Action on Point3 @@ -525,9 +525,9 @@ class Pose3 { gtsam::Point3 transformTo(const gtsam::Point3& point, Eigen::Ref Hself, Eigen::Ref Hpoint) const; - // Matrix versions - Matrix transformFrom(const Matrix& points) const; - Matrix transformTo(const Matrix& points) const; + // gtsam::Matrix versions + gtsam::Matrix transformFrom(const gtsam::Matrix& points) const; + gtsam::Matrix transformTo(const gtsam::Matrix& points) const; // Standard Interface gtsam::Rot3 rotation() const; @@ -537,7 +537,7 @@ class Pose3 { double x() const; double y() const; double z() const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose) const; gtsam::Pose3 transformPoseFrom(const gtsam::Pose3& pose, Eigen::Ref Hself, Eigen::Ref HaTb) const; @@ -584,9 +584,9 @@ class Unit3 { bool equals(const gtsam::Unit3& pose, double tol) const; // Other functionality - Matrix basis() const; - Matrix basis(Eigen::Ref H) const; - Matrix skew() const; + gtsam::Matrix basis() const; + gtsam::Matrix basis(Eigen::Ref H) const; + gtsam::Matrix skew() const; gtsam::Point3 point3() const; gtsam::Point3 point3(Eigen::Ref H) const; @@ -602,8 +602,8 @@ class Unit3 { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Unit3 retract(Vector v) const; - Vector localCoordinates(const gtsam::Unit3& s) const; + gtsam::Unit3 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Unit3& s) const; gtsam::Unit3 FromPoint3(const gtsam::Point3& point) const; gtsam::Unit3 FromPoint3(const gtsam::Point3& point, Eigen::Ref H) const; @@ -632,14 +632,14 @@ class EssentialMatrix { // Manifold static size_t Dim(); size_t dim() const; - gtsam::EssentialMatrix retract(Vector v) const; - Vector localCoordinates(const gtsam::EssentialMatrix& s) const; + gtsam::EssentialMatrix retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::EssentialMatrix& s) const; // Other methods: gtsam::Rot3 rotation() const; gtsam::Unit3 direction() const; - Matrix matrix() const; - double error(Vector vA, Vector vB); + gtsam::Matrix matrix() const; + double error(gtsam::Vector vA, gtsam::Vector vB); }; #include @@ -647,7 +647,7 @@ class Cal3_S2 { // Standard Constructors Cal3_S2(); Cal3_S2(double fx, double fy, double s, double u0, double v0); - Cal3_S2(Vector v); + Cal3_S2(gtsam::Vector v); Cal3_S2(double fov, int w, int h); // Testable @@ -657,8 +657,8 @@ class Cal3_S2 { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3_S2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3_S2& c) const; + gtsam::Cal3_S2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3_S2& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -677,9 +677,9 @@ class Cal3_S2 { double px() const; double py() const; gtsam::Point2 principalPoint() const; - Vector vector() const; - Matrix K() const; - Matrix inverse() const; + gtsam::Vector vector() const; + gtsam::Matrix K() const; + gtsam::Matrix inverse() const; // enabling serialization functionality void serialize() const; @@ -701,9 +701,9 @@ virtual class Cal3DS2_Base { double py() const; double k1() const; double k2() const; - Matrix K() const; - Vector k() const; - Vector vector() const; + gtsam::Matrix K() const; + gtsam::Vector k() const; + gtsam::Vector vector() const; // Action on Point2 gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; @@ -727,7 +727,7 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { double k2); Cal3DS2(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2); - Cal3DS2(Vector v); + Cal3DS2(gtsam::Vector v); // Testable bool equals(const gtsam::Cal3DS2& rhs, double tol) const; @@ -735,8 +735,8 @@ virtual class Cal3DS2 : gtsam::Cal3DS2_Base { // Manifold size_t dim() const; static size_t Dim(); - gtsam::Cal3DS2 retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3DS2& c) const; + gtsam::Cal3DS2 retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3DS2& c) const; // enabling serialization functionality void serialize() const; @@ -750,7 +750,7 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { double k2); Cal3Unified(double fx, double fy, double s, double u0, double v0, double k1, double k2, double p1, double p2, double xi); - Cal3Unified(Vector v); + Cal3Unified(gtsam::Vector v); // Testable bool equals(const gtsam::Cal3Unified& rhs, double tol) const; @@ -763,8 +763,8 @@ virtual class Cal3Unified : gtsam::Cal3DS2_Base { // Manifold size_t dim() const; static size_t Dim(); - gtsam::Cal3Unified retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Unified& c) const; + gtsam::Cal3Unified retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Unified& c) const; // Action on Point2 // Note: the signature of this functions differ from the functions @@ -788,7 +788,7 @@ class Cal3Fisheye { Cal3Fisheye(); Cal3Fisheye(double fx, double fy, double s, double u0, double v0, double k1, double k2, double k3, double k4, double tol = 1e-5); - Cal3Fisheye(Vector v); + Cal3Fisheye(gtsam::Vector v); // Testable void print(string s = "Cal3Fisheye") const; @@ -797,8 +797,8 @@ class Cal3Fisheye { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3Fisheye retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; + gtsam::Cal3Fisheye retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Fisheye& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -821,10 +821,10 @@ class Cal3Fisheye { double px() const; double py() const; gtsam::Point2 principalPoint() const; - Vector vector() const; - Vector k() const; - Matrix K() const; - Matrix inverse() const; + gtsam::Vector vector() const; + gtsam::Vector k() const; + gtsam::Matrix K() const; + gtsam::Matrix inverse() const; // enabling serialization functionality void serialize() const; @@ -835,13 +835,13 @@ class Cal3_S2Stereo { // Standard Constructors Cal3_S2Stereo(); Cal3_S2Stereo(double fx, double fy, double s, double u0, double v0, double b); - Cal3_S2Stereo(Vector v); + Cal3_S2Stereo(gtsam::Vector v); // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3_S2Stereo retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const; + gtsam::Cal3_S2Stereo retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3_S2Stereo& c) const; // Testable void print(string s = "") const; @@ -853,11 +853,11 @@ class Cal3_S2Stereo { double skew() const; double px() const; double py() const; - Matrix K() const; + gtsam::Matrix K() const; gtsam::Point2 principalPoint() const; double baseline() const; Vector6 vector() const; - Matrix inverse() const; + gtsam::Matrix inverse() const; }; #include @@ -875,8 +875,8 @@ class Cal3Bundler { // Manifold static size_t Dim(); size_t dim() const; - gtsam::Cal3Bundler retract(Vector v) const; - Vector localCoordinates(const gtsam::Cal3Bundler& c) const; + gtsam::Cal3Bundler retract(gtsam::Vector v) const; + gtsam::Vector localCoordinates(const gtsam::Cal3Bundler& c) const; // Action on Point2 gtsam::Point2 calibrate(const gtsam::Point2& p) const; @@ -895,9 +895,9 @@ class Cal3Bundler { double k2() const; double px() const; double py() const; - Vector vector() const; - Vector k() const; - Matrix K() const; + gtsam::Vector vector() const; + gtsam::Vector k() const; + gtsam::Matrix K() const; // enabling serialization functionality void serialize() const; @@ -908,7 +908,7 @@ class CalibratedCamera { // Standard Constructors and Named Constructors CalibratedCamera(); CalibratedCamera(const gtsam::Pose3& pose); - CalibratedCamera(Vector v); + CalibratedCamera(gtsam::Vector v); static gtsam::CalibratedCamera Level(const gtsam::Pose2& pose2, double height); @@ -919,8 +919,8 @@ class CalibratedCamera { // Manifold static size_t Dim(); size_t dim() const; - gtsam::CalibratedCamera retract(Vector d) const; - Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; + gtsam::CalibratedCamera retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const gtsam::CalibratedCamera& T2) const; // Action on Point3 gtsam::Point2 project(const gtsam::Point3& point) const; @@ -972,8 +972,8 @@ class PinholeCamera { CALIBRATION calibration() const; // Manifold - This retract(Vector d) const; - Vector localCoordinates(const This& T2) const; + This retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const This& T2) const; size_t dim() const; static size_t Dim(); @@ -1039,8 +1039,8 @@ class PinholePose { CALIBRATION calibration() const; // Manifold - This retract(Vector d) const; - Vector localCoordinates(const This& T2) const; + This retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const This& T2) const; size_t dim() const; static size_t Dim(); @@ -1081,8 +1081,8 @@ class Similarity2 { Similarity2(); Similarity2(double s); Similarity2(const gtsam::Rot2& R, const gtsam::Point2& t, double s); - Similarity2(const Matrix& R, const Vector& t, double s); - Similarity2(const Matrix& T); + Similarity2(const gtsam::Matrix& R, const gtsam::Vector& t, double s); + Similarity2(const gtsam::Matrix& T); gtsam::Point2 transformFrom(const gtsam::Point2& p) const; gtsam::Pose2 transformFrom(const gtsam::Pose2& T); @@ -1093,7 +1093,7 @@ class Similarity2 { // Standard Interface bool equals(const gtsam::Similarity2& sim, double tol) const; void print(const std::string& s = "") const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Rot2& rotation(); gtsam::Point2& translation(); double scale() const; @@ -1105,8 +1105,8 @@ class Similarity3 { Similarity3(); Similarity3(double s); Similarity3(const gtsam::Rot3& R, const gtsam::Point3& t, double s); - Similarity3(const Matrix& R, const Vector& t, double s); - Similarity3(const Matrix& T); + Similarity3(const gtsam::Matrix& R, const gtsam::Vector& t, double s); + Similarity3(const gtsam::Matrix& T); gtsam::Point3 transformFrom(const gtsam::Point3& p) const; gtsam::Pose3 transformFrom(const gtsam::Pose3& T); @@ -1117,7 +1117,7 @@ class Similarity3 { // Standard Interface bool equals(const gtsam::Similarity3& sim, double tol) const; void print(const std::string& s = "") const; - Matrix matrix() const; + gtsam::Matrix matrix() const; gtsam::Rot3& rotation(); gtsam::Point3& translation(); double scale() const; @@ -1148,8 +1148,8 @@ class StereoCamera { gtsam::Cal3_S2Stereo calibration() const; // Manifold - gtsam::StereoCamera retract(Vector d) const; - Vector localCoordinates(const gtsam::StereoCamera& T2) const; + gtsam::StereoCamera retract(gtsam::Vector d) const; + gtsam::Vector localCoordinates(const gtsam::StereoCamera& T2) const; size_t dim() const; static size_t Dim();