Skip to content

Commit 1570767

Browse files
committed
clang-tidy: performance-*
I NOLINTed the noexcept move constructor for Task for now because the constructor *can* indeed throw exceptions.
1 parent 8faba15 commit 1570767

File tree

14 files changed

+27
-22
lines changed

14 files changed

+27
-22
lines changed

.clang-tidy

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
---
22
Checks: '-*,
3+
performance-*,
34
llvm-namespace-comment,
45
modernize-use-nullptr,
56
modernize-use-override,

core/include/moveit/task_constructor/container_p.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,8 @@ class ContainerBasePrivate : public StagePrivate
134134
/// copy external_state to a child's interface and remember the link in internal_to map
135135
void copyState(Interface::iterator external, const InterfacePtr& target, bool updated);
136136
/// lift solution from internal to external level
137-
void liftSolution(SolutionBasePtr solution, const InterfaceState* internal_from, const InterfaceState* internal_to);
137+
void liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
138+
const InterfaceState* internal_to);
138139

139140
auto& internalToExternalMap() { return internal_to_external_; }
140141
const auto& internalToExternalMap() const { return internal_to_external_; }

core/include/moveit/task_constructor/stage.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -370,7 +370,7 @@ class Connecting : public ComputeBase
370370

371371
protected:
372372
/// register solution as a solution connecting states from -> to
373-
void connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution);
373+
void connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution);
374374

375375
/// convienency methods consuming a SubTrajectory
376376
void connect(const InterfaceState& from, const InterfaceState& to, SubTrajectory&& trajectory) {

core/include/moveit/task_constructor/stage_p.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -139,10 +139,10 @@ class StagePrivate
139139
void composePropertyErrorMsg(const std::string& name, std::ostream& os);
140140

141141
// methods to spawn new solutions
142-
void sendForward(const InterfaceState& from, InterfaceState&& to, SolutionBasePtr solution);
143-
void sendBackward(InterfaceState&& from, const InterfaceState& to, SolutionBasePtr solution);
144-
void spawn(InterfaceState&& state, SolutionBasePtr solution);
145-
void connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution);
142+
void sendForward(const InterfaceState& from, InterfaceState&& to, const SolutionBasePtr& solution);
143+
void sendBackward(InterfaceState&& from, const InterfaceState& to, const SolutionBasePtr& solution);
144+
void spawn(InterfaceState&& state, const SolutionBasePtr& solution);
145+
void connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution);
146146

147147
bool storeSolution(const SolutionBasePtr& solution);
148148
void newSolution(const SolutionBasePtr& solution);

core/include/moveit/task_constructor/stages/generate_pose.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ class GeneratePose : public MonitoringGenerator
5555
bool canCompute() const override;
5656
void compute() override;
5757

58-
void setPose(const geometry_msgs::PoseStamped pose) { setProperty("pose", std::move(pose)); }
58+
void setPose(const geometry_msgs::PoseStamped& pose) { setProperty("pose", pose); }
5959

6060
protected:
6161
void onNewSolution(const SolutionBase& s) override;

core/include/moveit/task_constructor/task.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -80,8 +80,8 @@ class Task : protected WrapperBase
8080
const std::string& adapter_plugins_param_name = "request_adapters");
8181
Task(const std::string& id = "",
8282
ContainerBase::pointer&& container = std::make_unique<SerialContainer>("task pipeline"));
83-
Task(Task&& other);
84-
Task& operator=(Task&& other);
83+
Task(Task&& other); // NOLINT(performance-noexcept-move-constructor)
84+
Task& operator=(Task&& other); // NOLINT(performance-noexcept-move-constructor)
8585
~Task() override;
8686

8787
const std::string& id() const;

core/src/container.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ void ContainerBasePrivate::copyState(Interface::iterator external, const Interfa
118118
internal_to_external_.insert(std::make_pair(&*internal, &*external));
119119
}
120120

