Skip to content

Commit 974e845

Browse files
committed
Utilize rclcpp::WaitSet as part of the executors
Signed-off-by: Michael Carroll <[email protected]>
1 parent 6267741 commit 974e845

File tree

14 files changed

+207
-912
lines changed

14 files changed

+207
-912
lines changed

rclcpp/CMakeLists.txt

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,6 @@ set(${PROJECT_NAME}_SRCS
5959
src/rclcpp/executors/executor_notify_waitable.cpp
6060
src/rclcpp/executors/multi_threaded_executor.cpp
6161
src/rclcpp/executors/single_threaded_executor.cpp
62-
src/rclcpp/executors/static_executor_entities_collector.cpp
63-
src/rclcpp/executors/static_single_threaded_executor.cpp
6462
src/rclcpp/expand_topic_or_service_name.cpp
6563
src/rclcpp/future_return_code.cpp
6664
src/rclcpp/generic_publisher.cpp

rclcpp/include/rclcpp/executor.hpp

Lines changed: 15 additions & 154 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <cassert>
2020
#include <chrono>
2121
#include <cstdlib>
22+
#include <deque>
2223
#include <iostream>
2324
#include <list>
2425
#include <map>
@@ -29,26 +30,24 @@
2930

3031
#include "rcl/guard_condition.h"
3132
#include "rcl/wait.h"
33+
#include "rclcpp/executors/executor_notify_waitable.hpp"
3234
#include "rcpputils/scope_exit.hpp"
3335

3436
#include "rclcpp/context.hpp"
3537
#include "rclcpp/contexts/default_context.hpp"
3638
#include "rclcpp/guard_condition.hpp"
3739
#include "rclcpp/executor_options.hpp"
40+
#include "rclcpp/executors/executor_entities_collection.hpp"
41+
#include "rclcpp/executors/executor_entities_collector.hpp"
3842
#include "rclcpp/future_return_code.hpp"
39-
#include "rclcpp/memory_strategies.hpp"
40-
#include "rclcpp/memory_strategy.hpp"
4143
#include "rclcpp/node_interfaces/node_base_interface.hpp"
4244
#include "rclcpp/utilities.hpp"
4345
#include "rclcpp/visibility_control.hpp"
46+
#include "rclcpp/wait_set.hpp"
4447

4548
namespace rclcpp
4649
{
4750

48-
typedef std::map<rclcpp::CallbackGroup::WeakPtr,
49-
rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
50-
std::owner_less<rclcpp::CallbackGroup::WeakPtr>> WeakCallbackGroupsToNodesMap;
51-
5251
// Forward declaration is used in convenience method signature.
5352
class Node;
5453

@@ -402,17 +401,6 @@ class Executor
402401
void
403402
cancel();
404403

405-
/// Support dynamic switching of the memory strategy.
406-
/**
407-
* Switching the memory strategy while the executor is spinning in another threading could have
408-
* unintended consequences.
409-
* \param[in] memory_strategy Shared pointer to the memory strategy to set.
410-
* \throws std::runtime_error if memory_strategy is null
411-
*/
412-
RCLCPP_PUBLIC
413-
void
414-
set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy);
415-
416404
/// Returns true if the executor is currently spinning.
417405
/**
418406
* This function can be called asynchronously from any thread.
@@ -497,6 +485,10 @@ class Executor
497485
static void
498486
execute_client(rclcpp::ClientBase::SharedPtr client);
499487

488+
RCLCPP_PUBLIC
489+
void
490+
collect_entities();
491+
500492
/// Block until more work becomes avilable or timeout is reached.
501493
/**
502494
* Builds a set of waitable entities, which are passed to the middleware.
@@ -508,62 +500,6 @@ class Executor
508500
void
509501
wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
510502

511-
/// Find node associated with a callback group
512-
/**
513-
* \param[in] weak_groups_to_nodes map of callback groups to nodes
514-
* \param[in] group callback group to find assocatiated node
515-
* \return Pointer to associated node if found, else nullptr
516-
*/
517-
RCLCPP_PUBLIC
518-
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
519-
get_node_by_group(
520-
const WeakCallbackGroupsToNodesMap & weak_groups_to_nodes,
521-
rclcpp::CallbackGroup::SharedPtr group);
522-
523-
/// Return true if the node has been added to this executor.
524-
/**
525-
* \param[in] node_ptr a shared pointer that points to a node base interface
526-
* \param[in] weak_groups_to_nodes map to nodes to lookup
527-
* \return true if the node is associated with the executor, otherwise false
528-
*/
529-
RCLCPP_PUBLIC
530-
bool
531-
has_node(
532-
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
533-
const WeakCallbackGroupsToNodesMap & weak_groups_to_nodes) const;
534-
535-
/// Find the callback group associated with a timer
536-
/**
537-
* \param[in] timer Timer to find associated callback group
538-
* \return Pointer to callback group node if found, else nullptr
539-
*/
540-
RCLCPP_PUBLIC
541-
rclcpp::CallbackGroup::SharedPtr
542-
get_group_by_timer(rclcpp::TimerBase::SharedPtr timer);
543-
544-
/// Add a callback group to an executor
545-
/**
546-
* \see rclcpp::Executor::add_callback_group
547-
*/
548-
RCLCPP_PUBLIC
549-
virtual void
550-
add_callback_group_to_map(
551-
rclcpp::CallbackGroup::SharedPtr group_ptr,
552-
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
553-
WeakCallbackGroupsToNodesMap & weak_groups_to_nodes,
554-
bool notify = true) RCPPUTILS_TSA_REQUIRES(mutex_);
555-
556-
/// Remove a callback group from the executor.
557-
/**
558-
* \see rclcpp::Executor::remove_callback_group
559-
*/
560-
RCLCPP_PUBLIC
561-
virtual void
562-
remove_callback_group_from_map(
563-
rclcpp::CallbackGroup::SharedPtr group_ptr,
564-
WeakCallbackGroupsToNodesMap & weak_groups_to_nodes,
565-
bool notify = true) RCPPUTILS_TSA_REQUIRES(mutex_);
566-
567503
/// Check for executable in ready state and populate union structure.
568504
/**
569505
* \param[out] any_executable populated union structure of ready executable
@@ -574,33 +510,6 @@ class Executor
574510
bool
575511
get_next_ready_executable(AnyExecutable & any_executable);
576512

577-
/// Check for executable in ready state and populate union structure.
578-
/**
579-
* This is the implementation of get_next_ready_executable that takes into
580-
* account the current state of callback groups' association with nodes and
581-
* executors.
582-
*
583-
* This checks in a particular order for available work:
584-
* * Timers
585-
* * Subscriptions
586-
* * Services
587-
* * Clients
588-
* * Waitable
589-
*
590-
* If the next executable is not associated with this executor/node pair,
591-
* then this method will return false.
592-
*
593-
* \param[out] any_executable populated union structure of ready executable
594-
* \param[in] weak_groups_to_nodes mapping of callback groups to nodes
595-
* \return true if an executable was ready and any_executable was populated,
596-
* otherwise false
597-
*/
598-
RCLCPP_PUBLIC
599-
bool
600-
get_next_ready_executable_from_map(
601-
AnyExecutable & any_executable,
602-
const WeakCallbackGroupsToNodesMap & weak_groups_to_nodes);
603-
604513
/// Wait for executable in ready state and populate union structure.
605514
/**
606515
* If an executable is ready, it will return immediately, otherwise
@@ -618,21 +527,6 @@ class Executor
618527
AnyExecutable & any_executable,
619528
std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
620529

621-
/// Add all callback groups that can be automatically added from associated nodes.
622-
/**
623-
* The executor, before collecting entities, verifies if any callback group from
624-
* nodes associated with the executor, which is not already associated to an executor,
625-
* can be automatically added to this executor.
626-
* This takes care of any callback group that has been added to a node but not explicitly added
627-
* to the executor.
628-
* It is important to note that in order for the callback groups to be automatically added to an
629-
* executor through this function, the node of the callback groups needs to have been added
630-
* through the `add_node` method.
631-
*/
632-
RCLCPP_PUBLIC
633-
virtual void
634-
add_callback_groups_from_nodes_associated_to_executor() RCPPUTILS_TSA_REQUIRES(mutex_);
635-
636530
/// Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins.
637531
std::atomic_bool spinning;
638532

@@ -642,16 +536,8 @@ class Executor
642536
/// Guard condition for signaling the rmw layer to wake up for system shutdown.
643537
std::shared_ptr<rclcpp::GuardCondition> shutdown_guard_condition_;
644538

645-
/// Wait set for managing entities that the rmw layer waits on.
646-
rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set();
647-
648-
// Mutex to protect the subsequent memory_strategy_.
649539
mutable std::mutex mutex_;
650540

651-
/// The memory strategy: an interface for handling user-defined memory allocation strategies.
652-
memory_strategy::MemoryStrategy::SharedPtr
653-
memory_strategy_ RCPPUTILS_TSA_PT_GUARDED_BY(mutex_);
654-
655541
/// The context associated with this executor.
656542
std::shared_ptr<rclcpp::Context> context_;
657543

@@ -661,39 +547,14 @@ class Executor
661547
virtual void
662548
spin_once_impl(std::chrono::nanoseconds timeout);
663549

664-
typedef std::map<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
665-
const rclcpp::GuardCondition *,
666-
std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>
667-
WeakNodesToGuardConditionsMap;
668-
669-
typedef std::map<rclcpp::CallbackGroup::WeakPtr,
670-
const rclcpp::GuardCondition *,
671-
std::owner_less<rclcpp::CallbackGroup::WeakPtr>>
672-
WeakCallbackGroupsToGuardConditionsMap;
673-
674-
/// maps nodes to guard conditions
675-
WeakNodesToGuardConditionsMap
676-
weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
677-
678-
/// maps callback groups to guard conditions
679-
WeakCallbackGroupsToGuardConditionsMap
680-
weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
681-
682-
/// maps callback groups associated to nodes
683-
WeakCallbackGroupsToNodesMap
684-
weak_groups_associated_with_executor_to_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
685-
686-
/// maps callback groups to nodes associated with executor
687-
WeakCallbackGroupsToNodesMap
688-
weak_groups_to_nodes_associated_with_executor_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
550+
std::shared_ptr<rclcpp::executors::ExecutorNotifyWaitable> notify_waitable_;
551+
rclcpp::executors::ExecutorEntitiesCollector collector_;
689552

690-
/// maps all callback groups to nodes
691-
WeakCallbackGroupsToNodesMap
692-
weak_groups_to_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
553+
rclcpp::executors::ExecutorEntitiesCollection current_collection_;
554+
std::shared_ptr<rclcpp::executors::ExecutorNotifyWaitable> current_notify_waitable_;
693555

694-
/// nodes that are associated with the executor
695-
std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>
696-
weak_nodes_ RCPPUTILS_TSA_GUARDED_BY(mutex_);
556+
std::shared_ptr<rclcpp::WaitSet> wait_set_;
557+
std::deque<rclcpp::AnyExecutable> ready_executables_;
697558

698559
/// shutdown callback handle registered to Context
699560
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_;

rclcpp/include/rclcpp/executors.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020

2121
#include "rclcpp/executors/multi_threaded_executor.hpp"
2222
#include "rclcpp/executors/single_threaded_executor.hpp"
23-
#include "rclcpp/executors/static_single_threaded_executor.hpp"
2423
#include "rclcpp/node.hpp"
2524
#include "rclcpp/utilities.hpp"
2625
#include "rclcpp/visibility_control.hpp"

rclcpp/include/rclcpp/wait_set_policies/detail/storage_policy_common.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef RCLCPP__WAIT_SET_POLICIES__DETAIL__STORAGE_POLICY_COMMON_HPP_
1616
#define RCLCPP__WAIT_SET_POLICIES__DETAIL__STORAGE_POLICY_COMMON_HPP_
1717

18+
#include <iostream>
1819
#include <memory>
1920
#include <stdexcept>
2021
#include <utility>
@@ -79,13 +80,16 @@ class StoragePolicyCommon
7980
throw std::runtime_error("unexpected condition, fixed storage policy needs pruning");
8081
}
8182
// Flag for pruning.
83+
std::cout << "waitable needs pruning" << std::endl;
8284
needs_pruning_ = true;
8385
continue;
8486
}
8587

