fixed use of 2nd order integration in matlab wrapper
							parent
							
								
									a0a955e5a5
								
							
						
					
					
						commit
						26c296603f
					
				
							
								
								
									
										3
									
								
								gtsam.h
								
								
								
								
							
							
						
						
									
										3
									
								
								gtsam.h
								
								
								
								
							| 
						 | 
				
			
			@ -2286,7 +2286,8 @@ virtual class ConstantBias : gtsam::Value {
 | 
			
		|||
#include <gtsam/navigation/ImuFactor.h>
 | 
			
		||||
class ImuFactorPreintegratedMeasurements {
 | 
			
		||||
  // Standard Constructor
 | 
			
		||||
  ImuFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance, Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance);
 | 
			
		||||
  ImuFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance, bool use2ndOrderIntegration);
 | 
			
		||||
  ImuFactorPreintegratedMeasurements(const gtsam::imuBias::ConstantBias& bias, Matrix measuredAccCovariance,Matrix measuredOmegaCovariance, Matrix integrationErrorCovariance);
 | 
			
		||||
  ImuFactorPreintegratedMeasurements(const gtsam::ImuFactorPreintegratedMeasurements& rhs);
 | 
			
		||||
 | 
			
		||||
  // Testable
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -59,12 +59,14 @@ for i=0:length(measurements)
 | 
			
		|||
      currentBiasKey = symbol('b', i); % not used if includeIMUFactors is false
 | 
			
		||||
      
 | 
			
		||||
      if options.imuFactorType == 1
 | 
			
		||||
        use2ndOrderIntegration = true;
 | 
			
		||||
        % Initialize preintegration
 | 
			
		||||
        imuMeasurement = gtsam.ImuFactorPreintegratedMeasurements(...
 | 
			
		||||
          metadata.imu.zeroBias, ...
 | 
			
		||||
          metadata.imu.AccelerometerSigma.^2 * eye(3), ...
 | 
			
		||||
          metadata.imu.GyroscopeSigma.^2 * eye(3), ...
 | 
			
		||||
          metadata.imu.IntegrationSigma.^2 * eye(3));
 | 
			
		||||
          metadata.imu.IntegrationSigma.^2 * eye(3), ...
 | 
			
		||||
          use2ndOrderIntegration);
 | 
			
		||||
        % Generate IMU measurements with noise
 | 
			
		||||
        for j=1:length(measurements(i).imu) % all measurements to preintegrate
 | 
			
		||||
          imuAccel = measurements(i).imu(j).accel ...
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -9,7 +9,7 @@ import gtsam.*;
 | 
			
		|||
 | 
			
		||||
values = Values;
 | 
			
		||||
 | 
			
		||||
warning('fake angles! TODO: use constructor from roll-pitch-yaw when using real data - using identity rotation')
 | 
			
		||||
warning('fake angles! TODO: use constructor from roll-pitch-yaw when using real data - currently using identity rotation')
 | 
			
		||||
 | 
			
		||||
if options.useRealData == 1
 | 
			
		||||
  %% Create a ground truth trajectory from Real data (if available)
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue