Skip to content

Commit 3616634

Browse files
committed
clang-tidy: use using over typedef
$ run-clang-tidy.py -header-filter='.*' -checks='modernize-use-using' -fix add .clang-tidy file
1 parent c662311 commit 3616634

File tree

23 files changed

+101
-68
lines changed

23 files changed

+101
-68
lines changed

.clang-tidy

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
---
2+
Checks: '-*,
3+
modernize-use-using,
4+
'
5+
HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h'
6+
AnalyzeTemporaryDtors: false
7+
CheckOptions:
8+
- key: llvm-namespace-comment.ShortNamespaceLines
9+
value: '10'
10+
- key: llvm-namespace-comment.SpacesBeforeComments
11+
value: '2'
12+
- key: readability-braces-around-statements.ShortStatementLines
13+
value: '2'
14+
# type names
15+
- key: readability-identifier-naming.ClassCase
16+
value: CamelCase
17+
- key: readability-identifier-naming.EnumCase
18+
value: CamelCase
19+
- key: readability-identifier-naming.UnionCase
20+
value: CamelCase
21+
# method names
22+
- key: readability-identifier-naming.MethodCase
23+
value: camelBack
24+
# variable names
25+
- key: readability-identifier-naming.VariableCase
26+
value: lower_case
27+
- key: readability-identifier-naming.ClassMemberSuffix
28+
value: '_'
29+
# const static or global variables are UPPER_CASE
30+
- key: readability-identifier-naming.EnumConstantCase
31+
value: UPPER_CASE
32+
- key: readability-identifier-naming.StaticConstantCase
33+
value: UPPER_CASE
34+
- key: readability-identifier-naming.ClassConstantCase
35+
value: UPPER_CASE
36+
- key: readability-identifier-naming.GlobalVariableCase
37+
value: UPPER_CASE
38+
...

core/include/moveit/task_constructor/container.h

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -49,14 +49,14 @@ class ContainerBase : public Stage
4949
{
5050
public:
5151
PRIVATE_CLASS(ContainerBase)
52-
typedef std::unique_ptr<ContainerBase> pointer;
52+
using pointer = std::unique_ptr<ContainerBase>;
5353

5454
size_t numChildren() const;
5555
Stage* findChild(const std::string& name) const;
5656

5757
/** Callback function type used by traverse functions
5858
* The callback should return false if traversal should be stopped. */
59-
typedef std::function<bool(const Stage&, unsigned int depth)> StageCallback;
59+
using StageCallback = std::function<bool(const Stage&, unsigned int)>;
6060
/// traverse direct children of this container, calling the callback for each of them
6161
bool traverseChildren(const StageCallback& processor) const;
6262
/// traverse all children of this container recursively
@@ -98,8 +98,7 @@ class SerialContainer : public ContainerBase
9898
/// called by a (direct) child when a new solution becomes available
9999
void onNewSolution(const SolutionBase& s) override;
100100

101-
typedef std::function<void(const SolutionSequence::container_type& trace, double trace_accumulated_cost)>
102-
SolutionProcessor;
101+
using SolutionProcessor = std::function<void(const SolutionSequence::container_type&, double)>;
103102

104103
/// Traverse all solution pathes starting at start and going in given direction dir
105104
/// until the end, i.e. until there are no more subsolutions in the given direction

core/include/moveit/task_constructor/container_p.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,10 @@ class ContainerBasePrivate : public StagePrivate
7575
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);
7676

7777
public:
78-
typedef StagePrivate::container_type container_type;
79-
typedef container_type::iterator iterator;
80-
typedef container_type::const_iterator const_iterator;
81-
typedef std::function<bool(Stage&, int depth)> NonConstStageCallback;
78+
using container_type = StagePrivate::container_type;
79+
using iterator = container_type::iterator;
80+
using const_iterator = container_type::const_iterator;
81+
using NonConstStageCallback = std::function<bool(Stage&, int)>;
8282

8383
inline const container_type& children() const { return children_; }
8484

@@ -242,13 +242,13 @@ class MergerPrivate : public ParallelContainerBasePrivate
242242
friend class Merger;
243243

244244
moveit::core::JointModelGroupPtr jmg_merged_;
245-
typedef std::vector<const SubTrajectory*> ChildSolutionList;
246-
typedef std::map<const StagePrivate*, ChildSolutionList> ChildSolutionMap;
245+
using ChildSolutionList = std::vector<const SubTrajectory*>;
246+
using ChildSolutionMap = std::map<const StagePrivate*, ChildSolutionList>;
247247
// map from external source state (iterator) to all corresponding children's solutions
248248
std::map<InterfaceState*, ChildSolutionMap> source_state_to_solutions_;
249249

