Skip to content

Commit 5067dbb

Browse files
committed
clang-tidy fixes
1 parent 28b3e24 commit 5067dbb

File tree

4 files changed

+7
-7
lines changed

4 files changed

+7
-7
lines changed

core/include/moveit/task_constructor/solvers/cartesian_path.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class CartesianPath : public PlannerInterface
6060
void setStepSize(double step_size) { setProperty("step_size", step_size); }
6161
void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
6262
template <typename T = float>
63-
void setJumpThreshold(double) {
63+
void setJumpThreshold(double /*unused*/) {
6464
static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
6565
}
6666
void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ class GenerateRandomPose : public GeneratePose
5656

5757
/** Function signature for pose dimension samplers.
5858
* The input parameter is the seed, the returned value is the sampling result. */
59-
typedef std::function<double(double)> PoseDimensionSampler;
59+
using PoseDimensionSampler = std::function<double(double)>;
6060
enum PoseDimension
6161
{
6262
X,

core/python/bindings/src/properties.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ class PropertyConverterRegistry
5959
PropertyConverterBase::from_python_converter_function from_;
6060
};
6161
// map from type_index to corresponding converter functions
62-
typedef std::map<std::type_index, Entry> RegistryMap;
62+
using RegistryMap = std::map<std::type_index, Entry>;
6363
RegistryMap types_;
6464
// map from ros-msg-names to entry in types_
6565
using RosMsgTypeNameMap = std::map<std::string, RegistryMap::iterator>;

core/test/stage_mockups.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ struct GeneratorMockup : public Generator
6565
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
6666
bool canCompute() const override;
6767
void compute() override;
68-
virtual void reset() override { runs_ = 0; };
68+
void reset() override { runs_ = 0; };
6969
};
7070

7171
struct MonitoringGeneratorMockup : public MonitoringGenerator
@@ -82,7 +82,7 @@ struct MonitoringGeneratorMockup : public MonitoringGenerator
8282
bool canCompute() const override { return false; }
8383
void compute() override {}
8484
void onNewSolution(const SolutionBase& s) override;
85-
virtual void reset() override { runs_ = 0; };
85+
void reset() override { runs_ = 0; };
8686
};
8787

8888
struct ConnectMockup : public Connecting
@@ -99,7 +99,7 @@ struct ConnectMockup : public Connecting
9999
using Connecting::compatible; // make this accessible for testing
100100

101101
void compute(const InterfaceState& from, const InterfaceState& to) override;
102-
virtual void reset() override { runs_ = 0; };
102+
void reset() override { runs_ = 0; };
103103
};
104104

105105
struct PropagatorMockup : public PropagatingEitherWay
@@ -116,7 +116,7 @@ struct PropagatorMockup : public PropagatingEitherWay
116116

117117
void computeForward(const InterfaceState& from) override;
118118
void computeBackward(const InterfaceState& to) override;
119-
virtual void reset() override { runs_ = 0; };
119+
void reset() override { runs_ = 0; };
120120
};
121121

122122
struct ForwardMockup : public PropagatorMockup

0 commit comments

Comments
 (0)