diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index f2aa4eba6f..e7ce2e6ddb 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -10,8 +10,8 @@ find_package(rmw_implementation REQUIRED) find_package(rmw_implementation_cmake REQUIRED) find_package(rosidl_generator_cpp REQUIRED) -if(NOT WIN32) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -Wall -Wextra") +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-std=c++11 -Wall -Wextra -Wpedantic) endif() include_directories(include) diff --git a/rclcpp/include/rclcpp/any_executable.hpp b/rclcpp/include/rclcpp/any_executable.hpp index 656b2c7d34..5c1e2ae627 100644 --- a/rclcpp/include/rclcpp/any_executable.hpp +++ b/rclcpp/include/rclcpp/any_executable.hpp @@ -28,7 +28,7 @@ namespace executor struct AnyExecutable { - RCLCPP_SMART_PTR_DEFINITIONS(AnyExecutable); + RCLCPP_SMART_PTR_DEFINITIONS(AnyExecutable) RCLCPP_PUBLIC AnyExecutable(); diff --git a/rclcpp/include/rclcpp/callback_group.hpp b/rclcpp/include/rclcpp/callback_group.hpp index 434f1f80bb..15db7741ef 100644 --- a/rclcpp/include/rclcpp/callback_group.hpp +++ b/rclcpp/include/rclcpp/callback_group.hpp @@ -49,7 +49,7 @@ class CallbackGroup friend class rclcpp::node::Node; public: - RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup); + RCLCPP_SMART_PTR_DEFINITIONS(CallbackGroup) RCLCPP_PUBLIC explicit CallbackGroup(CallbackGroupType group_type); @@ -79,7 +79,7 @@ class CallbackGroup type() const; private: - RCLCPP_DISABLE_COPY(CallbackGroup); + RCLCPP_DISABLE_COPY(CallbackGroup) RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index b170310f80..dfc28f3122 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -50,7 +50,7 @@ namespace client class ClientBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase) RCLCPP_PUBLIC ClientBase( @@ -88,7 +88,7 @@ class ClientBase std::shared_ptr request_header, std::shared_ptr response) = 0; protected: - RCLCPP_DISABLE_COPY(ClientBase); + RCLCPP_DISABLE_COPY(ClientBase) RCLCPP_PUBLIC bool @@ -124,7 +124,7 @@ class Client : public ClientBase using CallbackType = std::function; using CallbackWithRequestType = std::function; - RCLCPP_SMART_PTR_DEFINITIONS(Client); + RCLCPP_SMART_PTR_DEFINITIONS(Client) Client( std::shared_ptr parent_node, @@ -250,7 +250,7 @@ class Client : public ClientBase } private: - RCLCPP_DISABLE_COPY(Client); + RCLCPP_DISABLE_COPY(Client) std::map> pending_requests_; std::mutex pending_requests_mutex_; diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index 0b1f1c1e98..27af6cd7b5 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -36,7 +36,7 @@ namespace context class Context { public: - RCLCPP_SMART_PTR_DEFINITIONS(Context); + RCLCPP_SMART_PTR_DEFINITIONS(Context) RCLCPP_PUBLIC Context(); @@ -68,7 +68,7 @@ class Context } private: - RCLCPP_DISABLE_COPY(Context); + RCLCPP_DISABLE_COPY(Context) std::unordered_map> sub_contexts_; std::mutex mutex_; diff --git a/rclcpp/include/rclcpp/contexts/default_context.hpp b/rclcpp/include/rclcpp/contexts/default_context.hpp index 757a767373..2a31da9269 100644 --- a/rclcpp/include/rclcpp/contexts/default_context.hpp +++ b/rclcpp/include/rclcpp/contexts/default_context.hpp @@ -28,7 +28,7 @@ namespace default_context class DefaultContext : public rclcpp::context::Context { public: - RCLCPP_SMART_PTR_DEFINITIONS(DefaultContext); + RCLCPP_SMART_PTR_DEFINITIONS(DefaultContext) RCLCPP_PUBLIC DefaultContext(); diff --git a/rclcpp/include/rclcpp/event.hpp b/rclcpp/include/rclcpp/event.hpp index 0de55ef31f..0ddb3f40f6 100644 --- a/rclcpp/include/rclcpp/event.hpp +++ b/rclcpp/include/rclcpp/event.hpp @@ -29,7 +29,7 @@ namespace event class Event { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Event); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Event) RCLCPP_PUBLIC Event(); @@ -47,7 +47,7 @@ class Event check_and_clear(); private: - RCLCPP_DISABLE_COPY(Event); + RCLCPP_DISABLE_COPY(Event) std::atomic_bool state_; }; diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 14cb8e3201..697c3c16ba 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -88,7 +88,7 @@ static inline ExecutorArgs create_default_executor_arguments() class Executor { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Executor) /// Default constructor. // \param[in] ms The memory strategy to be used with this executor. @@ -316,7 +316,7 @@ class Executor memory_strategy::MemoryStrategy::SharedPtr memory_strategy_; private: - RCLCPP_DISABLE_COPY(Executor); + RCLCPP_DISABLE_COPY(Executor) std::vector> weak_nodes_; }; diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index 6d35496965..d175d6f6ee 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -34,7 +34,7 @@ namespace multi_threaded_executor class MultiThreadedExecutor : public executor::Executor { public: - RCLCPP_SMART_PTR_DEFINITIONS(MultiThreadedExecutor); + RCLCPP_SMART_PTR_DEFINITIONS(MultiThreadedExecutor) RCLCPP_PUBLIC MultiThreadedExecutor( @@ -57,7 +57,7 @@ class MultiThreadedExecutor : public executor::Executor run(size_t this_thread_number); private: - RCLCPP_DISABLE_COPY(MultiThreadedExecutor); + RCLCPP_DISABLE_COPY(MultiThreadedExecutor) std::mutex wait_mutex_; size_t number_of_threads_; diff --git a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp index 4981d03cc5..f70e18f26e 100644 --- a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp @@ -42,7 +42,7 @@ namespace single_threaded_executor class SingleThreadedExecutor : public executor::Executor { public: - RCLCPP_SMART_PTR_DEFINITIONS(SingleThreadedExecutor); + RCLCPP_SMART_PTR_DEFINITIONS(SingleThreadedExecutor) /// Default constructor. See the default constructor for Executor. RCLCPP_PUBLIC @@ -61,7 +61,7 @@ class SingleThreadedExecutor : public executor::Executor spin(); private: - RCLCPP_DISABLE_COPY(SingleThreadedExecutor); + RCLCPP_DISABLE_COPY(SingleThreadedExecutor) }; } // namespace single_threaded_executor diff --git a/rclcpp/include/rclcpp/graph_listener.hpp b/rclcpp/include/rclcpp/graph_listener.hpp index 8927b99d85..c40c0fee2e 100644 --- a/rclcpp/include/rclcpp/graph_listener.hpp +++ b/rclcpp/include/rclcpp/graph_listener.hpp @@ -152,7 +152,7 @@ class GraphListener : public std::enable_shared_from_this run_loop(); private: - RCLCPP_DISABLE_COPY(GraphListener); + RCLCPP_DISABLE_COPY(GraphListener) std::thread listener_thread_; bool is_started_; diff --git a/rclcpp/include/rclcpp/intra_process_manager.hpp b/rclcpp/include/rclcpp/intra_process_manager.hpp index 0edec727b0..89b52817e0 100644 --- a/rclcpp/include/rclcpp/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager.hpp @@ -120,10 +120,10 @@ namespace intra_process_manager class IntraProcessManager { private: - RCLCPP_DISABLE_COPY(IntraProcessManager); + RCLCPP_DISABLE_COPY(IntraProcessManager) public: - RCLCPP_SMART_PTR_DEFINITIONS(IntraProcessManager); + RCLCPP_SMART_PTR_DEFINITIONS(IntraProcessManager) RCLCPP_PUBLIC explicit IntraProcessManager( diff --git a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp index 9cd5951844..f22d79d8b1 100644 --- a/rclcpp/include/rclcpp/intra_process_manager_impl.hpp +++ b/rclcpp/include/rclcpp/intra_process_manager_impl.hpp @@ -41,7 +41,7 @@ namespace intra_process_manager class IntraProcessManagerImplBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(IntraProcessManagerImplBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(IntraProcessManagerImplBase) IntraProcessManagerImplBase() = default; ~IntraProcessManagerImplBase() = default; @@ -78,7 +78,7 @@ class IntraProcessManagerImplBase matches_any_publishers(const rmw_gid_t * id) const = 0; private: - RCLCPP_DISABLE_COPY(IntraProcessManagerImplBase); + RCLCPP_DISABLE_COPY(IntraProcessManagerImplBase) }; template> @@ -242,7 +242,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase } private: - RCLCPP_DISABLE_COPY(IntraProcessManagerImpl); + RCLCPP_DISABLE_COPY(IntraProcessManagerImpl) template using RebindAlloc = typename std::allocator_traits::template rebind_alloc; @@ -262,7 +262,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase struct PublisherInfo { - RCLCPP_DISABLE_COPY(PublisherInfo); + RCLCPP_DISABLE_COPY(PublisherInfo) PublisherInfo() = default; diff --git a/rclcpp/include/rclcpp/mapped_ring_buffer.hpp b/rclcpp/include/rclcpp/mapped_ring_buffer.hpp index 54e56508cb..5965f33a32 100644 --- a/rclcpp/include/rclcpp/mapped_ring_buffer.hpp +++ b/rclcpp/include/rclcpp/mapped_ring_buffer.hpp @@ -35,7 +35,7 @@ namespace mapped_ring_buffer class RCLCPP_PUBLIC MappedRingBufferBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBufferBase); + RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBufferBase) }; /// Ring buffer container of unique_ptr's of T, which can be accessed by a key. @@ -58,7 +58,7 @@ template> class MappedRingBuffer : public MappedRingBufferBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBuffer); + RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBuffer) using ElemAllocTraits = allocator::AllocRebind; using ElemAlloc = typename ElemAllocTraits::allocator_type; using ElemDeleter = allocator::Deleter; @@ -207,7 +207,7 @@ class MappedRingBuffer : public MappedRingBufferBase } private: - RCLCPP_DISABLE_COPY(MappedRingBuffer); + RCLCPP_DISABLE_COPY(MappedRingBuffer) struct element { diff --git a/rclcpp/include/rclcpp/memory_strategy.hpp b/rclcpp/include/rclcpp/memory_strategy.hpp index 30f91cfd1d..cfb905bf78 100644 --- a/rclcpp/include/rclcpp/memory_strategy.hpp +++ b/rclcpp/include/rclcpp/memory_strategy.hpp @@ -40,7 +40,7 @@ namespace memory_strategy class RCLCPP_PUBLIC MemoryStrategy { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(MemoryStrategy); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(MemoryStrategy) using WeakNodeVector = std::vector>; virtual bool collect_entities(const WeakNodeVector & weak_nodes) = 0; diff --git a/rclcpp/include/rclcpp/message_memory_strategy.hpp b/rclcpp/include/rclcpp/message_memory_strategy.hpp index fc764afb5b..bcf8a7898d 100644 --- a/rclcpp/include/rclcpp/message_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/message_memory_strategy.hpp @@ -33,7 +33,7 @@ template> class MessageMemoryStrategy { public: - RCLCPP_SMART_PTR_DEFINITIONS(MessageMemoryStrategy); + RCLCPP_SMART_PTR_DEFINITIONS(MessageMemoryStrategy) using MessageAllocTraits = allocator::AllocRebind; using MessageAlloc = typename MessageAllocTraits::allocator_type; diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 78bb01ae79..003391aa58 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -80,7 +80,7 @@ class EventNotRegisteredError : public std::runtime_error class Node : public std::enable_shared_from_this { public: - RCLCPP_SMART_PTR_DEFINITIONS(Node); + RCLCPP_SMART_PTR_DEFINITIONS(Node) /// Create a new node with the specified name. /** @@ -380,7 +380,7 @@ class Node : public std::enable_shared_from_this std::atomic_bool has_executor; private: - RCLCPP_DISABLE_COPY(Node); + RCLCPP_DISABLE_COPY(Node) RCLCPP_PUBLIC bool diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 8751a83ce8..180d4aae89 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -44,7 +44,7 @@ namespace parameter_client class AsyncParametersClient { public: - RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient); + RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) RCLCPP_PUBLIC AsyncParametersClient( @@ -118,7 +118,7 @@ class AsyncParametersClient class SyncParametersClient { public: - RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient); + RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient) RCLCPP_PUBLIC explicit SyncParametersClient( diff --git a/rclcpp/include/rclcpp/parameter_service.hpp b/rclcpp/include/rclcpp/parameter_service.hpp index e5432d3ced..e5dd58560e 100644 --- a/rclcpp/include/rclcpp/parameter_service.hpp +++ b/rclcpp/include/rclcpp/parameter_service.hpp @@ -38,7 +38,7 @@ namespace parameter_service class ParameterService { public: - RCLCPP_SMART_PTR_DEFINITIONS(ParameterService); + RCLCPP_SMART_PTR_DEFINITIONS(ParameterService) RCLCPP_PUBLIC explicit ParameterService( diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 3904d49319..f03b26d92e 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -51,7 +51,7 @@ namespace publisher class PublisherBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase); + RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase) /// Default constructor. /** * Typically, a publisher is not created through this method, but instead is created through a @@ -151,7 +151,7 @@ class Publisher : public PublisherBase using MessageDeleter = allocator::Deleter; using MessageUniquePtr = std::unique_ptr; - RCLCPP_SMART_PTR_DEFINITIONS(Publisher); + RCLCPP_SMART_PTR_DEFINITIONS(Publisher) Publisher( std::shared_ptr node_handle, diff --git a/rclcpp/include/rclcpp/rate.hpp b/rclcpp/include/rclcpp/rate.hpp index 713b4a33c5..9587c91e1f 100644 --- a/rclcpp/include/rclcpp/rate.hpp +++ b/rclcpp/include/rclcpp/rate.hpp @@ -31,7 +31,7 @@ namespace rate class RateBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(RateBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(RateBase) virtual bool sleep() = 0; virtual bool is_steady() const = 0; @@ -46,7 +46,7 @@ template class GenericRate : public RateBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(GenericRate); + RCLCPP_SMART_PTR_DEFINITIONS(GenericRate) explicit GenericRate(double rate) : GenericRate( @@ -106,7 +106,7 @@ class GenericRate : public RateBase } private: - RCLCPP_DISABLE_COPY(GenericRate); + RCLCPP_DISABLE_COPY(GenericRate) std::chrono::nanoseconds period_; using ClockDurationNano = std::chrono::duration; diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 704ec40bd3..d8719a7170 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -39,7 +39,7 @@ namespace service class ServiceBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ServiceBase) RCLCPP_PUBLIC ServiceBase( @@ -64,7 +64,7 @@ class ServiceBase std::shared_ptr request) = 0; protected: - RCLCPP_DISABLE_COPY(ServiceBase); + RCLCPP_DISABLE_COPY(ServiceBase) std::shared_ptr node_handle_; @@ -88,7 +88,7 @@ class Service : public ServiceBase const std::shared_ptr, const std::shared_ptr, std::shared_ptr)>; - RCLCPP_SMART_PTR_DEFINITIONS(Service); + RCLCPP_SMART_PTR_DEFINITIONS(Service) Service( std::shared_ptr node_handle, @@ -158,7 +158,7 @@ class Service : public ServiceBase } private: - RCLCPP_DISABLE_COPY(Service); + RCLCPP_DISABLE_COPY(Service) AnyServiceCallback any_callback_; }; diff --git a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp index 39bdde39c4..465fa29b60 100644 --- a/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp @@ -44,7 +44,7 @@ template> class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy { public: - RCLCPP_SMART_PTR_DEFINITIONS(AllocatorMemoryStrategy); + RCLCPP_SMART_PTR_DEFINITIONS(AllocatorMemoryStrategy) using ExecAllocTraits = allocator::AllocRebind; using ExecAlloc = typename ExecAllocTraits::allocator_type; diff --git a/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp b/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp index 38d62d1b25..0eb1d54b92 100644 --- a/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp +++ b/rclcpp/include/rclcpp/strategies/message_pool_memory_strategy.hpp @@ -46,7 +46,7 @@ class MessagePoolMemoryStrategy : public message_memory_strategy::MessageMemoryStrategy { public: - RCLCPP_SMART_PTR_DEFINITIONS(MessagePoolMemoryStrategy); + RCLCPP_SMART_PTR_DEFINITIONS(MessagePoolMemoryStrategy) /// Default constructor MessagePoolMemoryStrategy() diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 88b543751d..c1002dd41d 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -51,7 +51,7 @@ namespace subscription class SubscriptionBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(SubscriptionBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(SubscriptionBase) /// Default constructor. /** @@ -109,7 +109,7 @@ class SubscriptionBase std::shared_ptr node_handle_; private: - RCLCPP_DISABLE_COPY(SubscriptionBase); + RCLCPP_DISABLE_COPY(SubscriptionBase) std::string topic_name_; bool ignore_local_publications_; }; @@ -128,7 +128,7 @@ class Subscription : public SubscriptionBase using MessageDeleter = allocator::Deleter; using MessageUniquePtr = std::unique_ptr; - RCLCPP_SMART_PTR_DEFINITIONS(Subscription); + RCLCPP_SMART_PTR_DEFINITIONS(Subscription) /// Default constructor. /** @@ -271,7 +271,7 @@ class Subscription : public SubscriptionBase return &intra_process_subscription_handle_; } - RCLCPP_DISABLE_COPY(Subscription); + RCLCPP_DISABLE_COPY(Subscription) AnySubscriptionCallback any_callback_; typename message_memory_strategy::MessageMemoryStrategy::SharedPtr diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index ad09dea11c..5d6290531c 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -43,7 +43,7 @@ namespace timer class TimerBase { public: - RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase); + RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase) RCLCPP_PUBLIC explicit TimerBase(std::chrono::nanoseconds period); @@ -103,7 +103,7 @@ template< class GenericTimer : public TimerBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(GenericTimer); + RCLCPP_SMART_PTR_DEFINITIONS(GenericTimer) /// Default constructor. /** @@ -170,7 +170,7 @@ class GenericTimer : public TimerBase } protected: - RCLCPP_DISABLE_COPY(GenericTimer); + RCLCPP_DISABLE_COPY(GenericTimer) FunctorT callback_; }; diff --git a/rclcpp/test/test_intra_process_manager.cpp b/rclcpp/test/test_intra_process_manager.cpp index a39f36a1c4..bc26543842 100644 --- a/rclcpp/test/test_intra_process_manager.cpp +++ b/rclcpp/test/test_intra_process_manager.cpp @@ -31,7 +31,7 @@ namespace mock class PublisherBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase); + RCLCPP_SMART_PTR_DEFINITIONS(PublisherBase) PublisherBase() : mock_topic_name(""), mock_queue_size(0) {} @@ -66,7 +66,7 @@ class Publisher : public PublisherBase using MessageUniquePtr = std::unique_ptr; std::shared_ptr allocator_; - RCLCPP_SMART_PTR_DEFINITIONS(Publisher); + RCLCPP_SMART_PTR_DEFINITIONS(Publisher) Publisher() { @@ -93,7 +93,7 @@ namespace mock class SubscriptionBase { public: - RCLCPP_SMART_PTR_DEFINITIONS(SubscriptionBase); + RCLCPP_SMART_PTR_DEFINITIONS(SubscriptionBase) SubscriptionBase() : mock_topic_name(""), mock_queue_size(0) {}