Better way of exporting Boost serialization guid
							parent
							
								
									8b9c199d0b
								
							
						
					
					
						commit
						a500b41473
					
				|  | @ -313,3 +313,6 @@ void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, | ||||||
| } | } | ||||||
|  /// namespace gtsam
 |  /// namespace gtsam
 | ||||||
| 
 | 
 | ||||||
|  | /// Boost serialization export definition for derived class
 | ||||||
|  | BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams); | ||||||
|  | 
 | ||||||
|  |  | ||||||
|  | @ -384,3 +384,5 @@ struct traits<CombinedImuFactor> : public Testable<CombinedImuFactor> {}; | ||||||
| 
 | 
 | ||||||
| }  // namespace gtsam
 | }  // namespace gtsam
 | ||||||
| 
 | 
 | ||||||
|  | /// Add Boost serialization export key (declaration) for derived class
 | ||||||
|  | BOOST_CLASS_EXPORT_KEY(gtsam::PreintegrationCombinedParams); | ||||||
|  |  | ||||||
|  | @ -42,9 +42,6 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, | ||||||
| BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); | BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); | ||||||
| BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); | BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); | ||||||
| 
 | 
 | ||||||
| /// Add Boost serialization export for derived class
 |  | ||||||
| BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); |  | ||||||
| 
 |  | ||||||
| template <typename P> | template <typename P> | ||||||
| P getPreintegratedMeasurements() { | P getPreintegratedMeasurements() { | ||||||
|   // Create default parameters with Z-down and above noise paramaters
 |   // Create default parameters with Z-down and above noise paramaters
 | ||||||
|  |  | ||||||
		Loading…
	
		Reference in New Issue