From c4f3a48bc9c88fda78dad4a074f534a169c9f20d Mon Sep 17 00:00:00 2001 From: Zhaoyang Lv Date: Thu, 13 Nov 2014 21:07:27 -0500 Subject: [PATCH] Revert "Fixed remaining compile issues in "make timing"" This reverts commit 502a7459f9299fd8290058dcd944cde1163b8cc9. --- gtsam_unstable/timing/timeDSFvariants.cpp | 6 ++---- .../timing/timeInertialNavFactor_GlobalVelocity.cpp | 4 ++-- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/gtsam_unstable/timing/timeDSFvariants.cpp b/gtsam_unstable/timing/timeDSFvariants.cpp index 0deb31bef..134c318cb 100644 --- a/gtsam_unstable/timing/timeDSFvariants.cpp +++ b/gtsam_unstable/timing/timeDSFvariants.cpp @@ -57,9 +57,7 @@ int main(int argc, char* argv[]) { volatile double fpm = 0.5; // fraction of points matched volatile size_t nm = fpm * n * np; // number of matches - cout - << format("\nTesting with %1% images, %2% points, %3% matches\n") - % (int)m % (int)N % (int)nm; + cout << format("\nTesting with %1% images, %2% points, %3% matches\n") % m % N % nm; cout << "Generating " << nm << " matches" << endl; boost::variate_generator > rn( boost::mt19937(), boost::uniform_int(0, N - 1)); @@ -69,7 +67,7 @@ int main(int argc, char* argv[]) { for (size_t k = 0; k < nm; k++) matches.push_back(Match(rn(), rn())); - os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm; + os << format("%1%,%2%,%3%,") % m % N % nm; { // DSFBase version diff --git a/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp b/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp index dabf283c6..bd191d887 100644 --- a/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp +++ b/gtsam_unstable/timing/timeInertialNavFactor_GlobalVelocity.cpp @@ -40,7 +40,7 @@ gtsam::Pose3 predictionErrorPose(const Pose3& p1, const Vector3& v1, const imuBi } gtsam::Vector3 predictionErrorVel(const Pose3& p1, const Vector3& v1, const imuBias::ConstantBias& b1, const Pose3& p2, const Vector3& v2, const InertialNavFactor_GlobalVelocity& factor) { - return factor.evaluateError(p1, v1, b1, p2, v2).tail(3); + return Vector3::Expmap(factor.evaluateError(p1, v1, b1, p2, v2).tail(3)); } #include @@ -78,7 +78,7 @@ int main() { Point3 t2 = t1.compose( Point3(Vel1*measurement_dt) ); Pose3 Pose2(R2, t2); Vector dv = measurement_dt * (R1.matrix() * measurement_acc + world_g); - Vector3 Vel2 = Vel1 + dv; + Vector3 Vel2 = Vel1.compose( dv ); imuBias::ConstantBias Bias1; Values values;