Split timing benchmark that had appeared inside a test to a separate timing script
							parent
							
								
									43ebc2c55e
								
							
						
					
					
						commit
						b0c25f2668
					
				| 
						 | 
				
			
			@ -19,3 +19,8 @@ set (navigation_excluded_tests "")
 | 
			
		|||
if (GTSAM_BUILD_TESTS)
 | 
			
		||||
	gtsam_add_subdir_tests(navigation "${navigation_local_libs}" "${gtsam-default}" "${navigation_excluded_tests}") 
 | 
			
		||||
endif()
 | 
			
		||||
 | 
			
		||||
# Build timing scripts
 | 
			
		||||
if (GTSAM_BUILD_TIMING)
 | 
			
		||||
    gtsam_add_subdir_timing(navigation "${navigation_local_libs}" "${gtsam-default}" "${navigation_excluded_files}") 
 | 
			
		||||
endif(GTSAM_BUILD_TIMING)
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -677,74 +677,6 @@ TEST (InertialNavFactor_GlobalVelocity, JacobianWithTransform ) {
 | 
			
		|||
  CHECK( gtsam::assert_equal(H5_expectedVel, H5_actualVel, 1e-5));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
#include <gtsam/linear/GaussianFactorGraph.h>
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
TEST( InertialNavFactor_GlobalVelocity, LinearizeTiming)
 | 
			
		||||
{
 | 
			
		||||
  gtsam::Key PoseKey1(11);
 | 
			
		||||
  gtsam::Key PoseKey2(12);
 | 
			
		||||
  gtsam::Key VelKey1(21);
 | 
			
		||||
  gtsam::Key VelKey2(22);
 | 
			
		||||
  gtsam::Key BiasKey1(31);
 | 
			
		||||
 | 
			
		||||
  double measurement_dt(0.1);
 | 
			
		||||
  Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
 | 
			
		||||
  Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
 | 
			
		||||
  gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
 | 
			
		||||
  gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
 | 
			
		||||
 | 
			
		||||
  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
 | 
			
		||||
 | 
			
		||||
  // Second test: zero angular motion, some acceleration - generated in matlab
 | 
			
		||||
  Vector measurement_acc(Vector_(3, 6.501390843381716,  -6.763926150509185,  -2.300389940090343));
 | 
			
		||||
  Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
 | 
			
		||||
 | 
			
		||||
  InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
 | 
			
		||||
 | 
			
		||||
  Rot3 R1(0.487316618,   0.125253866,   0.86419557,
 | 
			
		||||
       0.580273724,  0.693095498, -0.427669306,
 | 
			
		||||
      -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);
 | 
			
		||||
  Rot3 R2(0.473618898,   0.119523052,  0.872582019,
 | 
			
		||||
       0.609241153,   0.67099888, -0.422594037,
 | 
			
		||||
      -0.636011287,  0.731761397,  0.244979388);
 | 
			
		||||
  Point3 t2 = t1.compose( Point3(Vel1*measurement_dt) );
 | 
			
		||||
  Pose3 Pose2(R2, t2);
 | 
			
		||||
  Vector dv = measurement_dt * (R1.matrix() * measurement_acc + world_g);
 | 
			
		||||
  LieVector Vel2 = Vel1.compose( dv );
 | 
			
		||||
  imuBias::ConstantBias Bias1;
 | 
			
		||||
 | 
			
		||||
  Values values;
 | 
			
		||||
  values.insert(PoseKey1, Pose1);
 | 
			
		||||
  values.insert(PoseKey2, Pose2);
 | 
			
		||||
  values.insert(VelKey1,  Vel1);
 | 
			
		||||
  values.insert(VelKey2,  Vel2);
 | 
			
		||||
  values.insert(BiasKey1, Bias1);
 | 
			
		||||
 | 
			
		||||
  Ordering ordering;
 | 
			
		||||
  ordering.push_back(PoseKey1);
 | 
			
		||||
  ordering.push_back(VelKey1);
 | 
			
		||||
  ordering.push_back(BiasKey1);
 | 
			
		||||
  ordering.push_back(PoseKey2);
 | 
			
		||||
  ordering.push_back(VelKey2);
 | 
			
		||||
 | 
			
		||||
  GaussianFactorGraph graph;
 | 
			
		||||
  gttic_(LinearizeTiming);
 | 
			
		||||
  for(size_t i = 0; i < 100000; ++i) {
 | 
			
		||||
    GaussianFactor::shared_ptr g = f.linearize(values, ordering);
 | 
			
		||||
    graph.push_back(g);
 | 
			
		||||
  }
 | 
			
		||||
  gttoc_(LinearizeTiming);
 | 
			
		||||
  tictoc_finishedIteration_();
 | 
			
		||||
  tictoc_print_();
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
	int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -0,0 +1,110 @@
 | 
			
		|||
/* ----------------------------------------------------------------------------
 | 
			
		||||
 | 
			
		||||
 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
 | 
			
		||||
 * Atlanta, Georgia 30332-0415
 | 
			
		||||
 * All Rights Reserved
 | 
			
		||||
 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
 | 
			
		||||
 | 
			
		||||
 * See LICENSE for the license information
 | 
			
		||||
 | 
			
		||||
 * -------------------------------------------------------------------------- */
 | 
			
		||||
 | 
			
		||||
/**
 | 
			
		||||
 * @file    testInertialNavFactor_GlobalVelocity.cpp
 | 
			
		||||
 * @brief   Unit test for the InertialNavFactor_GlobalVelocity
 | 
			
		||||
 * @author  Vadim Indelman, Stephen Williams
 | 
			
		||||
 */
 | 
			
		||||
 | 
			
		||||
#include <iostream>
 | 
			
		||||
#include <gtsam/navigation/ImuBias.h>
 | 
			
		||||
#include <gtsam/navigation/InertialNavFactor_GlobalVelocity.h>
 | 
			
		||||
#include <gtsam/geometry/Pose3.h>
 | 
			
		||||
#include <gtsam/nonlinear/Values.h>
 | 
			
		||||
#include <gtsam/nonlinear/Key.h>
 | 
			
		||||
#include <gtsam/base/numericalDerivative.h>
 | 
			
		||||
#include <gtsam/base/LieVector.h>
 | 
			
		||||
 | 
			
		||||
using namespace std;
 | 
			
		||||
using namespace gtsam;
 | 
			
		||||
 | 
			
		||||
gtsam::Rot3 world_R_ECEF(
 | 
			
		||||
		0.31686,      0.51505,      0.79645,
 | 
			
		||||
		0.85173,     -0.52399,            0,
 | 
			
		||||
		0.41733,      0.67835,     -0.60471);
 | 
			
		||||
 | 
			
		||||
gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
 | 
			
		||||
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
gtsam::Pose3 predictionErrorPose(const Pose3& p1, const LieVector& v1, const imuBias::ConstantBias& b1, const Pose3& p2, const LieVector& v2, const InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias>& factor) {
 | 
			
		||||
  return Pose3::Expmap(factor.evaluateError(p1, v1, b1, p2, v2).head(6));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
gtsam::LieVector predictionErrorVel(const Pose3& p1, const LieVector& v1, const imuBias::ConstantBias& b1, const Pose3& p2, const LieVector& v2, const InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias>& factor) {
 | 
			
		||||
  return LieVector::Expmap(factor.evaluateError(p1, v1, b1, p2, v2).tail(3));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
#include <gtsam/linear/GaussianFactorGraph.h>
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
int main() {
 | 
			
		||||
  gtsam::Key PoseKey1(11);
 | 
			
		||||
  gtsam::Key PoseKey2(12);
 | 
			
		||||
  gtsam::Key VelKey1(21);
 | 
			
		||||
  gtsam::Key VelKey2(22);
 | 
			
		||||
  gtsam::Key BiasKey1(31);
 | 
			
		||||
 | 
			
		||||
  double measurement_dt(0.1);
 | 
			
		||||
  Vector world_g(Vector_(3, 0.0, 0.0, 9.81));
 | 
			
		||||
  Vector world_rho(Vector_(3, 0.0, -1.5724e-05, 0.0)); // NED system
 | 
			
		||||
  gtsam::Vector ECEF_omega_earth(Vector_(3, 0.0, 0.0, 7.292115e-5));
 | 
			
		||||
  gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
 | 
			
		||||
 | 
			
		||||
  SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
 | 
			
		||||
 | 
			
		||||
  // Second test: zero angular motion, some acceleration - generated in matlab
 | 
			
		||||
  Vector measurement_acc(Vector_(3, 6.501390843381716,  -6.763926150509185,  -2.300389940090343));
 | 
			
		||||
  Vector measurement_gyro(Vector_(3, 0.1, 0.2, 0.3));
 | 
			
		||||
 | 
			
		||||
  InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
 | 
			
		||||
 | 
			
		||||
  Rot3 R1(0.487316618,   0.125253866,   0.86419557,
 | 
			
		||||
       0.580273724,  0.693095498, -0.427669306,
 | 
			
		||||
      -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);
 | 
			
		||||
  Rot3 R2(0.473618898,   0.119523052,  0.872582019,
 | 
			
		||||
       0.609241153,   0.67099888, -0.422594037,
 | 
			
		||||
      -0.636011287,  0.731761397,  0.244979388);
 | 
			
		||||
  Point3 t2 = t1.compose( Point3(Vel1*measurement_dt) );
 | 
			
		||||
  Pose3 Pose2(R2, t2);
 | 
			
		||||
  Vector dv = measurement_dt * (R1.matrix() * measurement_acc + world_g);
 | 
			
		||||
  LieVector Vel2 = Vel1.compose( dv );
 | 
			
		||||
  imuBias::ConstantBias Bias1;
 | 
			
		||||
 | 
			
		||||
  Values values;
 | 
			
		||||
  values.insert(PoseKey1, Pose1);
 | 
			
		||||
  values.insert(PoseKey2, Pose2);
 | 
			
		||||
  values.insert(VelKey1,  Vel1);
 | 
			
		||||
  values.insert(VelKey2,  Vel2);
 | 
			
		||||
  values.insert(BiasKey1, Bias1);
 | 
			
		||||
 | 
			
		||||
  Ordering ordering;
 | 
			
		||||
  ordering.push_back(PoseKey1);
 | 
			
		||||
  ordering.push_back(VelKey1);
 | 
			
		||||
  ordering.push_back(BiasKey1);
 | 
			
		||||
  ordering.push_back(PoseKey2);
 | 
			
		||||
  ordering.push_back(VelKey2);
 | 
			
		||||
 | 
			
		||||
  GaussianFactorGraph graph;
 | 
			
		||||
  gttic_(LinearizeTiming);
 | 
			
		||||
  for(size_t i = 0; i < 100000; ++i) {
 | 
			
		||||
    GaussianFactor::shared_ptr g = f.linearize(values, ordering);
 | 
			
		||||
    graph.push_back(g);
 | 
			
		||||
  }
 | 
			
		||||
  gttoc_(LinearizeTiming);
 | 
			
		||||
  tictoc_finishedIteration_();
 | 
			
		||||
  tictoc_print_();
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
		Loading…
	
		Reference in New Issue