8688
rclcpp::Waitable & waitable = *waitable_ptr_pair.second;
8789
subscriptions_from_waitables += waitable.get_number_of_ready_subscriptions();
8890
guard_conditions_from_waitables += waitable.get_number_of_ready_guard_conditions();
91+
std::cout << "guard_conditions_from_waitables: " << guard_conditions_from_waitables <<
92+
std::endl;
8993
timers_from_waitables += waitable.get_number_of_ready_timers();
9094
clients_from_waitables += waitable.get_number_of_ready_clients();
9195
services_from_waitables += waitable.get_number_of_ready_services();

rclcpp/include/rclcpp/wait_set_policies/thread_safe_synchronization.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -279,9 +279,11 @@ class ThreadSafeSynchronization : public detail::SynchronizationPolicyCommon
279279
// storage wait sets since they cannot be changed after construction.
280280
// This will also clear the wait set and re-add all the entities, which
281281
// prepares it to be waited on again.
282+
std::cout << "rebuild_rcl_wait_set" << std::endl;
282283
rebuild_rcl_wait_set();
283284
}
284285

286+
std::cout << "get_rcl_wait_set" << std::endl;
285287
rcl_wait_set_t & rcl_wait_set = get_rcl_wait_set();
286288

287289
// Wait unconditionally until timeout condition occurs since we assume
@@ -297,6 +299,7 @@ class ThreadSafeSynchronization : public detail::SynchronizationPolicyCommon
297299
// It is ok to wait while not having the lock acquired, because the state
298300
// in the rcl wait set will not be updated until this method calls
299301
// rebuild_rcl_wait_set().
302+
std::cout << "rcl_wait" << std::endl;
300303
rcl_ret_t ret = rcl_wait(&rcl_wait_set, time_left_to_wait_ns.count());
301304
if (RCL_RET_OK == ret) {
302305
// Something has become ready in the wait set, first check if it was

rclcpp/include/rclcpp/wait_set_template.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -661,6 +661,7 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli
661661
this->storage_acquire_ownerships();
662662
RCPPUTILS_SCOPE_EXIT({this->storage_release_ownerships();});
663663

664+
664665
// this method comes from the SynchronizationPolicy
665666
return this->template sync_wait<WaitResult<WaitSetTemplate>>(
666667
// pass along the time_to_wait duration as nanoseconds

0 commit comments

Comments
 (0)