clang-tidy: performance-*

I NOLINTed the noexcept move constructor for Task for now because
the constructor *can* indeed throw exceptions.
This commit is contained in:
v4hn 2020-06-10 19:02:47 +02:00
parent 8faba159f9
commit 15707673ed
14 changed files with 27 additions and 22 deletions

View File

@ -1,5 +1,6 @@
---
Checks: '-*,
performance-*,
llvm-namespace-comment,
modernize-use-nullptr,
modernize-use-override,

View File

@ -134,7 +134,8 @@ protected:
/// copy external_state to a child's interface and remember the link in internal_to map
void copyState(Interface::iterator external, const InterfacePtr& target, bool updated);
/// lift solution from internal to external level
void liftSolution(SolutionBasePtr solution, const InterfaceState* internal_from, const InterfaceState* internal_to);
void liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
const InterfaceState* internal_to);
auto& internalToExternalMap() { return internal_to_external_; }
const auto& internalToExternalMap() const { return internal_to_external_; }

View File

@ -370,7 +370,7 @@ public:
protected:
/// register solution as a solution connecting states from -> to
void connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution);
void connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution);
/// convienency methods consuming a SubTrajectory
void connect(const InterfaceState& from, const InterfaceState& to, SubTrajectory&& trajectory) {

View File

@ -139,10 +139,10 @@ public:
void composePropertyErrorMsg(const std::string& name, std::ostream& os);
// methods to spawn new solutions
void sendForward(const InterfaceState& from, InterfaceState&& to, SolutionBasePtr solution);
void sendBackward(InterfaceState&& from, const InterfaceState& to, SolutionBasePtr solution);
void spawn(InterfaceState&& state, SolutionBasePtr solution);
void connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution);
void sendForward(const InterfaceState& from, InterfaceState&& to, const SolutionBasePtr& solution);
void sendBackward(InterfaceState&& from, const InterfaceState& to, const SolutionBasePtr& solution);
void spawn(InterfaceState&& state, const SolutionBasePtr& solution);
void connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution);
bool storeSolution(const SolutionBasePtr& solution);
void newSolution(const SolutionBasePtr& solution);

View File

@ -55,7 +55,7 @@ public:
bool canCompute() const override;
void compute() override;
void setPose(const geometry_msgs::PoseStamped pose) { setProperty("pose", std::move(pose)); }
void setPose(const geometry_msgs::PoseStamped& pose) { setProperty("pose", pose); }
protected:
void onNewSolution(const SolutionBase& s) override;

View File

@ -80,8 +80,8 @@ public:
const std::string& adapter_plugins_param_name = "request_adapters");
Task(const std::string& id = "",
ContainerBase::pointer&& container = std::make_unique<SerialContainer>("task pipeline"));
Task(Task&& other);
Task& operator=(Task&& other);
Task(Task&& other); // NOLINT(performance-noexcept-move-constructor)
Task& operator=(Task&& other); // NOLINT(performance-noexcept-move-constructor)
~Task() override;
const std::string& id() const;

View File

