Skip to content

Commit 32160fe

Browse files
committed
refactored the smart ptr class macros
1 parent 28175f4 commit 32160fe

20 files changed

+74
-35
lines changed

rclcpp/include/rclcpp/any_executable.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2014 Open Source Robotics Foundation, Inc.
1+
// Copyright 2015 Open Source Robotics Foundation, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -27,11 +27,11 @@ namespace executor
2727

2828
struct AnyExecutable
2929
{
30-
RCLCPP_MAKE_SHARED_DEFINITIONS(AnyExecutable);
30+
RCLCPP_SMART_PTR_DEFINITIONS(AnyExecutable);
3131
AnyExecutable()
3232
: subscription(0), timer(0), callback_group(0), node(0)
3333
{}
34-
// Either the subscription or the timer will be set, but not both
34+
// Only one of the following pointers will be set.
3535
rclcpp::subscription::SubscriptionBase::SharedPtr subscription;
3636
rclcpp::timer::TimerBase::SharedPtr timer;
3737
rclcpp::service::ServiceBase::SharedPtr service;

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ class CallbackGroup
5252
friend class rclcpp::executor::Executor;
5353

5454
public:
55-
RCLCPP_MAKE_SHARED_DEFINITIONS(CallbackGroup);
55+
RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup);
5656

5757
CallbackGroup(CallbackGroupType group_type)
5858
: type_(group_type), can_be_taken_from_(true)

rclcpp/include/rclcpp/client.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class ClientBase
4545
friend class rclcpp::executor::Executor;
4646

4747
public:
48-
RCLCPP_MAKE_SHARED_DEFINITIONS(ClientBase);
48+
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase);
4949

