Skip to content

CallbackIsolatedAgnocastExecutor may select wrong executor type when agnocast entities are added after callback group registration #1263

@atsushi421

Description

@atsushi421

Problem

CallbackIsolatedAgnocastExecutor (CIE) spawns a dedicated executor thread per callback group, choosing the executor type based on whether the group contains agnocast entities:

Agnocast entities present No agnocast entities
SingleThreadedAgnocastExecutor SingleThreadedExecutor (standard ROS 2)

This decision is made at the moment the callback group is first detected. If agnocast entities are added to the group after detection, the standard executor is chosen, and the agnocast subscriptions never execute.

Reproduction scenario

  1. A node is already registered with CIE and spinning.
  2. A new callback group is dynamically created on that node.
  3. CIE's monitoring loop (check_for_new_callback_groups) detects the group → get_agnocast_topics_by_group() returns empty → SingleThreadedExecutor is spawned.
  4. An agnocast subscription is subsequently added to that group.
  5. The agnocast entity never executes because it is running under the wrong executor type.

Affected code

The same pattern exists in two independent implementations:

  1. src/agnocastlib/src/agnocast_callback_isolated_executor.cppspawn_child_executor lambda (~L76-88)
  2. src/agnocast_components/src/agnocast_component_container_cie.cppstart_executor_for_callback_group (L156-170)

Both call get_agnocast_topics_by_group(group) to decide the executor type at callback group detection time, and both are invoked from a monitoring loop that periodically scans for new callback groups.

auto agnocast_topics = agnocast::get_agnocast_topics_by_group(group);

if (agnocast_topics.empty()) {
  executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
  // ...
} else {
  executor = std::make_shared<SingleThreadedAgnocastExecutor>(...);
  // ...
}

Constraint

Unconditionally using SingleThreadedAgnocastExecutor for all callback groups is not acceptable. get_next_agnocast_executable blocks for next_exec_timeout_ms (default 50 ms) on each spin iteration, which would add unnecessary latency to ROS-only callback processing.

Context

Reported by Jin-kun during need_epoll_update refactoring work. Slack thread.

Metadata

Metadata

Assignees

No one assigned

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions