From aa093a35da0c8cdbd9950c6da95c8e309cbb16bd Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Sat, 22 Nov 2014 16:35:27 -0800 Subject: [PATCH] Updated all comma initializer usages to use .finished() --- .cproject | 18 +- examples/CameraResectioning.cpp | 2 +- examples/LocalizationExample.cpp | 8 +- examples/OdometryExample.cpp | 4 +- examples/PlanarSLAMExample.cpp | 6 +- examples/Pose2SLAMExample.cpp | 4 +- examples/Pose2SLAMExample_g2o.cpp | 2 +- examples/Pose2SLAMExample_graph.cpp | 4 +- examples/Pose2SLAMExample_graphviz.cpp | 4 +- examples/Pose2SLAMExample_lago.cpp | 2 +- examples/Pose2SLAMwSPCG.cpp | 6 +- examples/Pose3SLAMExample_g2o.cpp | 2 +- ...ose3SLAMExample_initializePose3Chordal.cpp | 2 +- ...se3SLAMExample_initializePose3Gradient.cpp | 2 +- examples/SFMExample.cpp | 2 +- examples/SFMExample_SmartFactor.cpp | 2 +- examples/SelfCalibrationExample.cpp | 4 +- examples/VisualISAM2Example.cpp | 2 +- examples/VisualISAMExample.cpp | 2 +- examples/easyPoint2KalmanFilter.cpp | 8 +- gtsam/base/LieScalar.h | 4 +- gtsam/base/LieVector.h | 2 +- gtsam/base/tests/testCholesky.cpp | 6 +- gtsam/base/tests/testLieMatrix.cpp | 14 +- gtsam/base/tests/testLieScalar.cpp | 2 +- gtsam/base/tests/testLieVector.cpp | 4 +- gtsam/base/tests/testMatrix.cpp | 240 +++++++++--------- gtsam/base/tests/testNumericalDerivative.cpp | 20 +- gtsam/base/tests/testSerializationBase.cpp | 18 +- gtsam/base/tests/testSymmetricBlockMatrix.cpp | 22 +- gtsam/base/tests/testVector.cpp | 62 ++--- gtsam/base/tests/testVerticalBlockMatrix.cpp | 2 +- .../discrete/tests/testDiscreteMarginals.cpp | 4 +- gtsam/geometry/Cal3Bundler.cpp | 6 +- gtsam/geometry/Cal3DS2_Base.cpp | 4 +- gtsam/geometry/Cal3Unified.cpp | 4 +- gtsam/geometry/Cal3_S2.h | 4 +- gtsam/geometry/CalibratedCamera.cpp | 6 +- gtsam/geometry/EssentialMatrix.cpp | 4 +- gtsam/geometry/EssentialMatrix.h | 2 +- gtsam/geometry/Point2.h | 2 +- gtsam/geometry/Pose2.cpp | 22 +- gtsam/geometry/Pose2.h | 2 +- gtsam/geometry/Pose3.cpp | 4 +- gtsam/geometry/Pose3.h | 4 +- gtsam/geometry/Rot2.cpp | 12 +- gtsam/geometry/Rot2.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/StereoCamera.cpp | 6 +- gtsam/geometry/Unit3.cpp | 4 +- gtsam/geometry/tests/testCal3DS2.cpp | 2 +- gtsam/geometry/tests/testCalibratedCamera.cpp | 2 +- gtsam/geometry/tests/testEssentialMatrix.cpp | 10 +- gtsam/geometry/tests/testPinholeCamera.cpp | 2 +- gtsam/geometry/tests/testPoint2.cpp | 6 +- gtsam/geometry/tests/testPoint3.cpp | 4 +- gtsam/geometry/tests/testPose2.cpp | 50 ++-- gtsam/geometry/tests/testPose3.cpp | 20 +- gtsam/geometry/tests/testRot2.cpp | 2 +- gtsam/geometry/tests/testRot3.cpp | 48 ++-- gtsam/geometry/tests/testRot3M.cpp | 4 +- gtsam/geometry/tests/testSimpleCamera.cpp | 4 +- gtsam/geometry/tests/testStereoCamera.cpp | 2 +- gtsam/geometry/tests/testStereoPoint2.cpp | 4 +- gtsam/geometry/tests/testUnit3.cpp | 28 +- gtsam/linear/VectorValues.h | 8 +- gtsam/linear/tests/testErrors.cpp | 4 +- gtsam/linear/tests/testGaussianBayesNet.cpp | 68 ++--- gtsam/linear/tests/testGaussianBayesTree.cpp | 108 ++++---- .../linear/tests/testGaussianConditional.cpp | 44 ++-- gtsam/linear/tests/testGaussianDensity.cpp | 4 +- .../linear/tests/testGaussianFactorGraph.cpp | 90 +++---- gtsam/linear/tests/testHessianFactor.cpp | 144 +++++------ gtsam/linear/tests/testJacobianFactor.cpp | 72 +++--- gtsam/linear/tests/testKalmanFilter.cpp | 34 +-- gtsam/linear/tests/testNoiseModel.cpp | 68 ++--- gtsam/linear/tests/testSampler.cpp | 2 +- .../linear/tests/testSerializationLinear.cpp | 34 +-- gtsam/linear/tests/testVectorValues.cpp | 78 +++--- gtsam/navigation/tests/testImuBias.cpp | 4 +- gtsam/navigation/tests/testImuFactor.cpp | 20 +- gtsam/nonlinear/ISAM2.h | 4 +- gtsam/nonlinear/WhiteNoiseFactor.h | 12 +- .../tests/testLinearContainerFactor.cpp | 56 ++-- gtsam/nonlinear/tests/testValues.cpp | 12 +- gtsam/slam/BearingRangeFactor.h | 2 +- gtsam/slam/BoundingConstraint.h | 8 +- gtsam/slam/InitializePose3.cpp | 4 +- gtsam/slam/RangeFactor.h | 2 +- gtsam/slam/RotateFactor.h | 2 +- gtsam/slam/dataset.cpp | 2 +- gtsam/slam/lago.cpp | 18 +- gtsam/slam/tests/testDataset.cpp | 8 +- .../slam/tests/testEssentialMatrixFactor.cpp | 6 +- gtsam/slam/tests/testGeneralSFMFactor.cpp | 6 +- .../testGeneralSFMFactor_Cal3Bundler.cpp | 6 +- gtsam/slam/tests/testInitializePose3.cpp | 20 +- gtsam/slam/tests/testLago.cpp | 56 ++-- gtsam/slam/tests/testPoseRotationPrior.cpp | 14 +- gtsam/slam/tests/testPoseTranslationPrior.cpp | 12 +- gtsam/slam/tests/testProjectionFactor.cpp | 12 +- gtsam/slam/tests/testRangeFactor.cpp | 8 +- .../tests/testRegularImplicitSchurFactor.cpp | 2 +- gtsam/slam/tests/testRotateFactor.cpp | 16 +- gtsam/slam/tests/testStereoFactor.cpp | 14 +- gtsam_unstable/base/tests/testFixedVector.cpp | 20 +- gtsam_unstable/dynamics/IMUFactor.h | 2 +- gtsam_unstable/dynamics/Pendulum.h | 8 +- gtsam_unstable/dynamics/PoseRTV.cpp | 14 +- gtsam_unstable/dynamics/SimpleHelicopter.h | 2 +- gtsam_unstable/dynamics/VelocityConstraint3.h | 2 +- .../dynamics/tests/testIMUSystem.cpp | 12 +- gtsam_unstable/dynamics/tests/testPoseRTV.cpp | 10 +- .../dynamics/tests/testSimpleHelicopter.cpp | 16 +- .../dynamics/tests/testVelocityConstraint.cpp | 4 +- .../examples/ConcurrentCalibration.cpp | 2 +- ...ConcurrentFilteringAndSmoothingExample.cpp | 16 +- .../examples/FixedLagSmootherExample.cpp | 6 +- .../examples/Pose2SLAMExampleExpressions.cpp | 4 +- .../examples/SFMExampleExpressions.cpp | 2 +- gtsam_unstable/geometry/BearingS2.cpp | 4 +- gtsam_unstable/geometry/InvDepthCamera3.h | 6 +- gtsam_unstable/geometry/SimPolygon2D.cpp | 2 +- gtsam_unstable/geometry/SimWall2D.cpp | 2 +- .../geometry/tests/testInvDepthCamera3.cpp | 18 +- .../geometry/tests/testPose3Upright.cpp | 2 +- .../tests/testBatchFixedLagSmoother.cpp | 4 +- .../tests/testConcurrentBatchFilter.cpp | 8 +- .../tests/testConcurrentBatchSmoother.cpp | 8 +- .../tests/testConcurrentIncrementalFilter.cpp | 10 +- .../testConcurrentIncrementalSmootherDL.cpp | 8 +- .../testConcurrentIncrementalSmootherGN.cpp | 8 +- .../nonlinear/tests/testExpressionFactor.cpp | 4 +- .../tests/testIncrementalFixedLagSmoother.cpp | 4 +- .../nonlinear/tests/testParticleFactor.cpp | 4 +- gtsam_unstable/slam/AHRS.cpp | 12 +- gtsam_unstable/slam/BetweenFactorEM.h | 2 +- .../slam/EquivInertialNavFactor_GlobalVel.h | 10 +- .../EquivInertialNavFactor_GlobalVel_NoBias.h | 4 +- .../slam/InertialNavFactor_GlobalVelocity.h | 10 +- gtsam_unstable/slam/InvDepthFactor3.h | 2 +- gtsam_unstable/slam/InvDepthFactorVariant1.h | 2 +- gtsam_unstable/slam/InvDepthFactorVariant2.h | 2 +- gtsam_unstable/slam/InvDepthFactorVariant3.h | 4 +- gtsam_unstable/slam/Mechanization_bRn2.cpp | 8 +- gtsam_unstable/slam/Mechanization_bRn2.h | 2 +- gtsam_unstable/slam/PartialPriorFactor.h | 2 +- .../slam/RelativeElevationFactor.cpp | 2 +- .../slam/TransformBtwRobotsUnaryFactorEM.h | 2 +- gtsam_unstable/slam/tests/testAHRS.cpp | 14 +- .../slam/tests/testBetweenFactorEM.cpp | 16 +- .../slam/tests/testBiasedGPSFactor.cpp | 4 +- .../testEquivInertialNavFactor_GlobalVel.cpp | 6 +- .../tests/testGaussMarkov1stOrderFactor.cpp | 14 +- .../testInertialNavFactor_GlobalVelocity.cpp | 86 +++---- .../slam/tests/testInvDepthFactor3.cpp | 2 +- .../slam/tests/testInvDepthFactorVariant1.cpp | 8 +- .../slam/tests/testInvDepthFactorVariant2.cpp | 8 +- .../slam/tests/testInvDepthFactorVariant3.cpp | 8 +- .../slam/tests/testMultiProjectionFactor.cpp | 12 +- .../slam/tests/testProjectionFactorPPP.cpp | 12 +- .../slam/tests/testProjectionFactorPPPC.cpp | 12 +- .../tests/testRelativeElevationFactor.cpp | 10 +- .../slam/tests/testSmartRangeFactor.cpp | 14 +- .../testTransformBtwRobotsUnaryFactor.cpp | 14 +- .../testTransformBtwRobotsUnaryFactorEM.cpp | 24 +- .../timeInertialNavFactor_GlobalVelocity.cpp | 8 +- tests/smallExample.h | 44 ++-- tests/testBoundingConstraint.cpp | 6 +- tests/testDoglegOptimizer.cpp | 44 ++-- tests/testExtendedKalmanFilter.cpp | 14 +- tests/testGaussianBayesTreeB.cpp | 18 +- tests/testGaussianFactorGraphB.cpp | 40 +-- tests/testGaussianISAM2.cpp | 12 +- tests/testGaussianJunctionTreeB.cpp | 4 +- tests/testGradientDescentOptimizer.cpp | 6 +- tests/testGraph.cpp | 2 +- tests/testIterative.cpp | 6 +- tests/testMarginals.cpp | 6 +- tests/testNonlinearEquality.cpp | 16 +- tests/testNonlinearFactor.cpp | 80 +++--- tests/testNonlinearISAM.cpp | 10 +- tests/testPCGSolver.cpp | 10 +- tests/testPreconditioner.cpp | 6 +- tests/testSerializationSLAM.cpp | 4 +- tests/testSimulated2DOriented.cpp | 2 +- tests/testSubgraphPreconditioner.cpp | 28 +- timing/timeCalibratedCamera.cpp | 2 +- timing/timeMatrix.cpp | 2 +- timing/timePinholeCamera.cpp | 2 +- timing/timePose3.cpp | 2 +- timing/timeStereoCamera.cpp | 2 +- 192 files changed, 1381 insertions(+), 1383 deletions(-) diff --git a/.cproject b/.cproject index 52c627f5c..21e171942 100644 --- a/.cproject +++ b/.cproject @@ -1,19 +1,17 @@ - - - + - - + + @@ -21,7 +19,7 @@ - +