fix matlab compile issue, by removing abstract class PreintegrationBase from wrapper declearation
							parent
							
								
									fb0a5489d7
								
							
						
					
					
						commit
						b173057e33
					
				
							
								
								
									
										40
									
								
								gtsam.h
								
								
								
								
							
							
						
						
									
										40
									
								
								gtsam.h
								
								
								
								
							|  | @ -2506,30 +2506,8 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { | |||
|   bool   getUse2ndOrderCoriolis()     const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/navigation/PreintegrationBase.h> | ||||
| virtual class PreintegrationBase { | ||||
|   // Constructors
 | ||||
|   PreintegrationBase(const gtsam::PreintegrationParams* params); | ||||
|   PreintegrationBase(const gtsam::PreintegrationParams* params, | ||||
|       const gtsam::imuBias::ConstantBias& bias); | ||||
| 
 | ||||
|   // Testable
 | ||||
|   void print(string s) const; | ||||
|   bool equals(const gtsam::PreintegrationBase& expected, double tol); | ||||
| 
 | ||||
|   double deltaTij() const; | ||||
|   gtsam::Rot3 deltaRij() const; | ||||
|   Vector deltaPij() const; | ||||
|   Vector deltaVij() const; | ||||
|   Vector biasHatVector() const; | ||||
| 
 | ||||
|   // Standard Interface
 | ||||
|   gtsam::NavState predict(const gtsam::NavState& state_i, | ||||
|       const gtsam::imuBias::ConstantBias& bias) const; | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/navigation/ImuFactor.h> | ||||
| virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase { | ||||
| class PreintegratedImuMeasurements { | ||||
|   // Constructors
 | ||||
|   PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params); | ||||
|   PreintegratedImuMeasurements(const gtsam::PreintegrationParams* params, | ||||
|  | @ -2544,6 +2522,13 @@ virtual class PreintegratedImuMeasurements: gtsam::PreintegrationBase { | |||
|       double deltaT); | ||||
|   void resetIntegration(); | ||||
|   Matrix preintMeasCov() const; | ||||
|   double deltaTij() const; | ||||
|   gtsam::Rot3 deltaRij() const; | ||||
|   Vector deltaPij() const; | ||||
|   Vector deltaVij() const; | ||||
|   Vector biasHatVector() const; | ||||
|   gtsam::NavState predict(const gtsam::NavState& state_i, | ||||
|       const gtsam::imuBias::ConstantBias& bias) const; | ||||
| }; | ||||
| 
 | ||||
| virtual class ImuFactor: gtsam::NonlinearFactor { | ||||
|  | @ -2559,7 +2544,7 @@ virtual class ImuFactor: gtsam::NonlinearFactor { | |||
| }; | ||||
| 
 | ||||
| #include <gtsam/navigation/CombinedImuFactor.h> | ||||
| virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase { | ||||
| class PreintegratedCombinedMeasurements { | ||||
|   // Testable
 | ||||
|   void print(string s) const; | ||||
|   bool equals(const gtsam::PreintegratedCombinedMeasurements& expected, | ||||
|  | @ -2570,6 +2555,13 @@ virtual class PreintegratedCombinedMeasurements: gtsam::PreintegrationBase { | |||
|       double deltaT); | ||||
|   void resetIntegration(); | ||||
|   Matrix preintMeasCov() const; | ||||
|   double deltaTij() const; | ||||
|   gtsam::Rot3 deltaRij() const; | ||||
|   Vector deltaPij() const; | ||||
|   Vector deltaVij() const; | ||||
|   Vector biasHatVector() const; | ||||
|   gtsam::NavState predict(const gtsam::NavState& state_i, | ||||
|       const gtsam::imuBias::ConstantBias& bias) const; | ||||
| }; | ||||
| 
 | ||||
| virtual class CombinedImuFactor: gtsam::NonlinearFactor { | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue