Skip to content

Commit

Permalink
Back out Waitable and GraphEvent-related changes
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <[email protected]>
  • Loading branch information
Emerson Knapp committed Mar 25, 2019
1 parent 71ba5f3 commit 7d345e1
Show file tree
Hide file tree
Showing 34 changed files with 501 additions and 496 deletions.
12 changes: 7 additions & 5 deletions rclcpp/include/rclcpp/any_executable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,18 @@ namespace executor
struct AnyExecutable
{
RCLCPP_PUBLIC
AnyExecutable() = default;
AnyExecutable();

RCLCPP_PUBLIC
virtual ~AnyExecutable();

bool
has_timer() const;

// Only one of the following pointers will be set.
rclcpp::SubscriptionBase::SharedPtr subscription;
rclcpp::SubscriptionBase::SharedPtr subscription_intra_process;
rclcpp::TimerBase::SharedPtr timer;
rclcpp::ServiceBase::SharedPtr service;
rclcpp::ClientBase::SharedPtr client;
rclcpp::Waitable::SharedPtr waitable;

// These are used to keep the scope on the containing items
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base;
Expand Down
24 changes: 1 addition & 23 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
#include "rcl/error_handling.h"
#include "rcl/wait.h"

#include "rclcpp/waitable.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/function_traits.hpp"
#include "rclcpp/macros.hpp"
Expand All @@ -50,7 +49,7 @@ namespace node_interfaces
class NodeBaseInterface;
} // namespace node_interfaces

class ClientBase : public Waitable
class ClientBase
{
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientBase)
Expand Down Expand Up @@ -83,26 +82,6 @@ class ClientBase : public Waitable
std::shared_ptr<const rcl_event_t>
get_event_handle() const;

RCLCPP_PUBLIC
size_t
get_number_of_ready_clients() override;

RCLCPP_PUBLIC
size_t
get_number_of_ready_events() override;

RCLCPP_PUBLIC
bool
add_to_wait_set(rcl_wait_set_t * wait_set) override;

RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;

RCLCPP_PUBLIC
void
execute() override;

RCLCPP_PUBLIC
bool
service_is_ready() const;
Expand Down Expand Up @@ -182,7 +161,6 @@ class Client : public ClientBase
using rosidl_typesupport_cpp::get_service_type_support_handle;
auto service_type_support_handle =
get_service_type_support_handle<ServiceT>();

rcl_ret_t ret = rcl_client_init(
this->get_client_handle().get(),
this->get_rcl_node_handle(),
Expand Down
5 changes: 2 additions & 3 deletions rclcpp/include/rclcpp/create_service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,10 @@ create_service(
service_options.qos = qos_profile;

auto serv = Service<ServiceT>::make_shared(
node_base->get_shared_rcl_node_handle(), service_name, service_options, any_service_callback);
node_base->get_shared_rcl_node_handle(),
service_name, any_service_callback, service_options);
auto serv_base_ptr = std::dynamic_pointer_cast<ServiceBase>(serv);

node_services->add_service(serv_base_ptr, group);

return serv;
}

Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,18 +42,19 @@ create_subscription(
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
bool use_intra_process_comms,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<CallbackMessageT,
AllocatorT>::SharedPtr msg_mem_strat,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT, AllocatorT>::SharedPtr
msg_mem_strat,
typename std::shared_ptr<AllocatorT> allocator)
{
auto subscription_options = rcl_subscription_get_default_options();
subscription_options.qos = qos_profile;
subscription_options.ignore_local_publications = ignore_local_publications;

auto factory = rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT,
CallbackMessageT, SubscriptionT>(
auto factory = rclcpp::create_subscription_factory
<MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT>(
std::forward<CallbackT>(callback),
callbacks,
callbacks,
msg_mem_strat,
allocator);

Expand All @@ -63,7 +64,6 @@ create_subscription(
subscription_options,
use_intra_process_comms);
node_topics->add_subscription(sub, group);

return std::dynamic_pointer_cast<SubscriptionT>(sub);
}

Expand Down
22 changes: 22 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -298,6 +298,28 @@ class Executor
void
execute_any_executable(AnyExecutable & any_exec);

RCLCPP_PUBLIC
static void
execute_subscription(
rclcpp::SubscriptionBase::SharedPtr subscription);

RCLCPP_PUBLIC
static void
execute_intra_process_subscription(
rclcpp::SubscriptionBase::SharedPtr subscription);

RCLCPP_PUBLIC
static void
execute_timer(rclcpp::TimerBase::SharedPtr timer);

RCLCPP_PUBLIC
static void
execute_service(rclcpp::ServiceBase::SharedPtr service);

RCLCPP_PUBLIC
static void
execute_client(rclcpp::ClientBase::SharedPtr client);

RCLCPP_PUBLIC
void
wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class MultiThreadedExecutor : public executor::Executor
bool yield_before_execute_;

std::mutex scheduled_timers_mutex_;
std::set<Waitable::SharedPtr> scheduled_timers_;
std::set<TimerBase::SharedPtr> scheduled_timers_;
};

} // namespace executors
Expand Down
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/memory_strategy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,21 @@ class RCLCPP_PUBLIC MemoryStrategy

