19
19
#include < cassert>
20
20
#include < chrono>
21
21
#include < cstdlib>
22
+ #include < deque>
22
23
#include < iostream>
23
24
#include < list>
24
25
#include < map>
35
36
#include " rclcpp/contexts/default_context.hpp"
36
37
#include " rclcpp/guard_condition.hpp"
37
38
#include " rclcpp/executor_options.hpp"
39
+ #include " rclcpp/executors/executor_entities_collection.hpp"
40
+ #include " rclcpp/executors/executor_entities_collector.hpp"
38
41
#include " rclcpp/future_return_code.hpp"
39
- #include " rclcpp/memory_strategies.hpp"
40
- #include " rclcpp/memory_strategy.hpp"
41
42
#include " rclcpp/node_interfaces/node_base_interface.hpp"
42
43
#include " rclcpp/utilities.hpp"
43
44
#include " rclcpp/visibility_control.hpp"
45
+ #include " rclcpp/wait_set.hpp"
44
46
45
47
namespace rclcpp
46
48
{
47
49
48
- typedef std::map<rclcpp::CallbackGroup::WeakPtr,
49
- rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
50
- std::owner_less<rclcpp::CallbackGroup::WeakPtr>> WeakCallbackGroupsToNodesMap;
51
-
52
50
// Forward declaration is used in convenience method signature.
53
51
class Node ;
54
52
@@ -402,17 +400,6 @@ class Executor
402
400
void
403
401
cancel ();
404
402
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
-
416
403
// / Returns true if the executor is currently spinning.
417
404
/* *
418
405
* This function can be called asynchronously from any thread.
@@ -508,62 +495,6 @@ class Executor
508
495
void
509
496
wait_for_work (std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1 ));
510
497
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
-
567
498
// / Check for executable in ready state and populate union structure.
568
499
/* *
569
500
* \param[out] any_executable populated union structure of ready executable
@@ -574,33 +505,6 @@ class Executor
574
505
bool
575
506
get_next_ready_executable (AnyExecutable & any_executable);
576
507
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
-
604
508
// / Wait for executable in ready state and populate union structure.
605
509
/* *
606
510
* If an executable is ready, it will return immediately, otherwise
@@ -618,21 +522,6 @@ class Executor
618
522
AnyExecutable & any_executable,
619
523
std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1 ));
620
524
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
-
636
525
// / Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins.
637
526
std::atomic_bool spinning;
638
527
@@ -641,16 +530,8 @@ class Executor
641
530
642
531
std::shared_ptr<rclcpp::GuardCondition> shutdown_guard_condition_;
643
532
644
- // / Wait set for managing entities that the rmw layer waits on.
645
- rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set();
646
-
647
- // Mutex to protect the subsequent memory_strategy_.
648
533
mutable std::mutex mutex_;
649
534
650
- // / The memory strategy: an interface for handling user-defined memory allocation strategies.
651
- memory_strategy::MemoryStrategy::SharedPtr
652
- memory_strategy_ RCPPUTILS_TSA_PT_GUARDED_BY (mutex_);
653
-
654
535
// / The context associated with this executor.
655
536
std::shared_ptr<rclcpp::Context> context_;
656
537
@@ -660,39 +541,11 @@ class Executor
660
541
virtual void
661
542
spin_once_impl (std::chrono::nanoseconds timeout);
662
543
663
- typedef std::map<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
664
- const rclcpp::GuardCondition *,
665
- std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>
666
- WeakNodesToGuardConditionsMap;
667
-
668
- typedef std::map<rclcpp::CallbackGroup::WeakPtr,
669
- const rclcpp::GuardCondition *,
670
- std::owner_less<rclcpp::CallbackGroup::WeakPtr>>
671
- WeakCallbackGroupsToGuardConditionsMap;
672
-
673
- // / maps nodes to guard conditions
674
- WeakNodesToGuardConditionsMap
675
- weak_nodes_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
676
-
677
- // / maps callback groups to guard conditions
678
- WeakCallbackGroupsToGuardConditionsMap
679
- weak_groups_to_guard_conditions_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
680
-
681
- // / maps callback groups associated to nodes
682
- WeakCallbackGroupsToNodesMap
683
- weak_groups_associated_with_executor_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
684
-
685
- // / maps callback groups to nodes associated with executor
686
- WeakCallbackGroupsToNodesMap
687
- weak_groups_to_nodes_associated_with_executor_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
688
-
689
- // / maps all callback groups to nodes
690
- WeakCallbackGroupsToNodesMap
691
- weak_groups_to_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
544
+ rclcpp::executors::ExecutorEntitiesCollector collector_;
545
+ rclcpp::executors::ExecutorEntitiesCollection current_collection_;
692
546
693
- // / nodes that are associated with the executor
694
- std::list<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>
695
- weak_nodes_ RCPPUTILS_TSA_GUARDED_BY (mutex_);
547
+ std::shared_ptr<rclcpp::WaitSet> wait_set_;
548
+ std::deque<rclcpp::AnyExecutable> ready_executables_;
696
549
697
550
// / shutdown callback handle registered to Context
698
551
rclcpp::OnShutdownCallbackHandle shutdown_callback_handle_;
0 commit comments