Remove unnecessary virtual keywords

Signed-off-by: Monika Idzik <monika.idzik@apex.ai>
This commit is contained in:
Monika Idzik 2019-10-16 14:40:41 +02:00
parent 3e08d9e43f
commit ef52953824
8 changed files with 44 additions and 44 deletions

View file

@ -50,87 +50,87 @@ public:
~NodeBase(); ~NodeBase();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const char * const char *
get_name() const; get_name() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const char * const char *
get_namespace() const; get_namespace() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const char * const char *
get_fully_qualified_name() const; get_fully_qualified_name() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::Context::SharedPtr rclcpp::Context::SharedPtr
get_context(); get_context();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rcl_node_t * rcl_node_t *
get_rcl_node_handle(); get_rcl_node_handle();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const rcl_node_t * const rcl_node_t *
get_rcl_node_handle() const; get_rcl_node_handle() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::shared_ptr<rcl_node_t> std::shared_ptr<rcl_node_t>
get_shared_rcl_node_handle(); get_shared_rcl_node_handle();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::shared_ptr<const rcl_node_t> std::shared_ptr<const rcl_node_t>
get_shared_rcl_node_handle() const; get_shared_rcl_node_handle() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
bool bool
assert_liveliness() const; assert_liveliness() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
create_callback_group(rclcpp::callback_group::CallbackGroupType group_type); create_callback_group(rclcpp::callback_group::CallbackGroupType group_type);
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::callback_group::CallbackGroup::SharedPtr rclcpp::callback_group::CallbackGroup::SharedPtr
get_default_callback_group(); get_default_callback_group();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
bool bool
callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group); callback_group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group);
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> & const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
get_callback_groups() const; get_callback_groups() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::atomic_bool & std::atomic_bool &
get_associated_with_executor_atomic(); get_associated_with_executor_atomic();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rcl_guard_condition_t * rcl_guard_condition_t *
get_notify_guard_condition(); get_notify_guard_condition();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::unique_lock<std::recursive_mutex> std::unique_lock<std::recursive_mutex>
acquire_notify_guard_condition_lock() const; acquire_notify_guard_condition_lock() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
bool bool
get_use_intra_process_default() const; get_use_intra_process_default() const;

View file

@ -50,7 +50,7 @@ public:
/// Get a clock which will be kept up to date by the node. /// Get a clock which will be kept up to date by the node.
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::Clock::SharedPtr rclcpp::Clock::SharedPtr
get_clock(); get_clock();

View file

@ -56,64 +56,64 @@ public:
~NodeGraph(); ~NodeGraph();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>> std::map<std::string, std::vector<std::string>>
get_topic_names_and_types(bool no_demangle = false) const; get_topic_names_and_types(bool no_demangle = false) const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::map<std::string, std::vector<std::string>> std::map<std::string, std::vector<std::string>>
get_service_names_and_types() const; get_service_names_and_types() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::vector<std::string> std::vector<std::string>
get_node_names() const; get_node_names() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
std::vector<std::pair<std::string, std::string>> std::vector<std::pair<std::string, std::string>>
get_node_names_and_namespaces() const; get_node_names_and_namespaces() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
size_t size_t
count_publishers(const std::string & topic_name) const; count_publishers(const std::string & topic_name) const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
size_t size_t
count_subscribers(const std::string & topic_name) const; count_subscribers(const std::string & topic_name) const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const rcl_guard_condition_t * const rcl_guard_condition_t *
get_graph_guard_condition() const; get_graph_guard_condition() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
notify_graph_change(); notify_graph_change();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
notify_shutdown(); notify_shutdown();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::Event::SharedPtr rclcpp::Event::SharedPtr
get_graph_event(); get_graph_event();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
wait_for_graph_change( wait_for_graph_change(
rclcpp::Event::SharedPtr event, rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout); std::chrono::nanoseconds timeout);
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
size_t size_t
count_graph_users(); count_graph_users();

View file

