diff --git a/gtsam/linear/Sampler.cpp b/gtsam/linear/Sampler.cpp index ed204fcac..fc58b2ba2 100644 --- a/gtsam/linear/Sampler.cpp +++ b/gtsam/linear/Sampler.cpp @@ -20,16 +20,16 @@ namespace gtsam { /* ************************************************************************* */ -Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model, int32_t seed) - : model_(model), generator_(static_cast(seed)) {} +Sampler::Sampler(const noiseModel::Diagonal::shared_ptr& model, + uint_fast64_t seed) + : model_(model), generator_(seed) {} /* ************************************************************************* */ -Sampler::Sampler(const Vector& sigmas, int32_t seed) - : model_(noiseModel::Diagonal::Sigmas(sigmas, true)), - generator_(static_cast(seed)) {} +Sampler::Sampler(const Vector& sigmas, uint_fast64_t seed) + : model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(seed) {} /* ************************************************************************* */ -Sampler::Sampler(int32_t seed) : generator_(static_cast(seed)) {} +Sampler::Sampler(uint_fast64_t seed) : generator_(seed) {} /* ************************************************************************* */ Vector Sampler::sampleDiagonal(const Vector& sigmas) const { diff --git a/gtsam/linear/Sampler.h b/gtsam/linear/Sampler.h index a52cde330..54c240a2b 100644 --- a/gtsam/linear/Sampler.h +++ b/gtsam/linear/Sampler.h @@ -49,7 +49,7 @@ class GTSAM_EXPORT Sampler { * NOTE: do not use zero as a seed, it will break the generator */ explicit Sampler(const noiseModel::Diagonal::shared_ptr& model, - int32_t seed = 42u); + uint_fast64_t seed = 42u); /** * Create a sampler for a distribution specified by a vector of sigmas @@ -57,7 +57,7 @@ class GTSAM_EXPORT Sampler { * * NOTE: do not use zero as a seed, it will break the generator */ - explicit Sampler(const Vector& sigmas, int32_t seed = 42u); + explicit Sampler(const Vector& sigmas, uint_fast64_t seed = 42u); /// @} /// @name access functions @@ -87,7 +87,7 @@ class GTSAM_EXPORT Sampler { #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @name Deprecated /// @{ - explicit Sampler(int32_t seed = 42u); + explicit Sampler(uint_fast64_t seed = 42u); Vector sampleNewModel(const noiseModel::Diagonal::shared_ptr& model) const; /// @} #endif