virtual void remove_guard_condition(const rcl_guard_condition_t * guard_condition) = 0;

virtual void
get_next_subscription(
rclcpp::executor::AnyExecutable & any_exec,
const WeakNodeVector & weak_nodes) = 0;

virtual void
get_next_service(
rclcpp::executor::AnyExecutable & any_exec,
const WeakNodeVector & weak_nodes) = 0;

virtual void
get_next_client(
rclcpp::executor::AnyExecutable & any_exec,
const WeakNodeVector & weak_nodes) = 0;

virtual void
get_next_waitable(
rclcpp::executor::AnyExecutable & any_exec,
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -366,17 +366,17 @@ class Node : public std::enable_shared_from_this<Node>
count_subscribers(const std::string & topic_name) const;

/// Return a graph event, which will be set anytime a graph change occurs.
/* The graph GraphEvent object is a loan which must be returned.
* The GraphEvent object is scoped and therefore to return the loan just let it go
/* The graph Event object is a loan which must be returned.
* The Event object is scoped and therefore to return the loan just let it go
* out of scope.
*/
RCLCPP_PUBLIC
rclcpp::GraphEvent::SharedPtr
rclcpp::Event::SharedPtr
get_graph_event();

/// Wait for a graph event to occur by waiting on an GraphEvent to become set.
/// Wait for a graph event to occur by waiting on an Event to become set.
/**
* The given GraphEvent must be acquire through the get_graph_event() method.
* The given Event must be acquire through the get_graph_event() method.
*
* \throws InvalidEventError if the given event is nullptr
* \throws EventNotRegisteredError if the given event was not acquired with
Expand All @@ -385,7 +385,7 @@ class Node : public std::enable_shared_from_this<Node>
RCLCPP_PUBLIC
void
wait_for_graph_change(
rclcpp::GraphEvent::SharedPtr event,
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout);

RCLCPP_PUBLIC
Expand Down
7 changes: 5 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,11 @@ Node::create_publisher(
allocator);
}

template<typename MessageT, typename CallbackT, typename Alloc, typename SubscriptionT>
template<
typename MessageT,
typename CallbackT,
typename Alloc,
typename SubscriptionT>
std::shared_ptr<SubscriptionT>
Node::create_subscription(
const std::string & topic_name,
Expand Down Expand Up @@ -157,7 +161,6 @@ Node::create_client(

auto cli_base_ptr = std::dynamic_pointer_cast<ClientBase>(cli);
node_services_->add_client(cli_base_ptr, group);

return cli;
}

Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/node_interfaces/node_graph.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@

#include "rcl/guard_condition.h"

#include "rclcpp/graph_event.hpp"
#include "rclcpp/event.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
Expand Down Expand Up @@ -102,14 +102,14 @@ class NodeGraph : public NodeGraphInterface

RCLCPP_PUBLIC
virtual
rclcpp::GraphEvent::SharedPtr
rclcpp::Event::SharedPtr
get_graph_event();

RCLCPP_PUBLIC
virtual
void
wait_for_graph_change(
rclcpp::GraphEvent::SharedPtr event,
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout);

RCLCPP_PUBLIC
Expand All @@ -133,7 +133,7 @@ class NodeGraph : public NodeGraphInterface
/// For notifying waiting threads (wait_for_graph_change()) on changes (notify_graph_change()).
std::condition_variable graph_cv_;
/// Weak references to graph events out on loan.
std::vector<rclcpp::GraphEvent::WeakPtr> graph_events_;
std::vector<rclcpp::Event::WeakPtr> graph_events_;
/// Number of graph events out on loan, used to determine if the graph should be monitored.
/** graph_users_count_ is atomic so that it can be accessed without acquiring the graph_mutex_ */
std::atomic_size_t graph_users_count_;
Expand Down
16 changes: 8 additions & 8 deletions rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include "rcl/guard_condition.h"

#include "rclcpp/graph_event.hpp"
#include "rclcpp/event.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"

Expand Down Expand Up @@ -99,7 +99,7 @@ class NodeGraphInterface
/**
* Affects threads waiting on the notify guard condition, see:
* get_notify_guard_condition(), as well as the threads waiting on graph
* changes using a graph GraphEvent, see: wait_for_graph_change().
* changes using a graph Event, see: wait_for_graph_change().
*
* This is typically only used by the rclcpp::graph_listener::GraphListener.
*
Expand All @@ -118,18 +118,18 @@ class NodeGraphInterface

/// Return a graph event, which will be set anytime a graph change occurs.
/**
* The graph GraphEvent object is a loan which must be returned.
* The GraphEvent object is scoped and therefore to return the load just let it go
* The graph Event object is a loan which must be returned.
* The Event object is scoped and therefore to return the load just let it go
* out of scope.
*/
RCLCPP_PUBLIC
virtual
rclcpp::GraphEvent::SharedPtr
rclcpp::Event::SharedPtr
get_graph_event() = 0;

/// Wait for a graph event to occur by waiting on an GraphEvent to become set.
/// Wait for a graph event to occur by waiting on an Event to become set.
/**
* The given GraphEvent must be acquire through the get_graph_event() method.
* The given Event must be acquire through the get_graph_event() method.
*
* \throws InvalidEventError if the given event is nullptr
* \throws EventNotRegisteredError if the given event was not acquired with
Expand All @@ -139,7 +139,7 @@ class NodeGraphInterface
virtual
void
wait_for_graph_change(
rclcpp::GraphEvent::SharedPtr event,
rclcpp::Event::SharedPtr event,
std::chrono::nanoseconds timeout) = 0;

/// Return the number of on loan graph events, see get_graph_event().
Expand Down
13 changes: 6 additions & 7 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"


namespace rclcpp
{

Expand Down Expand Up @@ -188,17 +187,16 @@ class PublisherBase
const rcl_publisher_options_t & intra_process_options);

protected:
using IntraProcessManagerWeakPtr =
std::weak_ptr<rclcpp::intra_process_manager::IntraProcessManager>;

std::shared_ptr<rcl_node_t> rcl_node_handle_;

rcl_publisher_t publisher_handle_ = rcl_get_zero_initialized_publisher();
rcl_publisher_t intra_process_publisher_handle_ = rcl_get_zero_initialized_publisher();

std::vector<std::shared_ptr<QOSEventBase>> event_handles_;

std::vector<std::shared_ptr<QOSEventBase>> event_handles_;

using IntraProcessManagerWeakPtr =
std::weak_ptr<rclcpp::intra_process_manager::IntraProcessManager>;
bool use_intra_process_;
rcl_publisher_t intra_process_publisher_handle_ = rcl_get_zero_initialized_publisher();
IntraProcessManagerWeakPtr weak_ipm_;
uint64_t intra_process_publisher_id_;
StoreMessageCallbackT store_intra_process_message_;
Expand Down Expand Up @@ -401,6 +399,7 @@ class Publisher : public PublisherBase
}

std::shared_ptr<MessageAlloc> message_allocator_;

MessageDeleter message_deleter_;
};

Expand Down
5 changes: 3 additions & 2 deletions rclcpp/include/rclcpp/qos_event.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ struct QOSLivelinessEventInfo
};

LivelinessEventType event_type;
void * other_info;
rmw_liveliness_lost_t * other_info;
};

struct QOSLifespanEventInfo
Expand Down Expand Up @@ -141,7 +141,8 @@ class QOSEvent : public QOSEventBase
{
EventCallbackInfoT callback_info;

rcl_ret_t ret = rcl_take_event(&event_handle_, callback_info.other_info);
rcl_ret_t ret = RCL_RET_ERROR;
// rcl_ret_t ret = rcl_take_event(&event_handle_, callback_info.other_info);
if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rclcpp",
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@
* - Graph Events (a waitable event object that wakes up when the graph changes):
* - rclcpp::Node::get_graph_event()
* - rclcpp::Node::wait_for_graph_change()
* - rclcpp::GraphEvent
* - rclcpp::Event
* - List topic names and types:
* - rclcpp::Node::get_topic_names_and_types()
* - Get the number of publishers or subscribers on a topic:
Expand Down
Loading

0 comments on commit 7d345e1

Please sign in to comment.