Skip to content

Commit

Permalink
Merge pull request #1950 from mcm001/deprecated-copy-redundant-move
Browse files Browse the repository at this point in the history
Fix deprecated copies and redundant moves
  • Loading branch information
dellaert authored Jan 2, 2025
2 parents 6c516cc + 846c29f commit c2a1242
Show file tree
Hide file tree
Showing 19 changed files with 42 additions and 18 deletions.
2 changes: 2 additions & 0 deletions gtsam/base/ConcurrentMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,8 @@ class ConcurrentMap : public ConcurrentMapBase<KEY,VALUE> {
/** 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); }

Expand Down
2 changes: 2 additions & 0 deletions gtsam/base/FastList.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,8 @@ class FastList: public std::list<VALUE, typename internal::FastDefaultAllocator<
/// Construct from c++11 initializer list:
FastList(std::initializer_list<VALUE> l) : Base(l) {}

FastList& operator=(const FastList& other) = default;

#ifdef GTSAM_ALLOCATOR_BOOSTPOOL
/** Copy constructor from a standard STL container */
FastList(const std::list<VALUE>& x) {
Expand Down
2 changes: 2 additions & 0 deletions gtsam/base/FastMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class FastMap : public std::map<KEY, VALUE, std::less<KEY>,
/** Copy constructor from another FastMap */
FastMap(const FastMap<KEY,VALUE>& x) : Base(x) {}

FastMap& operator=(const FastMap<KEY,VALUE>& x) = default;

/** Copy constructor from the base map class */
FastMap(const Base& x) : Base(x) {}

Expand Down
2 changes: 2 additions & 0 deletions gtsam/base/FastSet.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@ class FastSet: public std::set<VALUE, std::less<VALUE>,
Base(x) {
}

FastSet& operator=(const FastSet& other) = default;

#ifdef GTSAM_ALLOCATOR_BOOSTPOOL
/** Copy constructor from a standard STL container */
FastSet(const std::set<VALUE>& x) {
Expand Down
9 changes: 5 additions & 4 deletions gtsam/base/GenericValue.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down Expand Up @@ -112,7 +113,7 @@ class GenericValue: public Value {
* Clone this value (normal clone on the heap, delete with 'delete' operator)
*/
std::shared_ptr<Value> clone() const override {
return std::allocate_shared<GenericValue>(Eigen::aligned_allocator<GenericValue>(), *this);
return std::allocate_shared<GenericValue>(Eigen::aligned_allocator<GenericValue>(), *this);
}

/// Generic Value interface version of retract
Expand Down
3 changes: 3 additions & 0 deletions gtsam/base/Value.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/discrete/SignatureParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ std::optional<Row> static ParseConditional(const std::string& token) {
} catch (...) {
return std::nullopt;
}
return std::move(row);
return row;
}

std::optional<Table> static ParseConditionalTable(
Expand All @@ -62,7 +62,7 @@ std::optional<Table> static ParseConditionalTable(
}
}
}
return std::move(table);
return table;
}

std::vector<std::string> static Tokenize(const std::string& str) {
Expand Down
5 changes: 4 additions & 1 deletion gtsam/geometry/Pose2.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,10 @@ class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
}

/** 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)
Expand Down
7 changes: 4 additions & 3 deletions gtsam/geometry/Pose3.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,10 @@ class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
Pose3() : R_(traits<Rot3>::Identity()), t_(traits<Point3>::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) :
Expand Down
5 changes: 4 additions & 1 deletion gtsam/geometry/Rot2.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 2 additions & 0 deletions gtsam/linear/ConjugateGradientSolver.h
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
Expand Down
2 changes: 1 addition & 1 deletion gtsam/linear/HessianFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -379,7 +379,7 @@ GaussianFactor::shared_ptr HessianFactor::negate() const {
shared_ptr result = std::make_shared<This>(*this);
// Negate the information matrix of the result
result->info_.negate();
return std::move(result);
return result;
}

/* ************************************************************************* */
Expand Down
2 changes: 2 additions & 0 deletions gtsam/linear/JacobianFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down
2 changes: 1 addition & 1 deletion gtsam/linear/NoiseModel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ std::optional<Vector> checkIfDiagonal(const Matrix& M) {
Vector diagonal(n);
for (j = 0; j < n; j++)
diagonal(j) = M(j, j);
return std::move(diagonal);
return diagonal;
}
}

Expand Down
2 changes: 2 additions & 0 deletions gtsam/linear/VectorValues.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
2 changes: 1 addition & 1 deletion gtsam/nonlinear/ExpressionFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion gtsam/slam/FrobeniusFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
}

Expand Down
1 change: 1 addition & 0 deletions gtsam_unstable/geometry/Pose3Upright.h
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
4 changes: 1 addition & 3 deletions gtsam_unstable/slam/Mechanization_bRn2.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down

0 comments on commit c2a1242

Please sign in to comment.