From 8aac62ec1e5533adbc3c094588c4c3a6b8906f1f Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 00:52:55 -0500 Subject: [PATCH 01/14] fix LieVector constructor away from Vector_() --- gtsam/base/LieVector.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/base/LieVector.cpp b/gtsam/base/LieVector.cpp index 17aeff73a..c86b51a24 100644 --- a/gtsam/base/LieVector.cpp +++ b/gtsam/base/LieVector.cpp @@ -24,8 +24,10 @@ namespace gtsam { /* ************************************************************************* */ LieVector::LieVector(size_t m, const double* const data) -: Vector(Vector_(m,data)) +: Vector(m) { + for(size_t i = 0; i < m; i++) + (*this)(i) = data[i]; } /* ************************************************************************* */ From 5e9540470a29bc17771eec6b5e9a207caf8aa9e4 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 01:17:07 -0500 Subject: [PATCH 02/14] modified Vector_() in gtsam/base and gtsam/geometry folders --- gtsam/base/numericalDerivative.h | 2 +- gtsam/base/tests/testLieMatrix.cpp | 2 +- gtsam/base/tests/testLieScalar.cpp | 2 +- gtsam/geometry/Point2.h | 2 +- gtsam/geometry/Pose3.cpp | 2 +- gtsam/geometry/Rot2.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/Sphere2.cpp | 2 +- gtsam/geometry/tests/testCal3DS2.cpp | 2 +- gtsam/geometry/tests/testPoint3.cpp | 2 +- gtsam/geometry/tests/testRot2.cpp | 2 +- gtsam/geometry/tests/testSphere2.cpp | 12 ++++++------ gtsam/geometry/tests/timePose2.cpp | 2 +- gtsam/geometry/tests/timeRot2.cpp | 2 +- gtsam/geometry/tests/timeRot3.cpp | 2 +- 15 files changed, 20 insertions(+), 20 deletions(-) diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index 053a89da8..036f23f68 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -59,7 +59,7 @@ namespace gtsam { /** global functions for converting to a LieVector for use with numericalDerivative */ inline LieVector makeLieVector(const Vector& v) { return LieVector(v); } - inline LieVector makeLieVectorD(double d) { return LieVector(Vector_(1, d)); } + inline LieVector makeLieVectorD(double d) { return LieVector((Vector) (Vector(1) << d)); } /** * Numerically compute gradient of scalar function diff --git a/gtsam/base/tests/testLieMatrix.cpp b/gtsam/base/tests/testLieMatrix.cpp index b21756dc4..88bae697a 100644 --- a/gtsam/base/tests/testLieMatrix.cpp +++ b/gtsam/base/tests/testLieMatrix.cpp @@ -50,7 +50,7 @@ TEST( LieMatrix, other_constructors ) { /* ************************************************************************* */ TEST(LieMatrix, retract) { LieMatrix init(2,2, 1.0,2.0,3.0,4.0); - Vector update = Vector_(4, 3.0, 4.0, 6.0, 7.0); + Vector update = (Vector(4) << 3.0, 4.0, 6.0, 7.0); LieMatrix expected(2,2, 4.0, 6.0, 9.0, 11.0); LieMatrix actual = init.retract(update); diff --git a/gtsam/base/tests/testLieScalar.cpp b/gtsam/base/tests/testLieScalar.cpp index 11157a701..68655cc71 100644 --- a/gtsam/base/tests/testLieScalar.cpp +++ b/gtsam/base/tests/testLieScalar.cpp @@ -42,7 +42,7 @@ TEST( testLieScalar, construction ) { TEST( testLieScalar, localCoordinates ) { LieScalar lie1(1.), lie2(3.); - EXPECT(assert_equal(Vector_(1, 2.), lie1.localCoordinates(lie2))); + EXPECT(assert_equal((Vector)(Vector(1) << 2), lie1.localCoordinates(lie2))); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 0838650ea..dc9a1dac8 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -172,7 +172,7 @@ public: static inline Point2 Expmap(const Vector& v) { return Point2(v); } /// Log map around identity - just return the Point2 as a vector - static inline Vector Logmap(const Point2& dp) { return Vector_(2, dp.x(), dp.y()); } + static inline Vector Logmap(const Point2& dp) { return (Vector(2) << dp.x(), dp.y()); } /// @} /// @name Vector Space diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index adbe763b3..bfd2fcb9a 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -98,7 +98,7 @@ Vector Pose3::adjointTranspose(const Vector& xi, const Vector& y, /* ************************************************************************* */ Matrix6 Pose3::dExpInv_exp(const Vector& xi) { // Bernoulli numbers, from Wikipedia - static const Vector B = Vector_(9, 1.0, -1.0 / 2.0, 1. / 6., 0.0, -1.0 / 30.0, + static const Vector B = (Vector(9) << 1.0, -1.0 / 2.0, 1. / 6., 0.0, -1.0 / 30.0, 0.0, 1.0 / 42.0, 0.0, -1.0 / 30); static const int N = 5; // order of approximation Matrix res = I6; diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 45012770f..d121beb12 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -170,7 +170,7 @@ namespace gtsam { ///Log map at identity - return the canonical coordinates of this rotation static inline Vector Logmap(const Rot2& r) { - return Vector_(1, r.theta()); + return (Vector(1) << r.theta()); } /// @} diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index d302a3502..847d31d65 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -194,7 +194,7 @@ namespace gtsam { * @return incremental rotation matrix */ static Rot3 rodriguez(double wx, double wy, double wz) - { return rodriguez(Vector_(3,wx,wy,wz));} + { return rodriguez((Vector(3) << wx, wy, wz));} /// @} /// @name Testable diff --git a/gtsam/geometry/Sphere2.cpp b/gtsam/geometry/Sphere2.cpp index ce386ac17..3c7765bd2 100644 --- a/gtsam/geometry/Sphere2.cpp +++ b/gtsam/geometry/Sphere2.cpp @@ -170,7 +170,7 @@ Sphere2 Sphere2::retract(const Vector& v, Sphere2::CoordinatesMode mode) const { double alpha = p.transpose() * q; assert(alpha != 0.0); Matrix coeffs = (B.transpose() * q) / alpha; - Vector result = Vector_(2, coeffs(0, 0), coeffs(1, 0)); + Vector result = (Vector(2) << coeffs(0, 0), coeffs(1, 0)); return result; } else { assert (false); diff --git a/gtsam/geometry/tests/testCal3DS2.cpp b/gtsam/geometry/tests/testCal3DS2.cpp index c73ae1182..53a21a9fb 100644 --- a/gtsam/geometry/tests/testCal3DS2.cpp +++ b/gtsam/geometry/tests/testCal3DS2.cpp @@ -36,7 +36,7 @@ TEST( Cal3DS2, uncalibrate) double g = 1+k[0]*r+k[1]*r*r ; double tx = 2*k[2]*p.x()*p.y() + k[3]*(r+2*p.x()*p.x()) ; double ty = k[2]*(r+2*p.y()*p.y()) + 2*k[3]*p.x()*p.y() ; - Vector v_hat = Vector_(3, g*p.x() + tx, g*p.y() + ty, 1.0) ; + Vector v_hat = (Vector(3) << g*p.x() + tx, g*p.y() + ty, 1.0) ; Vector v_i = K.K() * v_hat ; Point2 p_i(v_i(0)/v_i(2), v_i(1)/v_i(2)) ; Point2 q = K.uncalibrate(p); diff --git a/gtsam/geometry/tests/testPoint3.cpp b/gtsam/geometry/tests/testPoint3.cpp index ef4a3894c..5b49c92b2 100644 --- a/gtsam/geometry/tests/testPoint3.cpp +++ b/gtsam/geometry/tests/testPoint3.cpp @@ -40,7 +40,7 @@ TEST(Point3, Lie) { EXPECT(assert_equal(eye(3), H2)); EXPECT(assert_equal(Point3(5,7,9), p1.retract((Vector(3) << 4., 5., 6.)))); - EXPECT(assert_equal(Vector_(3, 3.,3.,3.), p1.localCoordinates(p2))); + EXPECT(assert_equal((Vector)(Vector(3) << 3.,3.,3.), p1.localCoordinates(p2))); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot2.cpp b/gtsam/geometry/tests/testRot2.cpp index 3de661224..c67031a13 100644 --- a/gtsam/geometry/tests/testRot2.cpp +++ b/gtsam/geometry/tests/testRot2.cpp @@ -96,7 +96,7 @@ TEST(Rot2, logmap) { Rot2 rot0(Rot2::fromAngle(M_PI/2.0)); Rot2 rot(Rot2::fromAngle(M_PI)); - Vector expected = Vector_(1, M_PI/2.0); + Vector expected = (Vector(1) << M_PI/2.0); Vector actual = rot0.localCoordinates(rot); CHECK(assert_equal(expected, actual)); } diff --git a/gtsam/geometry/tests/testSphere2.cpp b/gtsam/geometry/tests/testSphere2.cpp index 61dadb8eb..965f5389d 100644 --- a/gtsam/geometry/tests/testSphere2.cpp +++ b/gtsam/geometry/tests/testSphere2.cpp @@ -212,9 +212,9 @@ inline static Vector randomVector(const Vector& minLimits, TEST(Sphere2, localCoordinates_retract) { size_t numIterations = 10000; - Vector minSphereLimit = Vector_(3, -1.0, -1.0, -1.0), maxSphereLimit = - Vector_(3, 1.0, 1.0, 1.0); - Vector minXiLimit = Vector_(2, -1.0, -1.0), maxXiLimit = Vector_(2, 1.0, 1.0); + Vector minSphereLimit = (Vector(3) << -1.0, -1.0, -1.0), maxSphereLimit = + (Vector(3) << 1.0, 1.0, 1.0); + Vector minXiLimit = (Vector(2) << -1.0, -1.0), maxXiLimit = (Vector(2) << 1.0, 1.0); for (size_t i = 0; i < numIterations; i++) { // Sleep for the random number generator (TODO?: Better create all of them first). @@ -242,9 +242,9 @@ TEST(Sphere2, localCoordinates_retract) { TEST(Sphere2, localCoordinates_retract_expmap) { size_t numIterations = 10000; - Vector minSphereLimit = Vector_(3, -1.0, -1.0, -1.0), maxSphereLimit = - Vector_(3, 1.0, 1.0, 1.0); - Vector minXiLimit = Vector_(2, -M_PI, -M_PI), maxXiLimit = Vector_(2, M_PI, M_PI); + Vector minSphereLimit = (Vector(3) << -1.0, -1.0, -1.0), maxSphereLimit = + (Vector(3) << 1.0, 1.0, 1.0); + Vector minXiLimit = (Vector(2) << -M_PI, -M_PI), maxXiLimit = (Vector(2) << M_PI, M_PI); for (size_t i = 0; i < numIterations; i++) { // Sleep for the random number generator (TODO?: Better create all of them first). diff --git a/gtsam/geometry/tests/timePose2.cpp b/gtsam/geometry/tests/timePose2.cpp index a8f2f7137..28044068c 100644 --- a/gtsam/geometry/tests/timePose2.cpp +++ b/gtsam/geometry/tests/timePose2.cpp @@ -138,7 +138,7 @@ int main() // create a random pose: double x = 4.0, y = 2.0, r = 0.3; - Vector v = Vector_(3,x,y,r); + Vector v = (Vector(3) << x, y, r); Pose2 X = Pose2(3,2,0.4), X2 = X.retract(v), X3(5,6,0.3); TEST(Expmap, Pose2::Expmap(v)); diff --git a/gtsam/geometry/tests/timeRot2.cpp b/gtsam/geometry/tests/timeRot2.cpp index 6d828ef9c..86dda2b8c 100644 --- a/gtsam/geometry/tests/timeRot2.cpp +++ b/gtsam/geometry/tests/timeRot2.cpp @@ -95,7 +95,7 @@ int main() // create a random direction: double norm=sqrt(16.0+4.0); double x=4.0/norm, y=2.0/norm; - Vector v = Vector_(2,x,y); + Vector v = (Vector(2) << x, y); Rot2 R = Rot2(0.4), R2 = R.retract(v), R3(0.6); TEST(Rot2_Expmap, Rot2::Expmap(v)); diff --git a/gtsam/geometry/tests/timeRot3.cpp b/gtsam/geometry/tests/timeRot3.cpp index 64feb1909..dd98465ed 100644 --- a/gtsam/geometry/tests/timeRot3.cpp +++ b/gtsam/geometry/tests/timeRot3.cpp @@ -39,7 +39,7 @@ int main() // create a random direction: double norm=sqrt(1.0+16.0+4.0); double x=1.0/norm, y=4.0/norm, z=2.0/norm; - Vector v = Vector_(3,x,y,z); + Vector v = (Vector(3) << x, y, z); Rot3 R = Rot3::rodriguez(0.1, 0.4, 0.2), R2 = R.retract(v); TEST("Rodriguez formula given axis angle", Rot3::rodriguez(v,0.001)) From 90786c0203e8f2325be7c7211c5b95736ec1d8ad Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 01:44:55 -0500 Subject: [PATCH 03/14] fix Vector_() in rest of gtsam folder --- gtsam/linear/tests/testSampler.cpp | 2 +- gtsam/navigation/ImuBias.h | 2 +- gtsam/nonlinear/ISAM2.h | 4 ++-- gtsam/nonlinear/tests/testLinearContainerFactor.cpp | 2 +- gtsam/slam/BearingRangeFactor.h | 2 +- gtsam/slam/RangeFactor.h | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/linear/tests/testSampler.cpp b/gtsam/linear/tests/testSampler.cpp index 1d041d017..9db8b7edc 100644 --- a/gtsam/linear/tests/testSampler.cpp +++ b/gtsam/linear/tests/testSampler.cpp @@ -24,7 +24,7 @@ const double tol = 1e-5; /* ************************************************************************* */ TEST(testSampler, basic) { - Vector sigmas = Vector_(3, 1.0, 0.1, 0.0); + Vector sigmas = (Vector(3) << 1.0, 0.1, 0.0); noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Sigmas(sigmas); char seed = 'A'; Sampler sampler1(model, seed), sampler2(model, 1), sampler3(model, 1); diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index b535f5179..32911e589 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -113,7 +113,7 @@ namespace imuBias { // // return measurement - biasGyro_ - w_earth_rate_I; // -//// Vector bias_gyro_temp(Vector_(3, -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); +//// Vector bias_gyro_temp((Vector(3) << -bias_gyro_(0), bias_gyro_(1), bias_gyro_(2))); //// return measurement - bias_gyro_temp - R_G_to_I * w_earth_rate_G; // } diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index d00be006b..469c78f33 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -122,8 +122,8 @@ struct GTSAM_EXPORT ISAM2Params { * entries would be added with: * \code FastMap thresholds; - thresholds['x'] = Vector_(6, 0.1, 0.1, 0.1, 0.5, 0.5, 0.5); // 0.1 rad rotation threshold, 0.5 m translation threshold - thresholds['l'] = Vector_(3, 1.0, 1.0, 1.0); // 1.0 m landmark position threshold + thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5); // 0.1 rad rotation threshold, 0.5 m translation threshold + thresholds['l'] = (Vector(3) << 1.0, 1.0, 1.0); // 1.0 m landmark position threshold params.relinearizeThreshold = thresholds; \endcode */ diff --git a/gtsam/nonlinear/tests/testLinearContainerFactor.cpp b/gtsam/nonlinear/tests/testLinearContainerFactor.cpp index bf75f134b..fd70519dc 100644 --- a/gtsam/nonlinear/tests/testLinearContainerFactor.cpp +++ b/gtsam/nonlinear/tests/testLinearContainerFactor.cpp @@ -19,7 +19,7 @@ using namespace std; using namespace boost::assign; using namespace gtsam; -const gtsam::noiseModel::Diagonal::shared_ptr diag_model2 = noiseModel::Diagonal::Sigmas(Vector_(2, 1.0, 1.0)); +const gtsam::noiseModel::Diagonal::shared_ptr diag_model2 = noiseModel::Diagonal::Sigmas((Vector(2) << 1.0, 1.0)); const double tol = 1e-5; gtsam::Key l1 = 101, l2 = 102, x1 = 1, x2 = 2; diff --git a/gtsam/slam/BearingRangeFactor.h b/gtsam/slam/BearingRangeFactor.h index 6f00c81a6..cf5760695 100644 --- a/gtsam/slam/BearingRangeFactor.h +++ b/gtsam/slam/BearingRangeFactor.h @@ -96,7 +96,7 @@ namespace gtsam { Vector e1 = Rot::Logmap(measuredBearing_.between(y1)); double y2 = pose.range(point, H21_, H22_); - Vector e2 = Vector_(1, y2 - measuredRange_); + Vector e2 = (Vector(1) << y2 - measuredRange_); if (H1) *H1 = gtsam::stack(2, &H11, &H21); if (H2) *H2 = gtsam::stack(2, &H12, &H22); diff --git a/gtsam/slam/RangeFactor.h b/gtsam/slam/RangeFactor.h index 7b807d88f..fe140a298 100644 --- a/gtsam/slam/RangeFactor.h +++ b/gtsam/slam/RangeFactor.h @@ -73,7 +73,7 @@ namespace gtsam { } else { hx = pose.range(point, H1, H2); } - return Vector_(1, hx - measured_); + return (Vector(1) << hx - measured_); } /** return the measured */ From 8641816b21fd814d1f2f28242e1a32aab1aa9450 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 02:03:12 -0500 Subject: [PATCH 04/14] fix Vector_() in gtsam_unstable and tests --- gtsam_unstable/base/tests/testFixedVector.cpp | 2 +- gtsam_unstable/geometry/BearingS2.cpp | 2 +- gtsam_unstable/geometry/SimPolygon2D.cpp | 2 +- gtsam_unstable/geometry/SimWall2D.cpp | 2 +- gtsam_unstable/geometry/tests/testPose3Upright.cpp | 2 +- gtsam_unstable/slam/BetweenFactorEM.h | 2 +- .../slam/EquivInertialNavFactor_GlobalVel_NoBias.h | 6 +++--- gtsam_unstable/slam/InvDepthFactor3.h | 2 +- gtsam_unstable/slam/InvDepthFactorVariant1.h | 2 +- gtsam_unstable/slam/InvDepthFactorVariant2.h | 2 +- gtsam_unstable/slam/Mechanization_bRn2.h | 2 +- gtsam_unstable/slam/PartialPriorFactor.h | 2 +- gtsam_unstable/slam/RelativeElevationFactor.cpp | 2 +- gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h | 2 +- gtsam_unstable/slam/tests/testAHRS.cpp | 2 +- tests/testGaussianJunctionTreeB.cpp | 2 +- tests/testSimulated2DOriented.cpp | 2 +- 17 files changed, 19 insertions(+), 19 deletions(-) diff --git a/gtsam_unstable/base/tests/testFixedVector.cpp b/gtsam_unstable/base/tests/testFixedVector.cpp index 1fddf80ca..54452e2c4 100644 --- a/gtsam_unstable/base/tests/testFixedVector.cpp +++ b/gtsam_unstable/base/tests/testFixedVector.cpp @@ -28,7 +28,7 @@ static const double tol = 1e-9; /* ************************************************************************* */ TEST( testFixedVector, conversions ) { double data1[] = {1.0, 2.0, 3.0}; - Vector v1 = Vector_(3, data1); + Vector v1 = (Vector(3) << data1[0], data1[1], data1[2]); TestVector3 fv1(v1), fv2(data1); Vector actFv2(fv2); diff --git a/gtsam_unstable/geometry/BearingS2.cpp b/gtsam_unstable/geometry/BearingS2.cpp index df9e14a36..3e1af8eb3 100644 --- a/gtsam_unstable/geometry/BearingS2.cpp +++ b/gtsam_unstable/geometry/BearingS2.cpp @@ -69,7 +69,7 @@ BearingS2 BearingS2::retract(const Vector& v) const { /* ************************************************************************* */ Vector BearingS2::localCoordinates(const BearingS2& x) const { - return Vector_(2, azimuth_.localCoordinates(x.azimuth_)(0), + return (Vector(2) << azimuth_.localCoordinates(x.azimuth_)(0), elevation_.localCoordinates(x.elevation_)(0)); } diff --git a/gtsam_unstable/geometry/SimPolygon2D.cpp b/gtsam_unstable/geometry/SimPolygon2D.cpp index 85b592b98..15fd47236 100644 --- a/gtsam_unstable/geometry/SimPolygon2D.cpp +++ b/gtsam_unstable/geometry/SimPolygon2D.cpp @@ -145,7 +145,7 @@ SimPolygon2D SimPolygon2D::randomTriangle( // extend line by random dist and angle to get BC double dAB = randomDistance(mean_side_len, sigma_side_len, min_side_len); double tABC = randomAngle().theta(); - Pose2 xB = xA.retract(Vector_(3, dAB, 0.0, tABC)); + Pose2 xB = xA.retract((Vector(3) << dAB, 0.0, tABC)); // extend from B to find C double dBC = randomDistance(mean_side_len, sigma_side_len, min_side_len); diff --git a/gtsam_unstable/geometry/SimWall2D.cpp b/gtsam_unstable/geometry/SimWall2D.cpp index 78347a077..894312556 100644 --- a/gtsam_unstable/geometry/SimWall2D.cpp +++ b/gtsam_unstable/geometry/SimWall2D.cpp @@ -128,7 +128,7 @@ std::pair moveWithBounce(const Pose2& cur_pose, double step_size, // calculate angle to change by Rot2 dtheta = Rot2::fromAngle(angle_drift.sample()(0) + bias.theta()); - Pose2 test_pose = cur_pose.retract(Vector_(3, step_size, 0.0, Rot2::Logmap(dtheta)(0))); + Pose2 test_pose = cur_pose.retract((Vector(3) << step_size, 0.0, Rot2::Logmap(dtheta)(0))); // create a segment to use for intersection checking // find the closest intersection diff --git a/gtsam_unstable/geometry/tests/testPose3Upright.cpp b/gtsam_unstable/geometry/tests/testPose3Upright.cpp index 806f7dc16..dacf28992 100644 --- a/gtsam_unstable/geometry/tests/testPose3Upright.cpp +++ b/gtsam_unstable/geometry/tests/testPose3Upright.cpp @@ -72,7 +72,7 @@ TEST( testPose3Upright, manifold ) { EXPECT(assert_equal(x1, x1.retract(zero(4)), tol)); EXPECT(assert_equal(x2, x2.retract(zero(4)), tol)); - Vector delta12 = Vector_(4, 3.0, 0.0, 4.0, 0.0), delta21 = -delta12; + Vector delta12 = (Vector(4) << 3.0, 0.0, 4.0, 0.0), delta21 = -delta12; EXPECT(assert_equal(x2, x1.retract(delta12), tol)); EXPECT(assert_equal(x1, x2.retract(delta21), tol)); diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 8eff62acb..234ad25bc 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -266,7 +266,7 @@ namespace gtsam { } } - return Vector_(2, p_inlier, p_outlier); + return (Vector(2) << p_inlier, p_outlier); } /* ************************************************************************* */ diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h index 5f09ec216..dec1b2378 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel_NoBias.h @@ -537,7 +537,7 @@ public: Rot3 R_ECEF_to_ENU( UEN_to_ENU * C2 * C1 ); - Vector omega_earth_ECEF(Vector_(3, 0.0, 0.0, 7.292115e-5)); + Vector omega_earth_ECEF((Vector(3) << 0.0, 0.0, 7.292115e-5)); omega_earth_ENU = R_ECEF_to_ENU.matrix() * omega_earth_ECEF; // Calculating g @@ -551,7 +551,7 @@ public: double Ro( sqrt(Rp*Rm) ); // mean earth radius of curvature double g0( 9.780318*( 1 + 5.3024e-3 * pow(sin(lat_new),2) - 5.9e-6 * pow(sin(2*lat_new),2) ) ); double g_calc( g0/( pow(1 + height/Ro, 2) ) ); - g_ENU = Vector_(3, 0.0, 0.0, -g_calc); + g_ENU = (Vector(3) << 0.0, 0.0, -g_calc); // Calculate rho @@ -560,7 +560,7 @@ public: double rho_E = -Vn/(Rm + height); double rho_N = Ve/(Rp + height); double rho_U = Ve*tan(lat_new)/(Rp + height); - rho_ENU = Vector_(3, rho_E, rho_N, rho_U); + rho_ENU = (Vector(3) << rho_E, rho_N, rho_U); } static inline noiseModel::Gaussian::shared_ptr calc_descrete_noise_model(const noiseModel::Gaussian::shared_ptr& model, double delta_t){ diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 3cd87b8d2..29f9d4972 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -96,7 +96,7 @@ public: " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl; return gtsam::ones(2) * 2.0 * K_->fx(); } - return gtsam::Vector_(1, 0.0); + return (gtsam::Vector(1) << 0.0); } /** return the measurement */ diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index 5e67a39d3..d61787358 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -96,7 +96,7 @@ public: << std::endl; return gtsam::ones(2) * 2.0 * K_->fx(); } - return gtsam::Vector_(1, 0.0); + return (gtsam::Vector(1) << 0.0); } /// Evaluate error h(x)-z and optionally derivatives diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index 2da440425..9d4113431 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -99,7 +99,7 @@ public: << std::endl; return gtsam::ones(2) * 2.0 * K_->fx(); } - return gtsam::Vector_(1, 0.0); + return (gtsam::Vector(1) << 0.0); } /// Evaluate error h(x)-z and optionally derivatives diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index 711a44bf9..89afad040 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -35,7 +35,7 @@ public: } Vector b_g(double g_e) { - Vector n_g = Vector_(3, 0.0, 0.0, g_e); + Vector n_g = (Vector_(3) << 0.0, 0.0, g_e); return (bRn_ * n_g).vector(); } diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index bf0b2b6e3..1925a3fe4 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -70,7 +70,7 @@ namespace gtsam { /** Single Element Constructor: acts on a single parameter specified by idx */ PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : - Base(model, key), prior_(Vector_(1, prior)), mask_(1, idx), H_(zeros(1, T::Dim())) { + Base(model, key), prior_((Vector(1) << prior)), mask_(1, idx), H_(zeros(1, T::Dim())) { assert(model->dim() == 1); this->fillH(); } diff --git a/gtsam_unstable/slam/RelativeElevationFactor.cpp b/gtsam_unstable/slam/RelativeElevationFactor.cpp index 11d8ed3a3..292e3f68f 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.cpp +++ b/gtsam_unstable/slam/RelativeElevationFactor.cpp @@ -32,7 +32,7 @@ Vector RelativeElevationFactor::evaluateError(const Pose3& pose, const Point3& p *H2 = zeros(1, 3); (*H2)(0, 2) = -1.0; } - return Vector_(1, hx - measured_); + return (Vector(1) << hx - measured_); } /* ************************************************************************* */ diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 5ff8f66e7..0411765e8 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -276,7 +276,7 @@ namespace gtsam { } } - return Vector_(2, p_inlier, p_outlier); + return (Vector(2) << p_inlier, p_outlier); } /* ************************************************************************* */ diff --git a/gtsam_unstable/slam/tests/testAHRS.cpp b/gtsam_unstable/slam/tests/testAHRS.cpp index cc3d693ad..a3c963a58 100644 --- a/gtsam_unstable/slam/tests/testAHRS.cpp +++ b/gtsam_unstable/slam/tests/testAHRS.cpp @@ -75,7 +75,7 @@ TEST (AHRS, Mechanization_integrate) { Mechanization_bRn2 mech; KalmanFilter::State state; // boost::tie(mech,state) = ahrs.initialize(g_e); -// Vector u = Vector_(3,0.05,0.0,0.0); +// Vector u = (Vector(3) << 0.05,0.0,0.0); // double dt = 2; // Rot3 expected; // Mechanization_bRn2 mech2 = mech.integrate(u,dt); diff --git a/tests/testGaussianJunctionTreeB.cpp b/tests/testGaussianJunctionTreeB.cpp index ea34afa79..0b84f137d 100644 --- a/tests/testGaussianJunctionTreeB.cpp +++ b/tests/testGaussianJunctionTreeB.cpp @@ -199,7 +199,7 @@ TEST(GaussianJunctionTreeB, simpleMarginal) { // Create a simple graph NonlinearFactorGraph fg; fg.add(PriorFactor(X(0), Pose2(), noiseModel::Isotropic::Sigma(3, 10.0))); - fg.add(BetweenFactor(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas(Vector_(3, 10.0, 1.0, 1.0)))); + fg.add(BetweenFactor(X(0), X(1), Pose2(1.0, 0.0, 0.0), noiseModel::Diagonal::Sigmas((Vector(3) << 10.0, 1.0, 1.0)))); Values init; init.insert(X(0), Pose2()); diff --git a/tests/testSimulated2DOriented.cpp b/tests/testSimulated2DOriented.cpp index cf505c485..dcc31e0ec 100644 --- a/tests/testSimulated2DOriented.cpp +++ b/tests/testSimulated2DOriented.cpp @@ -58,7 +58,7 @@ TEST( simulated2DOriented, Dprior ) TEST( simulated2DOriented, constructor ) { Pose2 measurement(0.2, 0.3, 0.1); - SharedDiagonal model = noiseModel::Diagonal::Sigmas(Vector_(3, 1., 1., 1.)); + SharedDiagonal model = noiseModel::Diagonal::Sigmas((Vector(3) << 1., 1., 1.)); simulated2DOriented::Odometry factor(measurement, model, X(1), X(2)); simulated2DOriented::Values config; From c4eec5d5497914e8d91f8a741baa431e231189b9 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 02:16:04 -0500 Subject: [PATCH 05/14] fix Vector_() remained --- gtsam/base/tests/testVector.cpp | 3 ++- gtsam_unstable/slam/Mechanization_bRn2.h | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/base/tests/testVector.cpp b/gtsam/base/tests/testVector.cpp index fc2b7a266..7d7fc78bc 100644 --- a/gtsam/base/tests/testVector.cpp +++ b/gtsam/base/tests/testVector.cpp @@ -24,6 +24,7 @@ using namespace std; using namespace gtsam; /* ************************************************************************* */ +/* TEST( TestVector, Vector_variants ) { Vector a = (Vector(2) << 10.0,20.0); @@ -31,7 +32,7 @@ TEST( TestVector, Vector_variants ) Vector b = Vector_(2, data); EXPECT(assert_equal(a, b)); } - +*/ namespace { /* ************************************************************************* */ template diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index 89afad040..747ceafe7 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -35,7 +35,7 @@ public: } Vector b_g(double g_e) { - Vector n_g = (Vector_(3) << 0.0, 0.0, g_e); + Vector n_g = (Vector(3) << 0.0, 0.0, g_e); return (bRn_ * n_g).vector(); } From 97ebfbb1f01f3e4bce81eab54bdd66612da92177 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 02:16:36 -0500 Subject: [PATCH 06/14] fix Vector_() remained --- tests/testBoundingConstraint.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index dd16e6a9e..b85b75d1c 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -187,7 +187,7 @@ TEST( testBoundingConstraint, MaxDistance_basics) { EXPECT(!rangeBound.isGreaterThan()); EXPECT(rangeBound.dim() == 1); - EXPECT(assert_equal(Vector_(1, 2.0), rangeBound.evaluateError(pt1, pt1))); + EXPECT(assert_equal(Vector(1) << 2.0), rangeBound.evaluateError(pt1, pt1))); EXPECT(assert_equal(ones(1), rangeBound.evaluateError(pt1, pt2))); EXPECT(assert_equal(zero(1), rangeBound.evaluateError(pt1, pt3))); EXPECT(assert_equal(-1.0*ones(1), rangeBound.evaluateError(pt1, pt4))); From b36574f77a99ddd3b6ee6c009a4725058a71818b Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 02:51:05 -0500 Subject: [PATCH 07/14] remove all Vector_() definition and declaration --- gtsam/base/Matrix.cpp | 11 ----------- gtsam/base/Matrix.h | 5 ----- gtsam/base/Vector.cpp | 27 --------------------------- gtsam/base/Vector.h | 16 ---------------- tests/testBoundingConstraint.cpp | 2 +- 5 files changed, 1 insertion(+), 60 deletions(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index adf98cf9a..7f44d43db 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -211,17 +211,6 @@ void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, SubVec x += alpha * A.transpose() * e; } -/* ************************************************************************* */ -Vector Vector_(const Matrix& A) -{ - size_t m = A.rows(), n = A.cols(); - Vector v(m*n); - for( size_t j = 0, k=0 ; j < n ; j++) - for( size_t i = 0; i < m ; i++,k++) - v(k) = A(i,j); - return v; -} - /* ************************************************************************* */ void print(const Matrix& A, const string &s, ostream& stream) { size_t m = A.rows(), n = A.cols(); diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 05f3bc7c9..317698b3f 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -196,11 +196,6 @@ inline MATRIX prod(const MATRIX& A, const MATRIX&B) { return result; } -/** - * convert to column vector, column order !!! - */ -GTSAM_EXPORT Vector Vector_(const Matrix& A); - /** * print a matrix */ diff --git a/gtsam/base/Vector.cpp b/gtsam/base/Vector.cpp index 2a0192930..48ada018f 100644 --- a/gtsam/base/Vector.cpp +++ b/gtsam/base/Vector.cpp @@ -79,33 +79,6 @@ void odprintf(const char *format, ...) { //#endif } -/* ************************************************************************* */ -Vector Vector_( size_t m, const double* const data) { - Vector A(m); - copy(data, data+m, A.data()); - return A; -} - -/* ************************************************************************* */ -Vector Vector_(size_t m, ...) { - Vector v(m); - va_list ap; - va_start(ap, m); - for( size_t i = 0 ; i < m ; i++) { - double value = va_arg(ap, double); - v(i) = value; - } - va_end(ap); - return v; -} - -/* ************************************************************************* */ -Vector Vector_(const std::vector& d) { - Vector v(d.size()); - copy(d.begin(), d.end(), v.data()); - return v; -} - /* ************************************************************************* */ bool zero(const Vector& v) { bool result = true; diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index 2c6066042..b35afccdb 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -46,22 +46,6 @@ typedef Eigen::VectorBlock ConstSubVector; */ GTSAM_EXPORT void odprintf(const char *format, ...); -/** - * constructor with size and initial data, row order ! - */ -GTSAM_EXPORT Vector Vector_( size_t m, const double* const data); - -/** - * nice constructor, dangerous as number of arguments must be exactly right - * and you have to pass doubles !!! always use 0.0 never 0 - */ -GTSAM_EXPORT Vector Vector_(size_t m, ...); - -/** - * Create a numeric vector from an STL vector of doubles - */ -GTSAM_EXPORT Vector Vector_(const std::vector& data); - /** * Create vector initialized to a constant value * @param n is the size of the vector diff --git a/tests/testBoundingConstraint.cpp b/tests/testBoundingConstraint.cpp index b85b75d1c..7b5f31660 100644 --- a/tests/testBoundingConstraint.cpp +++ b/tests/testBoundingConstraint.cpp @@ -187,7 +187,7 @@ TEST( testBoundingConstraint, MaxDistance_basics) { EXPECT(!rangeBound.isGreaterThan()); EXPECT(rangeBound.dim() == 1); - EXPECT(assert_equal(Vector(1) << 2.0), rangeBound.evaluateError(pt1, pt1))); + EXPECT(assert_equal(((Vector)Vector(1) << 2.0), rangeBound.evaluateError(pt1, pt1))); EXPECT(assert_equal(ones(1), rangeBound.evaluateError(pt1, pt2))); EXPECT(assert_equal(zero(1), rangeBound.evaluateError(pt1, pt3))); EXPECT(assert_equal(-1.0*ones(1), rangeBound.evaluateError(pt1, pt4))); From afdce9cd80f98aa0d39eaa9ce620e4bbbce7d17d Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 03:03:12 -0500 Subject: [PATCH 08/14] remove all Matrix_() in all folders --- gtsam/geometry/tests/testSphere2.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/tests/testSphere2.cpp b/gtsam/geometry/tests/testSphere2.cpp index 965f5389d..da33478dc 100644 --- a/gtsam/geometry/tests/testSphere2.cpp +++ b/gtsam/geometry/tests/testSphere2.cpp @@ -287,7 +287,7 @@ TEST(Sphere2, localCoordinates_retract_expmap) { // EXPECT(assert_equal(expected,actual1)); // EXPECT(assert_equal(expected,actual2)); // -// Matrix expectedH1 = Matrix_(3,3, +// Matrix expectedH1 = (Matrix(3,3) << // 0.0,-1.0,-2.0, // 1.0, 0.0,-2.0, // 0.0, 0.0,-1.0 @@ -298,7 +298,7 @@ TEST(Sphere2, localCoordinates_retract_expmap) { // // Assert H1 = -AdjointMap(between(p2,p1)) as in doc/math.lyx // EXPECT(assert_equal(-gT2.between(gT1).AdjointMap(),actualH1)); // -// Matrix expectedH2 = Matrix_(3,3, +// Matrix expectedH2 = (Matrix(3,3) << // 1.0, 0.0, 0.0, // 0.0, 1.0, 0.0, // 0.0, 0.0, 1.0 From ad0662a86071cc856ccce29450e50c6226928102 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 03:16:38 -0500 Subject: [PATCH 09/14] now all Matrix_() removed --- gtsam/base/Matrix.cpp | 32 -------------------------------- gtsam/base/Matrix.h | 21 --------------------- 2 files changed, 53 deletions(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 7f44d43db..3b16beb51 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -36,38 +36,6 @@ using namespace std; namespace gtsam { -/* ************************************************************************* */ -Matrix Matrix_( size_t m, size_t n, const double* const data) { - MatrixRowMajor A(m,n); - copy(data, data+m*n, A.data()); - return Matrix(A); -} - -/* ************************************************************************* */ -Matrix Matrix_( size_t m, size_t n, const Vector& v) -{ - Matrix A(m,n); - // column-wise copy - for( size_t j = 0, k=0 ; j < n ; j++) - for( size_t i = 0; i < m ; i++,k++) - A(i,j) = v(k); - return A; -} - -/* ************************************************************************* */ -Matrix Matrix_(size_t m, size_t n, ...) { - Matrix A(m,n); - va_list ap; - va_start(ap, n); - for( size_t i = 0 ; i < m ; i++) - for( size_t j = 0 ; j < n ; j++) { - double value = va_arg(ap, double); - A(i,j) = value; - } - va_end(ap); - return A; -} - /* ************************************************************************* */ Matrix zeros( size_t m, size_t n ) { return Matrix::Zero(m,n); diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 317698b3f..caee66851 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -45,27 +45,6 @@ typedef Eigen::Matrix Matrix6; typedef Eigen::Block SubMatrix; typedef Eigen::Block ConstSubMatrix; -/** - * constructor with size and initial data, row order ! - */ -GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, const double* const data); - -/** - * constructor with size and vector data, column order !!! - */ -GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, const Vector& v); - -/** - * constructor from Vector yielding v.size()*1 vector - */ -inline Matrix Matrix_(const Vector& v) { return Matrix_(v.size(),1,v);} - -/** - * nice constructor, dangerous as number of arguments must be exactly right - * and you have to pass doubles !!! always use 0.0 never 0 -*/ -GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, ...); - // Matlab-like syntax /** From 96296333aeae2e76a95fb9e2c86b78f226fe47a6 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 18:35:29 -0500 Subject: [PATCH 10/14] remove all LieVector(size_t m, ...), which doesn't check parameter's type and it's also dangerous --- gtsam/base/LieVector.cpp | 13 --- gtsam/base/LieVector.h | 3 - gtsam/base/tests/testLieVector.cpp | 5 -- gtsam/base/tests/testNumericalDerivative.cpp | 13 ++- .../tests/testCombinedImuFactor.cpp | 4 +- gtsam/navigation/tests/testImuFactor.cpp | 20 ++--- gtsam/nonlinear/tests/testValues.cpp | 83 ++++++++++--------- gtsam/slam/tests/testGeneralSFMFactor.cpp | 2 +- gtsam_unstable/geometry/InvDepthCamera3.h | 2 +- .../geometry/tests/testInvDepthCamera3.cpp | 18 ++-- .../testInertialNavFactor_GlobalVelocity.cpp | 36 ++++---- .../slam/tests/testInvDepthFactor3.cpp | 2 +- .../slam/tests/testInvDepthFactorVariant1.cpp | 2 +- .../slam/tests/testInvDepthFactorVariant2.cpp | 2 +- .../slam/tests/testInvDepthFactorVariant3.cpp | 2 +- tests/testNonlinearFactor.cpp | 30 +++---- 16 files changed, 114 insertions(+), 123 deletions(-) diff --git a/gtsam/base/LieVector.cpp b/gtsam/base/LieVector.cpp index c86b51a24..f6cae28e2 100644 --- a/gtsam/base/LieVector.cpp +++ b/gtsam/base/LieVector.cpp @@ -30,19 +30,6 @@ LieVector::LieVector(size_t m, const double* const data) (*this)(i) = data[i]; } -/* ************************************************************************* */ -LieVector::LieVector(size_t m, ...) -: Vector(m) -{ - va_list ap; - va_start(ap, m); - for( size_t i = 0 ; i < m ; i++) { - double value = va_arg(ap, double); - (*this)(i) = value; - } - va_end(ap); -} - /* ************************************************************************* */ void LieVector::print(const std::string& name) const { gtsam::print(vector(), name); diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index f1b05b34b..6989bbfd2 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -44,9 +44,6 @@ struct LieVector : public Vector, public DerivedValue { /** constructor with size and initial data, row order ! */ GTSAM_EXPORT LieVector(size_t m, const double* const data); - /** Specify arguments directly, as in Vector_() - always force these to be doubles */ - GTSAM_EXPORT LieVector(size_t m, ...); - /** get the underlying vector */ Vector vector() const { return static_cast(*this); diff --git a/gtsam/base/tests/testLieVector.cpp b/gtsam/base/tests/testLieVector.cpp index 67eed6656..f66678c25 100644 --- a/gtsam/base/tests/testLieVector.cpp +++ b/gtsam/base/tests/testLieVector.cpp @@ -39,14 +39,9 @@ TEST( testLieVector, construction ) { TEST( testLieVector, other_constructors ) { Vector init = (Vector(2) << 10.0, 20.0); LieVector exp(init); - LieVector a(2,10.0,20.0); double data[] = {10,20}; LieVector b(2,data); - LieVector c(2.3), c_exp(LieVector(1, 2.3)); - EXPECT(assert_equal(exp, a)); EXPECT(assert_equal(exp, b)); - EXPECT(assert_equal(b, a)); - EXPECT(assert_equal(c_exp, c)); } /* ************************************************************************* */ diff --git a/gtsam/base/tests/testNumericalDerivative.cpp b/gtsam/base/tests/testNumericalDerivative.cpp index bd3c2c217..f7e4d3baa 100644 --- a/gtsam/base/tests/testNumericalDerivative.cpp +++ b/gtsam/base/tests/testNumericalDerivative.cpp @@ -48,7 +48,8 @@ double f2(const LieVector& x) { /* ************************************************************************* */ TEST(testNumericalDerivative, numericalHessian2) { - LieVector center(2, 0.5, 1.0); + Vector v_center = (Vector(2) << 0.5, 1.0); + LieVector center(v_center); Matrix expected = (Matrix(2,2) << -cos(center(1))*sin(center(0)), -sin(center(1))*cos(center(0)), @@ -67,7 +68,9 @@ double f3(const LieVector& x1, const LieVector& x2) { /* ************************************************************************* */ TEST(testNumericalDerivative, numericalHessian211) { - LieVector center1(1, 1.0), center2(1, 5.0); + Vector v_center1 = (Vector(1) << 1.0); + Vector v_center2 = (Vector(1) << 5.0); + LieVector center1(v_center1), center2(v_center2); Matrix expected11 = (Matrix(1, 1) << -sin(center1(0))*cos(center2(0))); Matrix actual11 = numericalHessian211(f3, center1, center2); @@ -90,7 +93,11 @@ double f4(const LieVector& x, const LieVector& y, const LieVector& z) { /* ************************************************************************* */ TEST(testNumericalDerivative, numericalHessian311) { - LieVector center1(1, 1.0), center2(1, 2.0), center3(1, 3.0); + Vector v_center1 = (Vector(1) << 1.0); + Vector v_center2 = (Vector(1) << 2.0); + Vector v_center3 = (Vector(1) << 3.0); + LieVector center1(v_center1), center2(v_center2), center3(v_center3); + double x = center1(0), y = center2(0), z = center3(0); Matrix expected11 = (Matrix(1, 1) << -sin(x)*cos(y)*z*z); Matrix actual11 = numericalHessian311(f4, center1, center2, center3); diff --git a/gtsam/navigation/tests/testCombinedImuFactor.cpp b/gtsam/navigation/tests/testCombinedImuFactor.cpp index 25a2765eb..2d766dc6a 100644 --- a/gtsam/navigation/tests/testCombinedImuFactor.cpp +++ b/gtsam/navigation/tests/testCombinedImuFactor.cpp @@ -168,9 +168,9 @@ TEST( CombinedImuFactor, ErrorWithBiases ) imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) imuBias::ConstantBias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot) Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI/4.0)), Point3(5.0, 1.0, -50.0)); - LieVector v1(3, 0.5, 0.0, 0.0); + LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI/4.0 + M_PI/10.0)), Point3(5.5, 1.0, -50.0)); - LieVector v2(3, 0.5, 0.0, 0.0); + LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); // Measurements Vector3 gravity; gravity << 0, 0, 9.81; diff --git a/gtsam/navigation/tests/testImuFactor.cpp b/gtsam/navigation/tests/testImuFactor.cpp index 2db7c7c68..cc88505bd 100644 --- a/gtsam/navigation/tests/testImuFactor.cpp +++ b/gtsam/navigation/tests/testImuFactor.cpp @@ -167,9 +167,9 @@ TEST( ImuFactor, Error ) // Linearization point imuBias::ConstantBias bias; // Bias Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, -50.0)); - LieVector v1(3, 0.5, 0.0, 0.0); + LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); Pose3 x2(Rot3::RzRyRx(M_PI/12.0 + M_PI/100.0, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, -50.0)); - LieVector v2(3, 0.5, 0.0, 0.0); + LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); // Measurements Vector3 gravity; gravity << 0, 0, 9.81; @@ -238,16 +238,16 @@ TEST( ImuFactor, ErrorWithBiases ) // Linearization point // Vector bias(6); bias << 0.2, 0, 0, 0.1, 0, 0; // Biases (acc, rot) // Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, -50.0)); -// LieVector v1(3, 0.5, 0.0, 0.0); +// LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); // Pose3 x2(Rot3::RzRyRx(M_PI/12.0 + M_PI/10.0, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, -50.0)); -// LieVector v2(3, 0.5, 0.0, 0.0); +// LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI/4.0)), Point3(5.0, 1.0, -50.0)); - LieVector v1(3, 0.5, 0.0, 0.0); + LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI/4.0 + M_PI/10.0)), Point3(5.5, 1.0, -50.0)); - LieVector v2(3, 0.5, 0.0, 0.0); + LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); // Measurements Vector3 gravity; gravity << 0, 0, 9.81; @@ -445,9 +445,9 @@ TEST( ImuFactor, FirstOrderPreIntegratedMeasurements ) //{ // // Linearization point // Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, -50.0)); -// LieVector v1(3, 0.5, 0.0, 0.0); +// LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); // Pose3 x2(Rot3::RzRyRx(M_PI/12.0 + M_PI/100.0, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, -50.0)); -// LieVector v2(3, 0.5, 0.0, 0.0); +// LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); // imuBias::ConstantBias bias(Vector3(0.001, 0.002, 0.008), Vector3(0.002, 0.004, 0.012)); // // // Pre-integrator @@ -501,9 +501,9 @@ TEST( ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement ) imuBias::ConstantBias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot) Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI/4.0)), Point3(5.0, 1.0, -50.0)); - LieVector v1(3, 0.5, 0.0, 0.0); + LieVector v1((Vector(3) << 0.5, 0.0, 0.0)); Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI/4.0 + M_PI/10.0)), Point3(5.5, 1.0, -50.0)); - LieVector v2(3, 0.5, 0.0, 0.0); + LieVector v2((Vector(3) << 0.5, 0.0, 0.0)); // Measurements Vector3 gravity; gravity << 0, 0, 9.81; diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index ec386950d..041ea0387 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -65,7 +65,8 @@ public: TEST( Values, equals1 ) { Values expected; - LieVector v(3, 5.0, 6.0, 7.0); + LieVector v((Vector(3) << 5.0, 6.0, 7.0)); + expected.insert(key1,v); Values actual; actual.insert(key1,v); @@ -76,8 +77,9 @@ TEST( Values, equals1 ) TEST( Values, equals2 ) { Values cfg1, cfg2; - LieVector v1(3, 5.0, 6.0, 7.0); - LieVector v2(3, 5.0, 6.0, 8.0); + LieVector v1((Vector(3) << 5.0, 6.0, 7.0)); + LieVector v2((Vector(3) << 5.0, 6.0, 8.0)); + cfg1.insert(key1, v1); cfg2.insert(key1, v2); CHECK(!cfg1.equals(cfg2)); @@ -88,8 +90,9 @@ TEST( Values, equals2 ) TEST( Values, equals_nan ) { Values cfg1, cfg2; - LieVector v1(3, 5.0, 6.0, 7.0); - LieVector v2(3, inf, inf, inf); + LieVector v1((Vector(3) << 5.0, 6.0, 7.0)); + LieVector v2((Vector(3) << inf, inf, inf)); + cfg1.insert(key1, v1); cfg2.insert(key1, v2); CHECK(!cfg1.equals(cfg2)); @@ -100,10 +103,11 @@ TEST( Values, equals_nan ) TEST( Values, insert_good ) { Values cfg1, cfg2, expected; - LieVector v1(3, 5.0, 6.0, 7.0); - LieVector v2(3, 8.0, 9.0, 1.0); - LieVector v3(3, 2.0, 4.0, 3.0); - LieVector v4(3, 8.0, 3.0, 7.0); + LieVector v1((Vector(3) << 5.0, 6.0, 7.0)); + LieVector v2((Vector(3) << 8.0, 9.0, 1.0)); + LieVector v3((Vector(3) << 2.0, 4.0, 3.0)); + LieVector v4((Vector(3) << 8.0, 3.0, 7.0)); + cfg1.insert(key1, v1); cfg1.insert(key2, v2); cfg2.insert(key3, v4); @@ -121,10 +125,11 @@ TEST( Values, insert_good ) TEST( Values, insert_bad ) { Values cfg1, cfg2; - LieVector v1(3, 5.0, 6.0, 7.0); - LieVector v2(3, 8.0, 9.0, 1.0); - LieVector v3(3, 2.0, 4.0, 3.0); - LieVector v4(3, 8.0, 3.0, 7.0); + LieVector v1((Vector(3) << 5.0, 6.0, 7.0)); + LieVector v2((Vector(3) << 8.0, 9.0, 1.0)); + LieVector v3((Vector(3) << 2.0, 4.0, 3.0)); + LieVector v4((Vector(3) << 8.0, 3.0, 7.0)); + cfg1.insert(key1, v1); cfg1.insert(key2, v2); cfg2.insert(key2, v3); @@ -137,8 +142,8 @@ TEST( Values, insert_bad ) TEST( Values, update_element ) { Values cfg; - LieVector v1(3, 5.0, 6.0, 7.0); - LieVector v2(3, 8.0, 9.0, 1.0); + LieVector v1((Vector(3) << 5.0, 6.0, 7.0)); + LieVector v2((Vector(3) << 8.0, 9.0, 1.0)); cfg.insert(key1, v1); CHECK(cfg.size() == 1); @@ -181,8 +186,8 @@ TEST(Values, basic_functions) //TEST(Values, dim_zero) //{ // Values config0; -// config0.insert(key1, LieVector(2, 2.0, 3.0)); -// config0.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); +// config0.insert(key1, LieVector((Vector(2) << 2.0, 3.0)); +// config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0)); // LONGS_EQUAL(5, config0.dim()); // // VectorValues expected; @@ -195,16 +200,16 @@ TEST(Values, basic_functions) TEST(Values, expmap_a) { Values config0; - config0.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); - config0.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); + config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); + config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0))); VectorValues increment = pair_list_of (key1, (Vector(3) << 1.0, 1.1, 1.2)) (key2, (Vector(3) << 1.3, 1.4, 1.5)); Values expected; - expected.insert(key1, LieVector(3, 2.0, 3.1, 4.2)); - expected.insert(key2, LieVector(3, 6.3, 7.4, 8.5)); + expected.insert(key1, LieVector((Vector(3) << 2.0, 3.1, 4.2))); + expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5))); CHECK(assert_equal(expected, config0.retract(increment))); } @@ -213,15 +218,15 @@ TEST(Values, expmap_a) TEST(Values, expmap_b) { Values config0; - config0.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); - config0.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); + config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); + config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0))); VectorValues increment = pair_list_of (key2, (Vector(3) << 1.3, 1.4, 1.5)); Values expected; - expected.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); - expected.insert(key2, LieVector(3, 6.3, 7.4, 8.5)); + expected.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); + expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5))); CHECK(assert_equal(expected, config0.retract(increment))); } @@ -230,16 +235,16 @@ TEST(Values, expmap_b) //TEST(Values, expmap_c) //{ // Values config0; -// config0.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); -// config0.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); +// config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); +// config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0))); // // Vector increment = LieVector(6, // 1.0, 1.1, 1.2, // 1.3, 1.4, 1.5); // // Values expected; -// expected.insert(key1, LieVector(3, 2.0, 3.1, 4.2)); -// expected.insert(key2, LieVector(3, 6.3, 7.4, 8.5)); +// expected.insert(key1, LieVector((Vector(3) << 2.0, 3.1, 4.2))); +// expected.insert(key2, LieVector((Vector(3) << 6.3, 7.4, 8.5))); // // CHECK(assert_equal(expected, config0.retract(increment))); //} @@ -248,8 +253,8 @@ TEST(Values, expmap_b) TEST(Values, expmap_d) { Values config0; - config0.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); - config0.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); + config0.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); + config0.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0))); //config0.print("config0"); CHECK(equal(config0, config0)); CHECK(config0.equals(config0)); @@ -266,8 +271,8 @@ TEST(Values, expmap_d) TEST(Values, localCoordinates) { Values valuesA; - valuesA.insert(key1, LieVector(3, 1.0, 2.0, 3.0)); - valuesA.insert(key2, LieVector(3, 5.0, 6.0, 7.0)); + valuesA.insert(key1, LieVector((Vector(3) << 1.0, 2.0, 3.0))); + valuesA.insert(key2, LieVector((Vector(3) << 5.0, 6.0, 7.0))); VectorValues expDelta = pair_list_of (key1, (Vector(3) << 0.1, 0.2, 0.3)) @@ -314,17 +319,17 @@ TEST(Values, exists_) TEST(Values, update) { Values config0; - config0.insert(key1, LieVector(1, 1.)); - config0.insert(key2, LieVector(1, 2.)); + config0.insert(key1, LieVector((Vector(1) << 1.))); + config0.insert(key2, LieVector((Vector(1) << 2.))); Values superset; - superset.insert(key1, LieVector(1, -1.)); - superset.insert(key2, LieVector(1, -2.)); + superset.insert(key1, LieVector((Vector(1) << -1.))); + superset.insert(key2, LieVector((Vector(1) << -2.))); config0.update(superset); Values expected; - expected.insert(key1, LieVector(1, -1.)); - expected.insert(key2, LieVector(1, -2.)); + expected.insert(key1, LieVector((Vector(1) << -1.))); + expected.insert(key2, LieVector((Vector(1) << -2.))); CHECK(assert_equal(expected,config0)); } diff --git a/gtsam/slam/tests/testGeneralSFMFactor.cpp b/gtsam/slam/tests/testGeneralSFMFactor.cpp index b37b36546..a7c91de3f 100644 --- a/gtsam/slam/tests/testGeneralSFMFactor.cpp +++ b/gtsam/slam/tests/testGeneralSFMFactor.cpp @@ -110,7 +110,7 @@ TEST( GeneralSFMFactor, error ) { Pose3 x1(R,t1); values.insert(X(1), GeneralCamera(x1)); Point3 l1; values.insert(L(1), l1); - EXPECT(assert_equal((Vector(2) << -3.0, 0.0), factor->unwhitenedError(values))); + EXPECT(assert_equal(((Vector) (Vector(2) << -3.0, 0.0)), factor->unwhitenedError(values))); } static const double baseline = 5.0 ; diff --git a/gtsam_unstable/geometry/InvDepthCamera3.h b/gtsam_unstable/geometry/InvDepthCamera3.h index c33505c54..4eb7992a2 100644 --- a/gtsam_unstable/geometry/InvDepthCamera3.h +++ b/gtsam_unstable/geometry/InvDepthCamera3.h @@ -166,7 +166,7 @@ public: gtsam::Point3 ray = pw - pt; double theta = atan2(ray.y(), ray.x()); // longitude double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y())); - return std::make_pair(gtsam::LieVector(5, pt.x(),pt.y(),pt.z(), theta, phi), + return std::make_pair(gtsam::LieVector((Vector(5) << pt.x(),pt.y(),pt.z(), theta, phi)), gtsam::LieScalar(1./depth)); } diff --git a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp index e899da0c9..b477d3e44 100644 --- a/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp +++ b/gtsam_unstable/geometry/tests/testInvDepthCamera3.cpp @@ -29,7 +29,7 @@ TEST( InvDepthFactor, Project1) { Point2 expected_uv = level_camera.project(landmark); InvDepthCamera3 inv_camera(level_pose, K); - LieVector inv_landmark(5, 1., 0., 1., 0., 0.); + LieVector inv_landmark((Vector(5) << 1., 0., 1., 0., 0.)); LieScalar inv_depth(1./4); Point2 actual_uv = inv_camera.project(inv_landmark, inv_depth); EXPECT(assert_equal(expected_uv, actual_uv)); @@ -45,7 +45,7 @@ TEST( InvDepthFactor, Project2) { Point2 expected = level_camera.project(landmark); InvDepthCamera3 inv_camera(level_pose, K); - LieVector diag_landmark(5, 0., 0., 1., M_PI/4., atan(1.0/sqrt(2.0))); + LieVector diag_landmark((Vector(5) << 0., 0., 1., M_PI/4., atan(1.0/sqrt(2.0)))); LieScalar inv_depth(1/sqrt(3.0)); Point2 actual = inv_camera.project(diag_landmark, inv_depth); EXPECT(assert_equal(expected, actual)); @@ -60,7 +60,7 @@ TEST( InvDepthFactor, Project3) { Point2 expected = level_camera.project(landmark); InvDepthCamera3 inv_camera(level_pose, K); - LieVector diag_landmark(5, 0., 0., 0., M_PI/4., atan(2./sqrt(2.0))); + LieVector diag_landmark((Vector(5) << 0., 0., 0., M_PI/4., atan(2./sqrt(2.0)))); LieScalar inv_depth( 1./sqrt(1.0+1+4)); Point2 actual = inv_camera.project(diag_landmark, inv_depth); EXPECT(assert_equal(expected, actual)); @@ -75,7 +75,7 @@ TEST( InvDepthFactor, Project4) { Point2 expected = level_camera.project(landmark); InvDepthCamera3 inv_camera(level_pose, K); - LieVector diag_landmark(5, 0., 0., 0., atan(4.0/1), atan(2./sqrt(1.+16.))); + LieVector diag_landmark((Vector(5) << 0., 0., 0., atan(4.0/1), atan(2./sqrt(1.+16.)))); LieScalar inv_depth(1./sqrt(1.+16.+4.)); Point2 actual = inv_camera.project(diag_landmark, inv_depth); EXPECT(assert_equal(expected, actual)); @@ -88,7 +88,7 @@ Point2 project_(const Pose3& pose, const LieVector& landmark, const LieScalar& i TEST( InvDepthFactor, Dproject_pose) { - LieVector landmark(6,0.1,0.2,0.3, 0.1,0.2); + LieVector landmark((Vector(5) << 0.1,0.2,0.3, 0.1,0.2)); LieScalar inv_depth(1./4); Matrix expected = numericalDerivative31(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); @@ -100,7 +100,7 @@ TEST( InvDepthFactor, Dproject_pose) /* ************************************************************************* */ TEST( InvDepthFactor, Dproject_landmark) { - LieVector landmark(5,0.1,0.2,0.3, 0.1,0.2); + LieVector landmark((Vector(5) << 0.1,0.2,0.3, 0.1,0.2)); LieScalar inv_depth(1./4); Matrix expected = numericalDerivative32(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); @@ -112,7 +112,7 @@ TEST( InvDepthFactor, Dproject_landmark) /* ************************************************************************* */ TEST( InvDepthFactor, Dproject_inv_depth) { - LieVector landmark(5,0.1,0.2,0.3, 0.1,0.2); + LieVector landmark((Vector(5) << 0.1,0.2,0.3, 0.1,0.2)); LieScalar inv_depth(1./4); Matrix expected = numericalDerivative33(project_,level_pose, landmark, inv_depth); InvDepthCamera3 inv_camera(level_pose,K); @@ -124,7 +124,7 @@ TEST( InvDepthFactor, Dproject_inv_depth) /* ************************************************************************* */ TEST(InvDepthFactor, backproject) { - LieVector expected(5,0.,0.,1., 0.1,0.2); + LieVector expected((Vector(5) << 0.,0.,1., 0.1,0.2)); LieScalar inv_depth(1./4); InvDepthCamera3 inv_camera(level_pose,K); Point2 z = inv_camera.project(expected, inv_depth); @@ -140,7 +140,7 @@ TEST(InvDepthFactor, backproject) TEST(InvDepthFactor, backproject2) { // backwards facing camera - LieVector expected(5,-5.,-5.,2., 3., -0.1); + LieVector expected((Vector(5) << -5.,-5.,2., 3., -0.1)); LieScalar inv_depth(1./10); InvDepthCamera3 inv_camera(Pose3(Rot3::ypr(1.5,0.1, -1.5), Point3(-5, -5, 2)),K); Point2 z = inv_camera.project(expected, inv_depth); diff --git a/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp b/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp index 53d94a4bc..7756e79d3 100644 --- a/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp +++ b/gtsam_unstable/slam/tests/testInertialNavFactor_GlobalVelocity.cpp @@ -119,10 +119,10 @@ TEST( InertialNavFactor_GlobalVelocity, Predict) InertialNavFactor_GlobalVelocity f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model); Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00)); - LieVector Vel1(3, 0.50, -0.50, 0.40); + LieVector Vel1((Vector(3) << 0.50, -0.50, 0.40)); imuBias::ConstantBias Bias1; Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04)); - LieVector expectedVel2(3, 0.51, -0.48, 0.43); + LieVector expectedVel2((Vector(3) << 0.51, -0.48, 0.43)); Pose3 actualPose2; LieVector actualVel2; f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2); @@ -157,8 +157,8 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorPosVel) Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00)); Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04)); - LieVector Vel1(3, 0.50, -0.50, 0.40); - LieVector Vel2(3, 0.51, -0.48, 0.43); + LieVector Vel1((Vector(3) << 0.50, -0.50, 0.40)); + LieVector Vel2((Vector(3) << 0.51, -0.48, 0.43)); imuBias::ConstantBias Bias1; Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2)); @@ -192,8 +192,8 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorRot) Pose3 Pose1(Rot3(), Point3(2.0,1.0,3.0)); Pose3 Pose2(Rot3::Expmap(measurement_gyro*measurement_dt), Point3(2.0,1.0,3.0)); - LieVector Vel1(3,0.0,0.0,0.0); - LieVector Vel2(3,0.0,0.0,0.0); + LieVector Vel1((Vector(3) << 0.0, 0.0, 0.0)); + LieVector Vel2((Vector(3) << 0.0, 0.0, 0.0)); imuBias::ConstantBias Bias1; Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2)); @@ -230,7 +230,7 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorRotPosVel) -0.652537293, 0.709880342, 0.265075427); Point3 t1(2.0,1.0,3.0); Pose3 Pose1(R1, t1); - LieVector Vel1(3,0.5,-0.5,0.4); + LieVector Vel1((Vector(3) << 0.5, -0.5, 0.4)); Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888, -0.422594037, -0.636011287, 0.731761397, 0.244979388); @@ -302,13 +302,13 @@ TEST (InertialNavFactor_GlobalVelocity, Jacobian ) { -0.652537293, 0.709880342, 0.265075427); Point3 t1(2.0,1.0,3.0); Pose3 Pose1(R1, t1); - LieVector Vel1(3,0.5,-0.5,0.4); + LieVector Vel1((Vector(3) << 0.5, -0.5, 0.4)); Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888, -0.422594037, -0.636011287, 0.731761397, 0.244979388); Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800); Pose3 Pose2(R2, t2); - LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000); + LieVector Vel2((Vector(3) << 0.510000000000000, -0.480000000000000, 0.430000000000000)); imuBias::ConstantBias Bias1; Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual; @@ -447,10 +447,10 @@ TEST( InertialNavFactor_GlobalVelocity, PredictWithTransform) InertialNavFactor_GlobalVelocity f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model, body_P_sensor); Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00)); - LieVector Vel1(3, 0.50, -0.50, 0.40); + LieVector Vel1((Vector(3) << 0.50, -0.50, 0.40)); imuBias::ConstantBias Bias1; Pose3 expectedPose2(Rot3(), Point3(2.05, 0.95, 3.04)); - LieVector expectedVel2(3, 0.51, -0.48, 0.43); + LieVector expectedVel2((Vector(3) << 0.51, -0.48, 0.43)); Pose3 actualPose2; LieVector actualVel2; f.predict(Pose1, Vel1, Bias1, actualPose2, actualVel2); @@ -488,8 +488,8 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorPosVelWithTransform) Pose3 Pose1(Rot3(), Point3(2.00, 1.00, 3.00)); Pose3 Pose2(Rot3(), Point3(2.05, 0.95, 3.04)); - LieVector Vel1(3, 0.50, -0.50, 0.40); - LieVector Vel2(3, 0.51, -0.48, 0.43); + LieVector Vel1((Vector(3) << 0.50, -0.50, 0.40)); + LieVector Vel2((Vector(3) << 0.51, -0.48, 0.43)); imuBias::ConstantBias Bias1; Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2)); @@ -527,8 +527,8 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorRotWithTransform) Pose3 Pose1(Rot3(), Point3(2.0,1.0,3.0)); Pose3 Pose2(Rot3::Expmap(body_P_sensor.rotation().matrix()*measurement_gyro*measurement_dt), Point3(2.0, 1.0, 3.0)); - LieVector Vel1(3,0.0,0.0,0.0); - LieVector Vel2(3,0.0,0.0,0.0); + LieVector Vel1((Vector(3) << 0.0,0.0,0.0)); + LieVector Vel2((Vector(3) << 0.0,0.0,0.0)); imuBias::ConstantBias Bias1; Vector ActualErr(f.evaluateError(Pose1, Vel1, Bias1, Pose2, Vel2)); @@ -569,7 +569,7 @@ TEST( InertialNavFactor_GlobalVelocity, ErrorRotPosVelWithTransform) -0.652537293, 0.709880342, 0.265075427); Point3 t1(2.0,1.0,3.0); Pose3 Pose1(R1, t1); - LieVector Vel1(3,0.5,-0.5,0.4); + LieVector Vel1((Vector(3) << 0.5,-0.5,0.4)); Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888, -0.422594037, -0.636011287, 0.731761397, 0.244979388); @@ -618,13 +618,13 @@ TEST (InertialNavFactor_GlobalVelocity, JacobianWithTransform ) { -0.652537293, 0.709880342, 0.265075427); Point3 t1(2.0,1.0,3.0); Pose3 Pose1(R1, t1); - LieVector Vel1(3,0.5,-0.5,0.4); + LieVector Vel1((Vector(3) << 0.5,-0.5,0.4)); Rot3 R2(0.473618898, 0.119523052, 0.872582019, 0.609241153, 0.67099888, -0.422594037, -0.636011287, 0.731761397, 0.244979388); Point3 t2(2.052670960415706, 0.977252139079380, 2.942482135362800); Pose3 Pose2(R2, t2); - LieVector Vel2(3,0.510000000000000, -0.480000000000000, 0.430000000000000); + LieVector Vel2((Vector(3) << 0.510000000000000, -0.480000000000000, 0.430000000000000)); imuBias::ConstantBias Bias1; Matrix H1_actual, H2_actual, H3_actual, H4_actual, H5_actual; diff --git a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp index 65cc1adbc..5ea9fe29d 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactor3.cpp @@ -38,7 +38,7 @@ TEST( InvDepthFactor, optimize) { Point2 expected_uv = level_camera.project(landmark); InvDepthCamera3 inv_camera(level_pose, K); - LieVector inv_landmark(5, 0., 0., 1., 0., 0.); + LieVector inv_landmark((Vector(5) << 0., 0., 1., 0., 0.)); // initialize inverse depth with "incorrect" depth of 1/4 // in reality this is 1/5, but initial depth is guessed LieScalar inv_depth(1./4); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp index 7bbee65ee..24535854d 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant1.cpp @@ -45,7 +45,7 @@ TEST( InvDepthFactorVariant1, optimize) { double theta = atan2(ray.y(), ray.x()); double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y())); double rho = 1./ray.norm(); - LieVector expected(6, x, y, z, theta, phi, rho); + LieVector expected((Vector(6) << x, y, z, theta, phi, rho)); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp index 1512d0fc2..e99c9bcdf 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant2.cpp @@ -43,7 +43,7 @@ TEST( InvDepthFactorVariant2, optimize) { double theta = atan2(ray.y(), ray.x()); double phi = atan2(ray.z(), sqrt(ray.x()*ray.x()+ray.y()*ray.y())); double rho = 1./ray.norm(); - LieVector expected(3, theta, phi, rho); + LieVector expected((Vector(3) << theta, phi, rho)); diff --git a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp index 799ebdf36..e65b7cacb 100644 --- a/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp +++ b/gtsam_unstable/slam/tests/testInvDepthFactorVariant3.cpp @@ -43,7 +43,7 @@ TEST( InvDepthFactorVariant3, optimize) { double theta = atan2(landmark_p1.x(), landmark_p1.z()); double phi = atan2(landmark_p1.y(), sqrt(landmark_p1.x()*landmark_p1.x()+landmark_p1.z()*landmark_p1.z())); double rho = 1./landmark_p1.norm(); - LieVector expected(3, theta, phi, rho); + LieVector expected((Vector(3) << theta, phi, rho)); diff --git a/tests/testNonlinearFactor.cpp b/tests/testNonlinearFactor.cpp index 247c6a6b0..390257f02 100644 --- a/tests/testNonlinearFactor.cpp +++ b/tests/testNonlinearFactor.cpp @@ -266,10 +266,10 @@ public: TEST(NonlinearFactor, NoiseModelFactor4) { TestFactor4 tf; Values tv; - tv.insert(X(1), LieVector(1, 1.0)); - tv.insert(X(2), LieVector(1, 2.0)); - tv.insert(X(3), LieVector(1, 3.0)); - tv.insert(X(4), LieVector(1, 4.0)); + tv.insert(X(1), LieVector((Vector(1) << 1.0))); + tv.insert(X(2), LieVector((Vector(1) << 2.0))); + tv.insert(X(3), LieVector((Vector(1) << 3.0))); + tv.insert(X(4), LieVector((Vector(1) << 4.0))); EXPECT(assert_equal((Vector(1) << 10.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv))); @@ -312,11 +312,11 @@ public: TEST(NonlinearFactor, NoiseModelFactor5) { TestFactor5 tf; Values tv; - tv.insert(X(1), LieVector(1, 1.0)); - tv.insert(X(2), LieVector(1, 2.0)); - tv.insert(X(3), LieVector(1, 3.0)); - tv.insert(X(4), LieVector(1, 4.0)); - tv.insert(X(5), LieVector(1, 5.0)); + tv.insert(X(1), LieVector((Vector(1) << 1.0))); + tv.insert(X(2), LieVector((Vector(1) << 2.0))); + tv.insert(X(3), LieVector((Vector(1) << 3.0))); + tv.insert(X(4), LieVector((Vector(1) << 4.0))); + tv.insert(X(5), LieVector((Vector(1) << 5.0))); EXPECT(assert_equal((Vector(1) << 15.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(56.25/2.0, tf.error(tv), 1e-9); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv))); @@ -364,12 +364,12 @@ public: TEST(NonlinearFactor, NoiseModelFactor6) { TestFactor6 tf; Values tv; - tv.insert(X(1), LieVector(1, 1.0)); - tv.insert(X(2), LieVector(1, 2.0)); - tv.insert(X(3), LieVector(1, 3.0)); - tv.insert(X(4), LieVector(1, 4.0)); - tv.insert(X(5), LieVector(1, 5.0)); - tv.insert(X(6), LieVector(1, 6.0)); + tv.insert(X(1), LieVector((Vector(1) << 1.0))); + tv.insert(X(2), LieVector((Vector(1) << 2.0))); + tv.insert(X(3), LieVector((Vector(1) << 3.0))); + tv.insert(X(4), LieVector((Vector(1) << 4.0))); + tv.insert(X(5), LieVector((Vector(1) << 5.0))); + tv.insert(X(6), LieVector((Vector(1) << 6.0))); EXPECT(assert_equal((Vector(1) << 21.0), tf.unwhitenedError(tv))); DOUBLES_EQUAL(110.25/2.0, tf.error(tv), 1e-9); JacobianFactor jf(*boost::dynamic_pointer_cast(tf.linearize(tv))); From 8c4aa2b9a6ac63cb91feac5e9c9f580b7204ee3d Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 18:46:01 -0500 Subject: [PATCH 11/14] remove all LieMatrix(sizt_t m, ...), which also has dangerous behavior --- gtsam/base/LieMatrix.cpp | 14 -------------- gtsam/base/LieMatrix.h | 3 --- gtsam/base/tests/testLieMatrix.cpp | 9 +++------ tests/testSerializationSLAM.cpp | 4 ++-- 4 files changed, 5 insertions(+), 25 deletions(-) diff --git a/gtsam/base/LieMatrix.cpp b/gtsam/base/LieMatrix.cpp index 9e88607cc..69054fc1c 100644 --- a/gtsam/base/LieMatrix.cpp +++ b/gtsam/base/LieMatrix.cpp @@ -19,20 +19,6 @@ namespace gtsam { -/* ************************************************************************* */ -LieMatrix::LieMatrix(size_t m, size_t n, ...) -: Matrix(m,n) { - va_list ap; - va_start(ap, n); - for(size_t i = 0; i < m; ++i) { - for(size_t j = 0; j < n; ++j) { - double value = va_arg(ap, double); - (*this)(i,j) = value; - } - } - va_end(ap); -} - /* ************************************************************************* */ void LieMatrix::print(const std::string& name) const { gtsam::print(matrix(), name); diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h index 0a27eff69..8d43dd6ea 100644 --- a/gtsam/base/LieMatrix.h +++ b/gtsam/base/LieMatrix.h @@ -48,9 +48,6 @@ struct LieMatrix : public Matrix, public DerivedValue { LieMatrix(size_t m, size_t n, const double* const data) : Matrix(Eigen::Map(data, m, n)) {} - /** Specify arguments directly, as in Matrix_() - always force these to be doubles */ - GTSAM_EXPORT LieMatrix(size_t m, size_t n, ...); - /// @} /// @name Testable interface /// @{ diff --git a/gtsam/base/tests/testLieMatrix.cpp b/gtsam/base/tests/testLieMatrix.cpp index 88bae697a..ee8fe14d9 100644 --- a/gtsam/base/tests/testLieMatrix.cpp +++ b/gtsam/base/tests/testLieMatrix.cpp @@ -39,20 +39,17 @@ TEST( LieMatrix, construction ) { TEST( LieMatrix, other_constructors ) { Matrix init = (Matrix(2,2) << 10.0,20.0, 30.0,40.0); LieMatrix exp(init); - LieMatrix a(2,2,10.0,20.0,30.0,40.0); double data[] = {10,30,20,40}; LieMatrix b(2,2,data); - EXPECT(assert_equal(exp, a)); EXPECT(assert_equal(exp, b)); - EXPECT(assert_equal(b, a)); } /* ************************************************************************* */ TEST(LieMatrix, retract) { - LieMatrix init(2,2, 1.0,2.0,3.0,4.0); + LieMatrix init((Matrix(2,2) << 1.0,2.0,3.0,4.0)); Vector update = (Vector(4) << 3.0, 4.0, 6.0, 7.0); - LieMatrix expected(2,2, 4.0, 6.0, 9.0, 11.0); + LieMatrix expected((Matrix(2,2) << 4.0, 6.0, 9.0, 11.0)); LieMatrix actual = init.retract(update); EXPECT(assert_equal(expected, actual)); @@ -63,7 +60,7 @@ TEST(LieMatrix, retract) { EXPECT(assert_equal(expectedUpdate, actualUpdate)); Vector expectedLogmap = (Vector(4) << 1, 2, 3, 4); - Vector actualLogmap = LieMatrix::Logmap(LieMatrix(2,2, 1.0, 2.0, 3.0, 4.0)); + Vector actualLogmap = LieMatrix::Logmap(LieMatrix((Matrix(2,2) << 1.0, 2.0, 3.0, 4.0))); EXPECT(assert_equal(expectedLogmap, actualLogmap)); } diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index ecf82d1bd..c9f434da2 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -287,8 +287,8 @@ TEST (testSerializationSLAM, smallExample_nonlinear) { /* ************************************************************************* */ TEST (testSerializationSLAM, factors) { - LieVector lieVector(4, 1.0, 2.0, 3.0, 4.0); - LieMatrix lieMatrix(2, 3, 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0); + LieVector lieVector((Vector(4) << 1.0, 2.0, 3.0, 4.0)); + LieMatrix lieMatrix((Matrix(2, 3) << 1.0, 2.0, 3.0, 4.0, 5.0 ,6.0)); Point2 point2(1.0, 2.0); StereoPoint2 stereoPoint2(1.0, 2.0, 3.0); Point3 point3(1.0, 2.0, 3.0); From 376892f67fb187b2133590b09a8fa4350e3f09ed Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 19:02:24 -0500 Subject: [PATCH 12/14] fix FixVector(size_t m, ...), which also has dangerous behavior --- gtsam_unstable/base/FixedVector.h | 3 ++- gtsam_unstable/base/tests/testFixedVector.cpp | 17 +++++++++-------- 2 files changed, 11 insertions(+), 9 deletions(-) diff --git a/gtsam_unstable/base/FixedVector.h b/gtsam_unstable/base/FixedVector.h index 53a9190ce..6df24fb4f 100644 --- a/gtsam_unstable/base/FixedVector.h +++ b/gtsam_unstable/base/FixedVector.h @@ -52,6 +52,7 @@ public: * NOTE: this will throw warnings/explode if there is no argument * before the variadic section, so there is a meaningless size argument. */ + /* FixedVector(size_t n, ...) { va_list ap; va_start(ap, n); @@ -61,7 +62,7 @@ public: } va_end(ap); } - + */ /** * Create vector initialized to a constant value * @param value constant value diff --git a/gtsam_unstable/base/tests/testFixedVector.cpp b/gtsam_unstable/base/tests/testFixedVector.cpp index 54452e2c4..e5e297b7c 100644 --- a/gtsam_unstable/base/tests/testFixedVector.cpp +++ b/gtsam_unstable/base/tests/testFixedVector.cpp @@ -37,7 +37,7 @@ TEST( testFixedVector, conversions ) { /* ************************************************************************* */ TEST( testFixedVector, variable_constructor ) { - TestVector3 act(3, 1.0, 2.0, 3.0); + TestVector3 act((Vector(3) << 1.0, 2.0, 3.0)); EXPECT_DOUBLES_EQUAL(1.0, act(0), tol); EXPECT_DOUBLES_EQUAL(2.0, act(1), tol); EXPECT_DOUBLES_EQUAL(3.0, act(2), tol); @@ -45,8 +45,9 @@ TEST( testFixedVector, variable_constructor ) { /* ************************************************************************* */ TEST( testFixedVector, equals ) { - TestVector3 vec1(3, 1.0, 2.0, 3.0), vec2(3, 1.0, 2.0, 3.0), vec3(3, 2.0, 3.0, 4.0); - TestVector5 vec4(5, 1.0, 2.0, 3.0, 4.0, 5.0); + TestVector3 vec1((Vector(3) << 1.0, 2.0, 3.0)), vec2((Vector(3) << 1.0, 2.0, 3.0)), + vec3((Vector(3) << 2.0, 3.0, 4.0)); + TestVector5 vec4((Vector(5) << 1.0, 2.0, 3.0, 4.0, 5.0)); EXPECT(assert_equal(vec1, vec1, tol)); EXPECT(assert_equal(vec1, vec2, tol)); @@ -60,23 +61,23 @@ TEST( testFixedVector, equals ) { /* ************************************************************************* */ TEST( testFixedVector, static_constructors ) { TestVector3 actZero = TestVector3::zero(); - TestVector3 expZero(3, 0.0, 0.0, 0.0); + TestVector3 expZero((Vector(3) << 0.0, 0.0, 0.0)); EXPECT(assert_equal(expZero, actZero, tol)); TestVector3 actOnes = TestVector3::ones(); - TestVector3 expOnes(3, 1.0, 1.0, 1.0); + TestVector3 expOnes((Vector(3) << 1.0, 1.0, 1.0)); EXPECT(assert_equal(expOnes, actOnes, tol)); TestVector3 actRepeat = TestVector3::repeat(2.3); - TestVector3 expRepeat(3, 2.3, 2.3, 2.3); + TestVector3 expRepeat((Vector(3) << 2.3, 2.3, 2.3)); EXPECT(assert_equal(expRepeat, actRepeat, tol)); TestVector3 actBasis = TestVector3::basis(1); - TestVector3 expBasis(3, 0.0, 1.0, 0.0); + TestVector3 expBasis((Vector(3) << 0.0, 1.0, 0.0)); EXPECT(assert_equal(expBasis, actBasis, tol)); TestVector3 actDelta = TestVector3::delta(1, 2.3); - TestVector3 expDelta(3, 0.0, 2.3, 0.0); + TestVector3 expDelta((Vector(3) << 0.0, 2.3, 0.0)); EXPECT(assert_equal(expDelta, actDelta, tol)); } From 38846aaac68a1a9f6e3c39553a9af36de97680c8 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 19:08:20 -0500 Subject: [PATCH 13/14] remove FixVector(size_t m, ...) --- gtsam_unstable/base/FixedVector.h | 18 ------------------ 1 file changed, 18 deletions(-) diff --git a/gtsam_unstable/base/FixedVector.h b/gtsam_unstable/base/FixedVector.h index 6df24fb4f..dd3668087 100644 --- a/gtsam_unstable/base/FixedVector.h +++ b/gtsam_unstable/base/FixedVector.h @@ -45,24 +45,6 @@ public: std::copy(values, values+N, this->data()); } - /** - * nice constructor, dangerous as number of arguments must be exactly right - * and you have to pass doubles !!! always use 0.0 never 0 - * - * NOTE: this will throw warnings/explode if there is no argument - * before the variadic section, so there is a meaningless size argument. - */ - /* - FixedVector(size_t n, ...) { - va_list ap; - va_start(ap, n); - for(size_t i = 0 ; i < N ; i++) { - double value = va_arg(ap, double); - (*this)(i) = value; - } - va_end(ap); - } - */ /** * Create vector initialized to a constant value * @param value constant value From 08f048f70e99c538a16abe85e428d52d24fe6059 Mon Sep 17 00:00:00 2001 From: jing Date: Thu, 23 Jan 2014 19:26:22 -0500 Subject: [PATCH 14/14] clean up --- gtsam/base/tests/testMatrix.cpp | 12 ------------ gtsam/base/tests/testVector.cpp | 10 ---------- gtsam/linear/VectorValues.h | 8 ++++---- 3 files changed, 4 insertions(+), 26 deletions(-) diff --git a/gtsam/base/tests/testMatrix.cpp b/gtsam/base/tests/testMatrix.cpp index 34502ba99..828208361 100644 --- a/gtsam/base/tests/testMatrix.cpp +++ b/gtsam/base/tests/testMatrix.cpp @@ -43,18 +43,6 @@ TEST( matrix, constructor_data ) EQUALITY(A,B); } -/* ************************************************************************* */ -/* -TEST( matrix, constructor_vector ) -{ - double data[] = { -5, 3, 0, -5 }; - Matrix A = Matrix_(2, 2, -5, 3, 0, -5); - Vector v(4); - copy(data, data + 4, v.data()); - Matrix B = Matrix_(2, 2, v); // this one is column order ! - EQUALITY(A,trans(B)); -} -*/ /* ************************************************************************* */ TEST( matrix, Matrix_ ) { diff --git a/gtsam/base/tests/testVector.cpp b/gtsam/base/tests/testVector.cpp index 7d7fc78bc..ee0d94366 100644 --- a/gtsam/base/tests/testVector.cpp +++ b/gtsam/base/tests/testVector.cpp @@ -23,16 +23,6 @@ using namespace std; using namespace gtsam; -/* ************************************************************************* */ -/* -TEST( TestVector, Vector_variants ) -{ - Vector a = (Vector(2) << 10.0,20.0); - double data[] = {10,20}; - Vector b = Vector_(2, data); - EXPECT(assert_equal(a, b)); -} -*/ namespace { /* ************************************************************************* */ template diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index a2f078ee2..502d9314b 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -49,15 +49,15 @@ namespace gtsam { * Example: * \code VectorValues values; - values.insert(3, Vector_(3, 1.0, 2.0, 3.0)); - values.insert(4, Vector_(2, 4.0, 5.0)); - values.insert(0, Vector_(4, 6.0, 7.0, 8.0, 9.0)); + values.insert(3, (Vector(3) << 1.0, 2.0, 3.0)); + values.insert(4, (Vector(2) << 4.0, 5.0)); + values.insert(0, (Vector(4) << 6.0, 7.0, 8.0, 9.0)); // Prints [ 3.0 4.0 ] gtsam::print(values[1]); // Prints [ 8.0 9.0 ] - values[1] = Vector_(2, 8.0, 9.0); + values[1] = (Vector(2) << 8.0, 9.0); gtsam::print(values[1]); \endcode *