diff --git a/gtsam/navigation/PreintegrationCombinedParams.h b/gtsam/navigation/PreintegrationCombinedParams.h index 2c99463bc..30441ec36 100644 --- a/gtsam/navigation/PreintegrationCombinedParams.h +++ b/gtsam/navigation/PreintegrationCombinedParams.h @@ -59,17 +59,17 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { // Default Params for a Z-down navigation frame, such as NED: gravity points // along positive Z-axis - static boost::shared_ptr MakeSharedD( + static std::shared_ptr MakeSharedD( double g = 9.81) { - return boost::shared_ptr( + return std::shared_ptr( new PreintegrationCombinedParams(Vector3(0, 0, g))); } // Default Params for a Z-up navigation frame, such as ENU: gravity points // along negative Z-axis - static boost::shared_ptr MakeSharedU( + static std::shared_ptr MakeSharedU( double g = 9.81) { - return boost::shared_ptr( + return std::shared_ptr( new PreintegrationCombinedParams(Vector3(0, 0, -g))); } @@ -86,6 +86,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; } private: +#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /** Serialization function */ friend class boost::serialization::access; template @@ -96,6 +97,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance); ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } +#endif public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW