Skip to content

Commit

Permalink
Fix CMake warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Jul 1, 2020
1 parent 8bf5906 commit e82589e
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ class AllowedCollisionMatrix
AllowedCollisionMatrix(const moveit_msgs::msg::AllowedCollisionMatrix& msg);

/** @brief Copy constructor */
AllowedCollisionMatrix(const AllowedCollisionMatrix& acm);
AllowedCollisionMatrix(const AllowedCollisionMatrix& acm) = default;

/** @brief Get the type of the allowed collision between two elements. Return true if the entry is included in the
* collision matrix.
Expand Down
8 changes: 0 additions & 8 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,14 +85,6 @@ AllowedCollisionMatrix::AllowedCollisionMatrix(const moveit_msgs::msg::AllowedCo
}
}

AllowedCollisionMatrix::AllowedCollisionMatrix(const AllowedCollisionMatrix& acm)
{
entries_ = acm.entries_;
allowed_contacts_ = acm.allowed_contacts_;
default_entries_ = acm.default_entries_;
default_allowed_contacts_ = acm.default_allowed_contacts_;
}

bool AllowedCollisionMatrix::getEntry(const std::string& name1, const std::string& name2, DecideContactFn& fn) const
{
auto it1 = allowed_contacts_.find(name1);
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ void RobotState::copyFrom(const RobotState& other)
(robot_model_->getVariableCount() * (1 + ((has_velocity_ || has_acceleration_ || has_effort_) ? 1 : 0) +
((has_acceleration_ || has_effort_) ? 1 : 0)) +
nr_doubles_for_dirty_joint_transforms);
memcpy(variable_joint_transforms_, other.variable_joint_transforms_, bytes);
memcpy((char*)variable_joint_transforms_, (char*)other.variable_joint_transforms_, bytes);
}

// copy attached bodies
Expand Down

0 comments on commit e82589e

Please sign in to comment.