changes revertted to 502a745
parent
70f59b83bc
commit
87ef601b66
|
@ -57,7 +57,8 @@ 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") % m % N % nm;
|
||||
cout << format("\nTesting with %1% images, %2% points, %3% matches\n")
|
||||
% (int)m % (int)N % (int)nm;
|
||||
cout << "Generating " << nm << " matches" << endl;
|
||||
boost::variate_generator<boost::mt19937, boost::uniform_int<size_t> > rn(
|
||||
boost::mt19937(), boost::uniform_int<size_t>(0, N - 1));
|
||||
|
@ -67,7 +68,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%,") % m % N % nm;
|
||||
os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm;
|
||||
|
||||
{
|
||||
// DSFBase version
|
||||
|
|
|
@ -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<Pose3, Vector3, imuBias::ConstantBias>& factor) {
|
||||
return Vector3::Expmap(factor.evaluateError(p1, v1, b1, p2, v2).tail(3));
|
||||
return factor.evaluateError(p1, v1, b1, p2, v2).tail(3);
|
||||
}
|
||||
|
||||
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||
|
@ -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.compose( dv );
|
||||
Vector3 Vel2 = Vel1 + dv;
|
||||
imuBias::ConstantBias Bias1;
|
||||
|
||||
Values values;
|
||||
|
|
Loading…
Reference in New Issue