250250
public:
251-
typedef std::function<void(SubTrajectory&&)> Spawner;
251+
using Spawner = std::function<void(SubTrajectory&&)>;
252252
MergerPrivate(Merger* me, const std::string& name);
253253

254254
void resolveInterface(InterfaceFlags expected) override;

core/include/moveit/task_constructor/cost_queue.h

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -30,21 +30,21 @@ class ordered
3030
{
3131
public:
3232
typedef std::list<T> container_type;
33-
typedef typename container_type::value_type value_type;
34-
typedef typename container_type::size_type size_type;
35-
typedef typename container_type::difference_type difference_type;
33+
using value_type = typename container_type::value_type;
34+
using size_type = typename container_type::size_type;
35+
using difference_type = typename container_type::difference_type;
3636

37-
typedef typename container_type::reference reference;
38-
typedef typename container_type::const_reference const_reference;
37+
using reference = typename container_type::reference;
38+
using const_reference = typename container_type::const_reference;
3939

40-
typedef typename container_type::pointer pointer;
41-
typedef typename container_type::const_pointer const_pointer;
40+
using pointer = typename container_type::pointer;
41+
using const_pointer = typename container_type::const_pointer;
4242

43-
typedef typename container_type::iterator iterator;
44-
typedef typename container_type::const_iterator const_iterator;
43+
using iterator = typename container_type::iterator;
44+
using const_iterator = typename container_type::const_iterator;
4545

46-
typedef typename container_type::reverse_iterator reverse_iterator;
47-
typedef typename container_type::const_reverse_iterator const_reverse_iterator;
46+
using reverse_iterator = typename container_type::reverse_iterator;
47+
using const_reverse_iterator = typename container_type::const_reverse_iterator;
4848

4949
protected:
5050
container_type c;
@@ -133,7 +133,7 @@ namespace detail {
133133
template <typename ValueType, typename CostType>
134134
struct ItemCostPair : std::pair<ValueType, CostType>
135135
{
136-
typedef CostType cost_type;
136+
using cost_type = CostType;
137137

138138
ItemCostPair(const std::pair<ValueType, CostType>& other) : std::pair<ValueType, CostType>(other) {}
139139
ItemCostPair(std::pair<ValueType, CostType>&& other) : std::pair<ValueType, CostType>(std::move(other)) {}
@@ -153,7 +153,7 @@ template <typename ValueType, typename CostType = double,
153153
typename Compare = std::less<detail::ItemCostPair<ValueType, CostType>>>
154154
class cost_ordered : public ordered<detail::ItemCostPair<ValueType, CostType>, Compare>
155155
{
156-
typedef ordered<detail::ItemCostPair<ValueType, CostType>, Compare> base_type;
156+
using base_type = ordered<detail::ItemCostPair<ValueType, CostType>, Compare>;
157157

158158
public:
159159
auto insert(const ValueType& value, const CostType cost) { return base_type::insert(std::make_pair(value, cost)); }

core/include/moveit/task_constructor/marker_tools.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ namespace moveit {
1919
namespace task_constructor {
2020

2121
/** signature of callback function, passing the generated marker and the name of the robot link / scene object */
22-
typedef std::function<void(visualization_msgs::Marker&, const std::string&)> MarkerCallback;
22+
using MarkerCallback = std::function<void(visualization_msgs::Marker&, const std::string&)>;
2323

2424
/** generate marker msgs to visualize the planning scene, calling the given callback for each of them
2525
* object_names: set of links to include (or all if empty) */

core/include/moveit/task_constructor/properties.h

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -89,9 +89,9 @@ class Property
8989
/// exception thrown when trying to set a value not matching the declared type
9090
class type_error;
9191

92-
typedef uint SourceFlags;
92+
using SourceFlags = uint;
9393
/// function callback used to initialize property value from another PropertyMap
94-
typedef std::function<boost::any(const PropertyMap& other)> InitializerFunction;
94+
using InitializerFunction = std::function<boost::any(const PropertyMap&)>;
9595

9696
/// set current value and default value
9797
void setValue(const boost::any& value);
@@ -191,8 +191,8 @@ struct hasDeserialize<T, decltype(std::declval<std::istream&>() >> std::declval<
191191
class PropertySerializerBase
192192
{
193193
public:
194-
typedef std::string (*SerializeFunction)(const boost::any&);
195-
typedef boost::any (*DeserializeFunction)(const std::string&);
194+
using SerializeFunction = std::string (*)(const boost::any&);
195+
using DeserializeFunction = boost::any (*)(const std::string&);
196196

197197
static std::string dummySerialize(const boost::any&) { return ""; }
198198
static boost::any dummyDeserialize(const std::string&) { return boost::any(); }
@@ -288,8 +288,8 @@ class PropertyMap
288288
Property& property(const std::string& name);
289289
const Property& property(const std::string& name) const { return const_cast<PropertyMap*>(this)->property(name); }
290290

291-
typedef std::map<std::string, Property>::iterator iterator;
292-
typedef std::map<std::string, Property>::const_iterator const_iterator;
291+
using iterator = std::map<std::string, Property>::iterator;
292+
using const_iterator = std::map<std::string, Property>::const_iterator;
293293

294294
iterator begin() { return props_.begin(); }
295295
iterator end() { return props_.end(); }

core/include/moveit/task_constructor/stage.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ enum InterfaceFlag
8484
GENERATE = WRITES_PREV_END | WRITES_NEXT_START,
8585
};
8686

87-
typedef Flags<InterfaceFlag> InterfaceFlags;
87+
using InterfaceFlags = Flags<InterfaceFlag>;
8888

8989
/** invert interface such that
9090
* - new end can connect to old start
@@ -111,7 +111,7 @@ constexpr InterfaceFlags END_IF_MASK({ READS_END, WRITES_NEXT_START });
111111
MOVEIT_CLASS_FORWARD(Interface)
112112
MOVEIT_CLASS_FORWARD(Stage)
113113
class InterfaceState;
114-
typedef std::pair<const InterfaceState&, const InterfaceState&> InterfaceStatePair;
114+
using InterfaceStatePair = std::pair<const InterfaceState&, const InterfaceState&>;
115115

116116
/// exception thrown by Stage::init()
117117
/// It collects individual errors in stages throughout the pipeline to allow overall error reporting
@@ -144,7 +144,7 @@ class Stage
144144
{
145145
public:
146146
PRIVATE_CLASS(Stage)
147-
typedef std::unique_ptr<Stage> pointer;
147+
using pointer = std::unique_ptr<Stage>;
148148
/** Names for property initialization sources
149149
*
150150
* - INTERFACE allows to pass properties from one stage to the next (in a SerialContainer).
@@ -203,8 +203,8 @@ class Stage
203203
}
204204
void setForwardedProperties(const std::set<std::string>& names) { setProperty("forwarded_properties", names); }
205205

206-
typedef std::function<void(const SolutionBase& s)> SolutionCallback;
207-
typedef std::list<SolutionCallback> SolutionCallbackList;
206+
using SolutionCallback = std::function<void(const SolutionBase&)>;
207+
using SolutionCallbackList = std::list<SolutionCallback>;
208208
/// add function to be called for every newly found solution or failure
209209
SolutionCallbackList::const_iterator addSolutionCallback(SolutionCallback&& cb);
210210
/// remove function callback

core/include/moveit/task_constructor/stage_p.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -280,7 +280,7 @@ class ConnectingPrivate : public ComputeBasePrivate
280280
{
281281
friend class Connecting;
282282

283-
typedef std::pair<Interface::const_iterator, Interface::const_iterator> StatePair;
283+
using StatePair = std::pair<Interface::const_iterator, Interface::const_iterator>;
284284
struct StatePairLess
285285
{
286286
bool operator()(const StatePair& x, const StatePair& y) const {

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ class Connect : public Connecting
7373
WAYPOINTS = 1
7474
};
7575

76-
typedef std::vector<std::pair<std::string, solvers::PlannerInterfacePtr>> GroupPlannerVector;
76+
using GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >;
7777
Connect(const std::string& name = "connect", const GroupPlannerVector& planners = {});
7878

7979
void setPathConstraints(moveit_msgs::Constraints path_constraints) {

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

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -65,9 +65,8 @@ namespace stages {
6565
class ModifyPlanningScene : public PropagatingEitherWay
6666
{
6767
public:
68-
typedef std::vector<std::string> Names;
69-
typedef std::function<void(const planning_scene::PlanningScenePtr& scene, const PropertyMap& properties)>
70-
ApplyCallback;
68+
using Names = std::vector<std::string>;
69+
using ApplyCallback = std::function<void(const planning_scene::PlanningScenePtr&, const PropertyMap&)>;
7170
ModifyPlanningScene(const std::string& name = "modify planning scene");
7271

7372
void computeForward(const InterfaceState& from) override;

0 commit comments

Comments
 (0)