@ -118,7 +118,7 @@ void ContainerBasePrivate::copyState(Interface::iterator external, const Interfa
internal_to_external_.insert(std::make_pair(&*internal, &*external));
}
void ContainerBasePrivate::liftSolution(SolutionBasePtr solution, const InterfaceState* internal_from,
void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
const InterfaceState* internal_to) {
if (!storeSolution(solution))
return;

View File

@ -140,7 +140,7 @@ bool StagePrivate::storeSolution(const SolutionBasePtr& solution) {
return true;
}
void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to, SolutionBasePtr solution) {
void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to, const SolutionBasePtr& solution) {
assert(nextStarts());
if (!storeSolution(solution))
return; // solution dropped
@ -157,7 +157,7 @@ void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to,
newSolution(solution);
}
void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to, SolutionBasePtr solution) {
void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to, const SolutionBasePtr& solution) {
assert(prevEnds());
if (!storeSolution(solution))
return; // solution dropped
@ -174,7 +174,7 @@ void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to,
newSolution(solution);
}
void StagePrivate::spawn(InterfaceState&& state, SolutionBasePtr solution) {
void StagePrivate::spawn(InterfaceState&& state, const SolutionBasePtr& solution) {
assert(prevEnds() && nextStarts());
if (!storeSolution(solution))
return; // solution dropped
@ -193,7 +193,7 @@ void StagePrivate::spawn(InterfaceState&& state, SolutionBasePtr solution) {
newSolution(solution);
}
void StagePrivate::connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution) {
void StagePrivate::connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution) {
if (!storeSolution(solution))
return; // solution dropped
@ -742,7 +742,7 @@ bool Connecting::compatible(const InterfaceState& from_state, const InterfaceSta
return true;
}
void Connecting::connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr s) {
void Connecting::connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& s) {
pimpl()->connect(from, to, s);
}

View File

@ -80,6 +80,8 @@ void PredicateFilter::init(const moveit::core::RobotModelConstPtr& robot_model)
void PredicateFilter::onNewSolution(const SolutionBase& s) {
const auto& props = properties();
// false-positive in clang-tidy 10.0.0: predicate might change comment
// NOLINTNEXTLINE(performance-unnecessary-value-param)
std::string comment = s.comment();
double cost = s.cost();

View File

@ -116,11 +116,12 @@ Task::Task(const std::string& id, ContainerBase::pointer&& container)
enableIntrospection(true);
}
Task::Task(Task&& other) : WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
Task::Task(Task&& other) // NOLINT(performance-noexcept-move-constructor)
: WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
*this = std::move(other);
}
Task& Task::operator=(Task&& other) {
Task& Task::operator=(Task&& other) { // NOLINT(performance-noexcept-move-constructor)
clear(); // remove all stages of current task
swap(this->pimpl_, other.pimpl_);
return *this;
@ -133,7 +134,7 @@ struct PlannerCache
using ModelList = std::list<std::pair<std::weak_ptr<const robot_model::RobotModel>, PlannerMap> >;
ModelList cache_;
PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, PlannerID id) {
PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, const PlannerID& id) {
// find model in cache_ and remove expired entries while doing so
ModelList::iterator model_it = cache_.begin();
while (model_it != cache_.end()) {

View File

@ -108,7 +108,7 @@ public:
/// remove all hosted markers from display
void clearMarkers();
/// add markers in MarkerVisualization for display
void addMarkers(MarkerVisualizationPtr markers);
void addMarkers(const MarkerVisualizationPtr& markers);
/// update pose of all markers
void update(const planning_scene::PlanningScene& scene, const moveit::core::RobotState& robot_state);

View File

@ -102,7 +102,7 @@ public:
virtual void reset();
void onInitialize(Ogre::SceneNode* scene_node, rviz::DisplayContext* context);
void onRobotModelLoaded(moveit::core::RobotModelConstPtr robot_model);
void onRobotModelLoaded(const moveit::core::RobotModelConstPtr& robot_model);
void onEnable();
void onDisable();
void setName(const QString& name);

View File

@ -188,7 +188,7 @@ void MarkerVisualizationProperty::clearMarkers() {
hosted_markers_.clear();
}
void MarkerVisualizationProperty::addMarkers(MarkerVisualizationPtr markers) {
void MarkerVisualizationProperty::addMarkers(const MarkerVisualizationPtr& markers) {
if (!markers)
return;

View File

@ -207,7 +207,7 @@ void TaskSolutionVisualization::setName(const QString& name) {
slider_dock_panel_->setWindowTitle(name + " - Slider");
}
void TaskSolutionVisualization::onRobotModelLoaded(robot_model::RobotModelConstPtr robot_model) {
void TaskSolutionVisualization::onRobotModelLoaded(const robot_model::RobotModelConstPtr& robot_model) {
// Error check
if (!robot_model) {
ROS_ERROR_STREAM_NAMED("task_solution_visualization", "No robot model found");