5050
ClientBase(
5151
std::shared_ptr<rmw_node_t> node_handle,
@@ -99,7 +99,7 @@ class Client : public ClientBase
9999

100100
typedef std::function<void (SharedFuture)> CallbackType;
101101

102-
RCLCPP_MAKE_SHARED_DEFINITIONS(Client);
102+
RCLCPP_SMART_PTR_DEFINITIONS(Client);
103103

104104
Client(
105105
std::shared_ptr<rmw_node_t> node_handle,

rclcpp/include/rclcpp/context.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ namespace context
2828
class Context
2929
{
3030
public:
31-
RCLCPP_MAKE_SHARED_DEFINITIONS(Context);
31+
RCLCPP_SMART_PTR_DEFINITIONS(Context);
3232

3333
Context() {}
3434

rclcpp/include/rclcpp/contexts/default_context.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ namespace default_context
2727
class DefaultContext : public rclcpp::context::Context
2828
{
2929
public:
30-
RCLCPP_MAKE_SHARED_DEFINITIONS(DefaultContext);
30+
RCLCPP_SMART_PTR_DEFINITIONS(DefaultContext);
3131

3232
DefaultContext() {}
3333

rclcpp/include/rclcpp/executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ class Executor
4040
friend class memory_strategy::MemoryStrategy;
4141

4242
public:
43-
RCLCPP_MAKE_SHARED_DEFINITIONS(Executor);
43+
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor);
4444

4545
explicit Executor(memory_strategy::MemoryStrategy::SharedPtr ms =
4646
memory_strategy::create_default_strategy())

rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ namespace multi_threaded_executor
3838
class MultiThreadedExecutor : public executor::Executor
3939
{
4040
public:
41-
RCLCPP_MAKE_SHARED_DEFINITIONS(MultiThreadedExecutor);
41+
RCLCPP_SMART_PTR_DEFINITIONS(MultiThreadedExecutor);
4242

4343
MultiThreadedExecutor(memory_strategy::MemoryStrategy::SharedPtr ms =
4444
memory_strategy::create_default_strategy())

rclcpp/include/rclcpp/executors/single_threaded_executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ namespace single_threaded_executor
3939
class SingleThreadedExecutor : public executor::Executor
4040
{
4141
public:
42-
RCLCPP_MAKE_SHARED_DEFINITIONS(SingleThreadedExecutor);
42+
RCLCPP_SMART_PTR_DEFINITIONS(SingleThreadedExecutor);
4343

4444
SingleThreadedExecutor(memory_strategy::MemoryStrategy::SharedPtr ms =
4545
memory_strategy::create_default_strategy())

rclcpp/include/rclcpp/macros.hpp

Lines changed: 47 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -23,21 +23,64 @@
2323
Class(const Class &) = delete; \
2424
Class & operator=(const Class &) = delete;
2525

26-
/* Defines a make_shared static function on the class using perfect forwarding.
26+
/* Defines aliases and static functions for using the Class with smart pointers.
2727
*
2828
* Use in the public section of the class.
2929
* Make sure to include <memory> in the header when using this.
3030
*/
31-
#define RCLCPP_MAKE_SHARED_DEFINITIONS(Class) \
32-
typedef std::shared_ptr<Class> SharedPtr; \
33-
\
31+
#define RCLCPP_SMART_PTR_DEFINITIONS(Class) \
32+
RCLCPP_SHARED_PTR_DEFINITIONS(Class) \
33+
RCLCPP_WEAK_PTR_DEFINITIONS(Class) \
34+
RCLCPP_UNIQUE_PTR_DEFINITIONS(Class)
35+
36+
/* Defines aliases and static functions for using the Class with smart pointers.
37+
*
38+
* Same as RCLCPP_SMART_PTR_DEFINITIONS expect it excludes the static
39+
* Class::make_unique() method definition which does not work on classes which
40+
* are not CopyConstructable.
41+
*
42+
* Use in the public section of the class.
43+
* Make sure to include <memory> in the header when using this.
44+
*/
45+
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Class) \
46+
RCLCPP_SHARED_PTR_DEFINITIONS(Class) \
47+
RCLCPP_WEAK_PTR_DEFINITIONS(Class) \
48+
__RCLCPP_UNIQUE_PTR_ALIAS(Class)
49+
50+
#define __RCLCPP_SHARED_PTR_ALIAS(Class) using SharedPtr = std::shared_ptr<Class>;
51+
52+
#define __RCLCPP_MAKE_SHARED_DEFINITION(Class) \
3453
template<typename ... Args> \
3554
static std::shared_ptr<Class> \
3655
make_shared(Args && ... args) \
3756
{ \
3857
return std::make_shared<Class>(std::forward<Args>(args) ...); \
3958
}
4059

60+
/// Defines aliases and static functions for using the Class with shared_ptrs.
61+
#define RCLCPP_SHARED_PTR_DEFINITIONS(Class) \
62+
__RCLCPP_SHARED_PTR_ALIAS(Class) \
63+
__RCLCPP_MAKE_SHARED_DEFINITION(Class)
64+
65+
#define __RCLCPP_WEAK_PTR_ALIAS(Class) using WeakPtr = std::weak_ptr<Class>;
66+
67+
/// Defines aliases and static functions for using the Class with weak_ptrs.
68+
#define RCLCPP_WEAK_PTR_DEFINITIONS(Class) __RCLCPP_WEAK_PTR_ALIAS(Class)
69+
70+
#define __RCLCPP_UNIQUE_PTR_ALIAS(Class) using UniquePtr = std::unique_ptr<Class>;
71+
72+
#define __RCLCPP_MAKE_UNIQUE_DEFINITION(Class) \
73+
template<typename ... Args> \
74+
static std::unique_ptr<Class> \
75+
make_unique(Args && ... args) \
76+
{ \
77+
return std::unique_ptr<Class>(new Class(std::forward<Args>(args) ...)); \
78+
}
79+
/// Defines aliases and static functions for using the Class with unique_ptrs.
80+
#define RCLCPP_UNIQUE_PTR_DEFINITIONS(Class) \
81+
__RCLCPP_UNIQUE_PTR_ALIAS(Class) \
82+
__RCLCPP_MAKE_UNIQUE_DEFINITION(Class)
83+
4184
#define RCLCPP_INFO(Args) std::cout << Args << std::endl;
4285

4386
#endif /* RCLCPP_RCLCPP_MACROS_HPP_ */

rclcpp/include/rclcpp/memory_strategy.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class MemoryStrategy
3636
friend class executor::Executor;
3737

3838
public:
39-
RCLCPP_MAKE_SHARED_DEFINITIONS(MemoryStrategy);
39+
RCLCPP_SMART_PTR_DEFINITIONS(MemoryStrategy);
4040
virtual void ** borrow_handles(HandleType type, size_t number_of_handles)
4141
{
4242
(void)type;

0 commit comments

Comments
 (0)