@ -42,12 +42,12 @@ public:
~NodeLogging(); ~NodeLogging();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
rclcpp::Logger rclcpp::Logger
get_logger() const; get_logger() const;
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
const char * const char *
get_logger_name() const; get_logger_name() const;

View file

@ -42,14 +42,14 @@ public:
~NodeServices(); ~NodeServices();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
add_client( add_client(
rclcpp::ClientBase::SharedPtr client_base_ptr, rclcpp::ClientBase::SharedPtr client_base_ptr,
rclcpp::callback_group::CallbackGroup::SharedPtr group); rclcpp::callback_group::CallbackGroup::SharedPtr group);
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
add_service( add_service(
rclcpp::ServiceBase::SharedPtr service_base_ptr, rclcpp::ServiceBase::SharedPtr service_base_ptr,

View file

@ -42,7 +42,7 @@ public:
/// Add a timer to the node. /// Add a timer to the node.
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
add_timer( add_timer(
rclcpp::TimerBase::SharedPtr timer, rclcpp::TimerBase::SharedPtr timer,

View file

@ -42,14 +42,14 @@ public:
~NodeWaitables(); ~NodeWaitables();
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
add_waitable( add_waitable(
rclcpp::Waitable::SharedPtr waitable_base_ptr, rclcpp::Waitable::SharedPtr waitable_base_ptr,
rclcpp::callback_group::CallbackGroup::SharedPtr group); rclcpp::callback_group::CallbackGroup::SharedPtr group);
RCLCPP_PUBLIC RCLCPP_PUBLIC
virtual
void void
remove_waitable( remove_waitable(
rclcpp::Waitable::SharedPtr waitable_ptr, rclcpp::Waitable::SharedPtr waitable_ptr,

View file

@ -90,7 +90,7 @@ public:
waitable_handles_.clear(); waitable_handles_.clear();
} }
virtual void remove_null_handles(rcl_wait_set_t * wait_set) void remove_null_handles(rcl_wait_set_t * wait_set)
{ {
// TODO(jacobperron): Check if wait set sizes are what we expect them to be? // TODO(jacobperron): Check if wait set sizes are what we expect them to be?
// e.g. wait_set->size_of_clients == client_handles_.size() // e.g. wait_set->size_of_clients == client_handles_.size()
@ -250,7 +250,7 @@ public:
return true; return true;
} }
virtual void void
get_next_subscription( get_next_subscription(
executor::AnyExecutable & any_exec, executor::AnyExecutable & any_exec,
const WeakNodeList & weak_nodes) const WeakNodeList & weak_nodes)
@ -285,7 +285,7 @@ public:
} }
} }
virtual void void
get_next_service( get_next_service(
executor::AnyExecutable & any_exec, executor::AnyExecutable & any_exec,
const WeakNodeList & weak_nodes) const WeakNodeList & weak_nodes)
@ -320,7 +320,7 @@ public:
} }
} }
virtual void void
get_next_client(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) get_next_client(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes)
{ {
auto it = client_handles_.begin(); auto it = client_handles_.begin();
@ -353,7 +353,7 @@ public:
} }
} }
virtual void void
get_next_timer( get_next_timer(
executor::AnyExecutable & any_exec, executor::AnyExecutable & any_exec,
const WeakNodeList & weak_nodes) const WeakNodeList & weak_nodes)
@ -388,7 +388,7 @@ public:
} }
} }
virtual void void
get_next_waitable(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes) get_next_waitable(executor::AnyExecutable & any_exec, const WeakNodeList & weak_nodes)
{ {
auto it = waitable_handles_.begin(); auto it = waitable_handles_.begin();
@ -421,7 +421,7 @@ public:
} }
} }
virtual rcl_allocator_t get_allocator() rcl_allocator_t get_allocator()
{ {
return rclcpp::allocator::get_rcl_allocator<void *, VoidAlloc>(*allocator_.get()); return rclcpp::allocator::get_rcl_allocator<void *, VoidAlloc>(*allocator_.get());
} }