diff --git a/gtsam/base/ConcurrentMap.h b/gtsam/base/ConcurrentMap.h index 03687f5624..8ce44dda39 100644 --- a/gtsam/base/ConcurrentMap.h +++ b/gtsam/base/ConcurrentMap.h @@ -85,6 +85,8 @@ class ConcurrentMap : public ConcurrentMapBase { /** Copy constructor from the base map class */ ConcurrentMap(const Base& x) : Base(x) {} + ConcurrentMap& operator=(const ConcurrentMap& other) = default; + /** Handy 'exists' function */ bool exists(const KEY& e) const { return this->count(e); } diff --git a/gtsam/base/FastList.h b/gtsam/base/FastList.h index 1a3b9ed3fe..821575ca93 100644 --- a/gtsam/base/FastList.h +++ b/gtsam/base/FastList.h @@ -62,6 +62,8 @@ class FastList: public std::list l) : Base(l) {} + FastList& operator=(const FastList& other) = default; + #ifdef GTSAM_ALLOCATOR_BOOSTPOOL /** Copy constructor from a standard STL container */ FastList(const std::list& x) { diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 75998fd2fa..30052908d6 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -54,6 +54,8 @@ class FastMap : public std::map, /** Copy constructor from another FastMap */ FastMap(const FastMap& x) : Base(x) {} + FastMap& operator=(const FastMap& x) = default; + /** Copy constructor from the base map class */ FastMap(const Base& x) : Base(x) {} diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index 9a2f624974..1a2627e247 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -80,6 +80,8 @@ class FastSet: public std::set, Base(x) { } + FastSet& operator=(const FastSet& other) = default; + #ifdef GTSAM_ALLOCATOR_BOOSTPOOL /** Copy constructor from a standard STL container */ FastSet(const std::set& x) { diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 62ea8ec39f..396ca16ba7 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -56,9 +56,10 @@ class GenericValue: public Value { GenericValue(){} /// Construct from value - GenericValue(const T& value) : - value_(value) { - } + GenericValue(const T& value) : Value(), + value_(value) {} + + GenericValue(const GenericValue& other) = default; /// Return a constant value const T& value() const { @@ -112,7 +113,7 @@ class GenericValue: public Value { * Clone this value (normal clone on the heap, delete with 'delete' operator) */ std::shared_ptr clone() const override { - return std::allocate_shared(Eigen::aligned_allocator(), *this); + return std::allocate_shared(Eigen::aligned_allocator(), *this); } /// Generic Value interface version of retract diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 09a3f4878a..e80b9d4a4d 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -38,6 +38,9 @@ namespace gtsam { */ class GTSAM_EXPORT Value { public: + // todo - not sure if valid + Value() = default; + Value(const Value& other) = default; /** Clone this value in a special memory pool, must be deleted with Value::deallocate_, *not* with the 'delete' operator. */ virtual Value* clone_() const = 0; diff --git a/gtsam/discrete/SignatureParser.cpp b/gtsam/discrete/SignatureParser.cpp index 31e4253925..8e0221f015 100644 --- a/gtsam/discrete/SignatureParser.cpp +++ b/gtsam/discrete/SignatureParser.cpp @@ -38,7 +38,7 @@ std::optional static ParseConditional(const std::string& token) { } catch (...) { return std::nullopt; } - return std::move(row); + return row; } std::optional static ParseConditionalTable( @@ -62,7 +62,7 @@ std::optional
static ParseConditionalTable( } } } - return std::move(table); + return table; } std::vector static Tokenize(const std::string& str) { diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 3f85a7f42e..da7bc922e8 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -60,7 +60,10 @@ class GTSAM_EXPORT Pose2: public LieGroup { } /** copy constructor */ - Pose2(const Pose2& pose) : r_(pose.r_), t_(pose.t_) {} + Pose2(const Pose2& pose) = default; + // : r_(pose.r_), t_(pose.t_) {} + + Pose2& operator=(const Pose2& other) = default; /** * construct from (x,y,theta) diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 5805ce41b1..54bdd7f4c4 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -55,9 +55,10 @@ class GTSAM_EXPORT Pose3: public LieGroup { Pose3() : R_(traits::Identity()), t_(traits::Identity()) {} /** Copy constructor */ - Pose3(const Pose3& pose) : - R_(pose.R_), t_(pose.t_) { - } + Pose3(const Pose3& pose) = default; + // : + // R_(pose.R_), t_(pose.t_) { + // } /** Construct from R,t */ Pose3(const Rot3& R, const Point3& t) : diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 07f328b96d..7a6f25c4d0 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -52,11 +52,14 @@ namespace gtsam { Rot2() : c_(1.0), s_(0.0) {} /** copy constructor */ - Rot2(const Rot2& r) : Rot2(r.c_, r.s_) {} + Rot2(const Rot2& r) = default; + // : Rot2(r.c_, r.s_) {} /// Constructor from angle in radians == exponential map at identity Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {} + // Rot2& operator=(const gtsam::Rot2& other) = default; + /// Named constructor from angle in radians static Rot2 fromAngle(double theta) { return Rot2(theta); diff --git a/gtsam/linear/ConjugateGradientSolver.h b/gtsam/linear/ConjugateGradientSolver.h index 46d49ca4fc..aaec039e96 100644 --- a/gtsam/linear/ConjugateGradientSolver.h +++ b/gtsam/linear/ConjugateGradientSolver.h @@ -69,6 +69,8 @@ struct GTSAM_EXPORT ConjugateGradientParameters epsilon_abs(p.epsilon_abs), blas_kernel(GTSAM) {} + ConjugateGradientParameters& operator=(const ConjugateGradientParameters& other) = default; + #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43 inline size_t getMinIterations() const { return minIterations; } inline size_t getMaxIterations() const { return maxIterations; } diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index 4e8ef804c0..1172dc2813 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -379,7 +379,7 @@ GaussianFactor::shared_ptr HessianFactor::negate() const { shared_ptr result = std::make_shared(*this); // Negate the information matrix of the result result->info_.negate(); - return std::move(result); + return result; } /* ************************************************************************* */ diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 4a5b6d5d1e..a9933374f2 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -117,6 +117,8 @@ namespace gtsam { /** Conversion from HessianFactor (does Cholesky to obtain Jacobian matrix) */ explicit JacobianFactor(const HessianFactor& hf); + JacobianFactor& operator=(const JacobianFactor& jf) = default; + /** default constructor for I/O */ JacobianFactor(); diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 39666b46bc..2f693bbc41 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -64,7 +64,7 @@ std::optional checkIfDiagonal(const Matrix& M) { Vector diagonal(n); for (j = 0; j < n; j++) diagonal(j) = M(j, j); - return std::move(diagonal); + return diagonal; } } diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index e60209a832..4728706c50 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -119,6 +119,8 @@ namespace gtsam { /// Constructor from Vector, with Scatter VectorValues(const Vector& c, const Scatter& scatter); + VectorValues& operator=(const VectorValues& other) = default; + /** Create a VectorValues with the same structure as \c other, but filled with zeros. */ static VectorValues Zero(const VectorValues& other); diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 4f6648849b..df89f5b44c 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -149,7 +149,7 @@ class ExpressionFactor : public NoiseModelFactor { noiseModel_->WhitenSystem(Ab.matrix(), b); } - return std::move(factor); + return factor; } /// @return a deep copy of this factor diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index e70f64d969..982430d81e 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -61,7 +61,7 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit) { return noiseModel::Robust::Create( noiseModel::mEstimator::Huber::Create(1.345), isoModel); } else { - return std::move(isoModel); + return isoModel; } } diff --git a/gtsam_unstable/geometry/Pose3Upright.h b/gtsam_unstable/geometry/Pose3Upright.h index 20e0fde5db..464f46928a 100644 --- a/gtsam_unstable/geometry/Pose3Upright.h +++ b/gtsam_unstable/geometry/Pose3Upright.h @@ -43,6 +43,7 @@ class GTSAM_UNSTABLE_EXPORT Pose3Upright { Pose3Upright(const Rot2& bearing, const Point3& t); Pose3Upright(double x, double y, double z, double theta); Pose3Upright(const Pose2& pose, double z); + Pose3Upright& operator=(const Pose3Upright& x) = default; /// Down-converts from a full Pose3 Pose3Upright(const Pose3& fullpose); diff --git a/gtsam_unstable/slam/Mechanization_bRn2.h b/gtsam_unstable/slam/Mechanization_bRn2.h index 4714f2b6f1..3d91f6b0ea 100644 --- a/gtsam_unstable/slam/Mechanization_bRn2.h +++ b/gtsam_unstable/slam/Mechanization_bRn2.h @@ -35,9 +35,7 @@ class GTSAM_UNSTABLE_EXPORT Mechanization_bRn2 { } /// Copy constructor - Mechanization_bRn2(const Mechanization_bRn2& other) : - bRn_(other.bRn_), x_g_(other.x_g_), x_a_(other.x_a_) { - } + Mechanization_bRn2(const Mechanization_bRn2& other) = default; /// gravity in the body frame Vector3 b_g(double g_e) const {