Skip to content

Commit 18dd05f

Browse files
authored
Documentation improvements on the executor (#2125)
Signed-off-by: Michael Carroll <[email protected]>
1 parent 232262c commit 18dd05f

File tree

1 file changed

+100
-0
lines changed

1 file changed

+100
-0
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 100 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -315,6 +315,16 @@ class Executor
315315
virtual void
316316
spin_all(std::chrono::nanoseconds max_duration);
317317

318+
319+
/// Collect work once and execute the next available work, optionally within a duration.
320+
/**
321+
* This function can be overridden. The default implementation is suitable for
322+
* a single-thread model of execution.
323+
* Adding subscriptions, timers, services, etc. with blocking callbacks will cause this function
324+
* to block (which may have unintended consequences).
325+
* \param[in] timeout The maximum amount of time to spend waiting for work.
326+
* `-1` is potentially block forever waiting for work.
327+
*/
318328
RCLCPP_PUBLIC
319329
virtual void
320330
spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
@@ -413,12 +423,29 @@ class Executor
413423
is_spinning();
414424

415425
protected:
426+
/// Add a node to executor, execute the next available unit of work, and remove the node.
427+
/**
428+
* Implementation of spin_node_once using std::chrono::nanoseconds
429+
* \param[in] node Shared pointer to the node to add.
430+
* \param[in] timeout How long to wait for work to become available. Negative values cause
431+
* spin_node_once to block indefinitely (the default behavior). A timeout of 0 causes this
432+
* function to be non-blocking.
433+
*/
416434
RCLCPP_PUBLIC
417435
void
418436
spin_node_once_nanoseconds(
419437
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
420438
std::chrono::nanoseconds timeout);
421439

440+
/// Collect work and execute available work, optionally within a duration.
441+
/**
442+
* Implementation of spin_some and spin_all.
443+
* The exhaustive flag controls if the function will re-collect available work within the duration.
444+
*
445+
* \param[in] max_duration The maximum amount of time to spend executing work, or 0 for no limit.
446+
* \param[in] exhaustive when set to true, continue to collect work and execute (spin_all)
447+
* when set to false, return when all collected work is executed (spin_some)
448+
*/
422449
RCLCPP_PUBLIC
423450
void
424451
spin_some_impl(std::chrono::nanoseconds max_duration, bool exhaustive);
@@ -433,30 +460,60 @@ class Executor
433460
void
434461
execute_any_executable(AnyExecutable & any_exec);
435462

463+
/// Run subscription executable.
464+
/**
465+
* Do necessary setup and tear-down as well as executing the subscription.
466+
* \param[in] subscription Subscription to execute
467+
*/
436468
RCLCPP_PUBLIC
437469
static void
438470
execute_subscription(
439471
rclcpp::SubscriptionBase::SharedPtr subscription);
440472

473+
/// Run timer executable.
474+
/**
475+
* Do necessary setup and tear-down as well as executing the timer callback.
476+
* \param[in] timer Timer to execute
477+
*/
441478
RCLCPP_PUBLIC
442479
static void
443480
execute_timer(rclcpp::TimerBase::SharedPtr timer);
444481

482+
/// Run service server executable.
483+
/**
484+
* Do necessary setup and tear-down as well as executing the service server callback.
485+
* \param[in] service Service to execute
486+
*/
445487
RCLCPP_PUBLIC
446488
static void
447489
execute_service(rclcpp::ServiceBase::SharedPtr service);
448490

491+
/// Run service client executable.
492+
/**
493+
* Do necessary setup and tear-down as well as executing the service client callback.
494+
* \param[in] service Service to execute
495+
*/
449496
RCLCPP_PUBLIC
450497
static void
451498
execute_client(rclcpp::ClientBase::SharedPtr client);
452499

500+
/// Block until more work becomes avilable or timeout is reached.
453501
/**
502+
* Builds a set of waitable entities, which are passed to the middleware.
503+
* After building wait set, waits on middleware to notify.
504+
* \param[in] timeout duration to wait for new work to become available.
454505
* \throws std::runtime_error if the wait set can be cleared
455506
*/
456507
RCLCPP_PUBLIC
457508
void
458509
wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
459510

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+
*/
460517
RCLCPP_PUBLIC
461518
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
462519
get_node_by_group(
@@ -475,6 +532,11 @@ class Executor
475532
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
476533
const WeakCallbackGroupsToNodesMap & weak_groups_to_nodes) const;
477534

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+
*/
478540
RCLCPP_PUBLIC
479541
rclcpp::CallbackGroup::SharedPtr
480542
get_group_by_timer(rclcpp::TimerBase::SharedPtr timer);
@@ -502,16 +564,54 @@ class Executor
502564
WeakCallbackGroupsToNodesMap & weak_groups_to_nodes,
503565
bool notify = true) RCPPUTILS_TSA_REQUIRES(mutex_);
504566

567+
/// Check for executable in ready state and populate union structure.
568+
/**
569+
* \param[out] any_executable populated union structure of ready executable
570+
* \return true if an executable was ready and any_executable was populated,
571+
* otherwise false
572+
*/
505573
RCLCPP_PUBLIC
506574
bool
507575
get_next_ready_executable(AnyExecutable & any_executable);
508576

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+
*/
509598
RCLCPP_PUBLIC
510599
bool
511600
get_next_ready_executable_from_map(
512601
AnyExecutable & any_executable,
513602
const WeakCallbackGroupsToNodesMap & weak_groups_to_nodes);
514603

604+
/// Wait for executable in ready state and populate union structure.
605+
/**
606+
* If an executable is ready, it will return immediately, otherwise
607+
* block based on the timeout for work to become ready.
608+
*
609+
* \param[out] any_executable populated union structure of ready executable
610+
* \param[in] timeout duration of time to wait for work, a negative value
611+
* (the defualt behavior), will make this function block indefinitely
612+
* \return true if an executable was ready and any_executable was populated,
613+
* otherwise false
614+
*/
515615
RCLCPP_PUBLIC
516616
bool
517617
get_next_executable(

0 commit comments

Comments
 (0)