Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace executor

struct AnyExecutable
{
RCLCPP_SMART_PTR_DEFINITIONS(AnyExecutable);
RCLCPP_SMART_PTR_DEFINITIONS(AnyExecutable)

RCLCPP_PUBLIC
AnyExecutable();
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -79,7 +79,7 @@ class CallbackGroup
type() const;

private:
RCLCPP_DISABLE_COPY(CallbackGroup);
RCLCPP_DISABLE_COPY(CallbackGroup)

RCLCPP_PUBLIC
void
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -88,7 +88,7 @@ class ClientBase
std::shared_ptr<rmw_request_id_t> request_header, std::shared_ptr<void> response) = 0;

protected:
RCLCPP_DISABLE_COPY(ClientBase);
RCLCPP_DISABLE_COPY(ClientBase)

RCLCPP_PUBLIC
bool
Expand Down Expand Up @@ -124,7 +124,7 @@ class Client : public ClientBase
using CallbackType = std::function<void(SharedFuture)>;
using CallbackWithRequestType = std::function<void(SharedFutureWithRequest)>;

RCLCPP_SMART_PTR_DEFINITIONS(Client);
RCLCPP_SMART_PTR_DEFINITIONS(Client)

Client(
std::shared_ptr<rclcpp::node::Node> parent_node,
Expand Down Expand Up @@ -250,7 +250,7 @@ class Client : public ClientBase
}

private:
RCLCPP_DISABLE_COPY(Client);
RCLCPP_DISABLE_COPY(Client)

std::map<int64_t, std::tuple<SharedPromise, CallbackType, SharedFuture>> pending_requests_;
std::mutex pending_requests_mutex_;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace context
class Context
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Context);
RCLCPP_SMART_PTR_DEFINITIONS(Context)

RCLCPP_PUBLIC
Context();
Expand Down Expand Up @@ -68,7 +68,7 @@ class Context
}

private:
RCLCPP_DISABLE_COPY(Context);
RCLCPP_DISABLE_COPY(Context)

std::unordered_map<std::type_index, std::shared_ptr<void>> sub_contexts_;
std::mutex mutex_;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/contexts/default_context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/event.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand All @@ -47,7 +47,7 @@ class Event
check_and_clear();

private:
RCLCPP_DISABLE_COPY(Event);
RCLCPP_DISABLE_COPY(Event)

std::atomic_bool state_;
};
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -316,7 +316,7 @@ class Executor
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_;

private:
RCLCPP_DISABLE_COPY(Executor);
RCLCPP_DISABLE_COPY(Executor)

std::vector<std::weak_ptr<rclcpp::node::Node>> weak_nodes_;
};
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand All @@ -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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -61,7 +61,7 @@ class SingleThreadedExecutor : public executor::Executor
spin();

private:
RCLCPP_DISABLE_COPY(SingleThreadedExecutor);
RCLCPP_DISABLE_COPY(SingleThreadedExecutor)
};

} // namespace single_threaded_executor
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/graph_listener.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
run_loop();

private:
RCLCPP_DISABLE_COPY(GraphListener);
RCLCPP_DISABLE_COPY(GraphListener)

std::thread listener_thread_;
bool is_started_;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/intra_process_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/intra_process_manager_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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<typename Allocator = std::allocator<void>>
Expand Down Expand Up @@ -242,7 +242,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase
}

private:
RCLCPP_DISABLE_COPY(IntraProcessManagerImpl);
RCLCPP_DISABLE_COPY(IntraProcessManagerImpl)

template<typename T>
using RebindAlloc = typename std::allocator_traits<Allocator>::template rebind_alloc<T>;
Expand All @@ -262,7 +262,7 @@ class IntraProcessManagerImpl : public IntraProcessManagerImplBase

struct PublisherInfo
{
RCLCPP_DISABLE_COPY(PublisherInfo);
RCLCPP_DISABLE_COPY(PublisherInfo)

PublisherInfo() = default;

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/mapped_ring_buffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -58,7 +58,7 @@ template<typename T, typename Alloc = std::allocator<void>>
class MappedRingBuffer : public MappedRingBufferBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBuffer<T, Alloc>);
RCLCPP_SMART_PTR_DEFINITIONS(MappedRingBuffer<T, Alloc>)
using ElemAllocTraits = allocator::AllocRebind<T, Alloc>;
using ElemAlloc = typename ElemAllocTraits::allocator_type;
using ElemDeleter = allocator::Deleter<ElemAlloc, T>;
Expand Down Expand Up @@ -207,7 +207,7 @@ class MappedRingBuffer : public MappedRingBufferBase
}

private:
RCLCPP_DISABLE_COPY(MappedRingBuffer<T, Alloc>);
RCLCPP_DISABLE_COPY(MappedRingBuffer<T, Alloc>)

struct element
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::weak_ptr<rclcpp::node::Node>>;

virtual bool collect_entities(const WeakNodeVector & weak_nodes) = 0;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/message_memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ template<typename MessageT, typename Alloc = std::allocator<void>>
class MessageMemoryStrategy
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(MessageMemoryStrategy);
RCLCPP_SMART_PTR_DEFINITIONS(MessageMemoryStrategy)

using MessageAllocTraits = allocator::AllocRebind<MessageT, Alloc>;
using MessageAlloc = typename MessageAllocTraits::allocator_type;
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class EventNotRegisteredError : public std::runtime_error
class Node : public std::enable_shared_from_this<Node>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Node);
RCLCPP_SMART_PTR_DEFINITIONS(Node)

/// Create a new node with the specified name.
/**
Expand Down Expand Up @@ -380,7 +380,7 @@ class Node : public std::enable_shared_from_this<Node>
std::atomic_bool has_executor;

private:
RCLCPP_DISABLE_COPY(Node);
RCLCPP_DISABLE_COPY(Node)

RCLCPP_PUBLIC
bool
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace parameter_client
class AsyncParametersClient
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient);
RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient)

RCLCPP_PUBLIC
AsyncParametersClient(
Expand Down Expand Up @@ -118,7 +118,7 @@ class AsyncParametersClient
class SyncParametersClient
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient);
RCLCPP_SMART_PTR_DEFINITIONS(SyncParametersClient)

RCLCPP_PUBLIC
explicit SyncParametersClient(
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/parameter_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ namespace parameter_service
class ParameterService
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService);
RCLCPP_SMART_PTR_DEFINITIONS(ParameterService)

RCLCPP_PUBLIC
explicit ParameterService(
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -151,7 +151,7 @@ class Publisher : public PublisherBase
using MessageDeleter = allocator::Deleter<MessageAlloc, MessageT>;
using MessageUniquePtr = std::unique_ptr<MessageT, MessageDeleter>;

RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, Alloc>);
RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, Alloc>)

Publisher(
std::shared_ptr<rcl_node_t> node_handle,
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/rate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -46,7 +46,7 @@ template<class Clock = std::chrono::high_resolution_clock>
class GenericRate : public RateBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(GenericRate);
RCLCPP_SMART_PTR_DEFINITIONS(GenericRate)

explicit GenericRate(double rate)
: GenericRate<Clock>(
Expand Down Expand Up @@ -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<typename Clock::rep, std::nano>;
Expand Down
Loading