121-
void ContainerBasePrivate::liftSolution(SolutionBasePtr solution, const InterfaceState* internal_from,
121+
void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
122122
const InterfaceState* internal_to) {
123123
if (!storeSolution(solution))
124124
return;

core/src/stage.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,7 @@ bool StagePrivate::storeSolution(const SolutionBasePtr& solution) {
140140
return true;
141141
}
142142

143-
void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to, SolutionBasePtr solution) {
143+
void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to, const SolutionBasePtr& solution) {
144144
assert(nextStarts());
145145
if (!storeSolution(solution))
146146
return; // solution dropped
@@ -157,7 +157,7 @@ void StagePrivate::sendForward(const InterfaceState& from, InterfaceState&& to,
157157
newSolution(solution);
158158
}
159159

160-
void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to, SolutionBasePtr solution) {
160+
void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to, const SolutionBasePtr& solution) {
161161
assert(prevEnds());
162162
if (!storeSolution(solution))
163163
return; // solution dropped
@@ -174,7 +174,7 @@ void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to,
174174
newSolution(solution);
175175
}
176176

177-
void StagePrivate::spawn(InterfaceState&& state, SolutionBasePtr solution) {
177+
void StagePrivate::spawn(InterfaceState&& state, const SolutionBasePtr& solution) {
178178
assert(prevEnds() && nextStarts());
179179
if (!storeSolution(solution))
180180
return; // solution dropped
@@ -193,7 +193,7 @@ void StagePrivate::spawn(InterfaceState&& state, SolutionBasePtr solution) {
193193
newSolution(solution);
194194
}
195195

196-
void StagePrivate::connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr solution) {
196+
void StagePrivate::connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution) {
197197
if (!storeSolution(solution))
198198
return; // solution dropped
199199

@@ -742,7 +742,7 @@ bool Connecting::compatible(const InterfaceState& from_state, const InterfaceSta
742742
return true;
743743
}
744744

745-
void Connecting::connect(const InterfaceState& from, const InterfaceState& to, SolutionBasePtr s) {
745+
void Connecting::connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& s) {
746746
pimpl()->connect(from, to, s);
747747
}
748748

core/src/stages/predicate_filter.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,8 @@ void PredicateFilter::init(const moveit::core::RobotModelConstPtr& robot_model)
8080
void PredicateFilter::onNewSolution(const SolutionBase& s) {
8181
const auto& props = properties();
8282

83+
// false-positive in clang-tidy 10.0.0: predicate might change comment
84+
// NOLINTNEXTLINE(performance-unnecessary-value-param)
8385
std::string comment = s.comment();
8486

8587
double cost = s.cost();

core/src/task.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -116,11 +116,12 @@ Task::Task(const std::string& id, ContainerBase::pointer&& container)
116116
enableIntrospection(true);
117117
}
118118

119-
Task::Task(Task&& other) : WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
119+
Task::Task(Task&& other) // NOLINT(performance-noexcept-move-constructor)
120+
: WrapperBase(new TaskPrivate(this, std::string()), std::make_unique<SerialContainer>()) {
120121
*this = std::move(other);
121122
}
122123

123-
Task& Task::operator=(Task&& other) {
124+
Task& Task::operator=(Task&& other) { // NOLINT(performance-noexcept-move-constructor)
124125
clear(); // remove all stages of current task
125126
swap(this->pimpl_, other.pimpl_);
126127
return *this;
@@ -133,7 +134,7 @@ struct PlannerCache
133134
using ModelList = std::list<std::pair<std::weak_ptr<const robot_model::RobotModel>, PlannerMap> >;
134135
ModelList cache_;
135136

136-
PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, PlannerID id) {
137+
PlannerMap::mapped_type& retrieve(const robot_model::RobotModelConstPtr& model, const PlannerID& id) {
137138
// find model in cache_ and remove expired entries while doing so
138139
ModelList::iterator model_it = cache_.begin();
139140
while (model_it != cache_.end()) {

0 commit comments

Comments
 (0)