From ef89e55a29dec6f62096c77774060d65dfbdd699 Mon Sep 17 00:00:00 2001 From: Akihiko Komada Date: Sat, 25 Apr 2026 16:01:15 +0900 Subject: [PATCH 1/5] docs(costmap-filters): add Zone Parameter Filter configuration page Companion documentation for ros-navigation/navigation2#6104, which introduces the new ZoneParameterFilter costmap filter plugin. - Add configuration/packages/costmap-plugins/zone_parameter_filter.rst documenting all parameters: enabled, filter_info_topic, transform_tolerance, target_nodes, state_ids, state_.., nominal_defaults.., state_event_topic, on_unknown_state, on_param_set_failure. Includes a fully-described YAML example. - Add the new file to the Costmap Filters Parameters toctree in configuration/packages/configuring-costmaps.rst. - Add Zone Parameter Filter row to the Costmap Filters table in plugins/index.rst (table widened to fit the longer plugin name). Co-Authored-By: Claude and aki1770-del Signed-off-by: Akihiko Komada --- .../packages/configuring-costmaps.rst | 1 + .../costmap-plugins/zone_parameter_filter.rst | 170 ++++++++++++++++++ plugins/index.rst | 29 +-- 3 files changed, 188 insertions(+), 12 deletions(-) create mode 100644 configuration/packages/costmap-plugins/zone_parameter_filter.rst diff --git a/configuration/packages/configuring-costmaps.rst b/configuration/packages/configuring-costmaps.rst index 4b2056973..e94debf44 100644 --- a/configuration/packages/configuring-costmaps.rst +++ b/configuration/packages/configuring-costmaps.rst @@ -401,6 +401,7 @@ Costmap Filters Parameters costmap-plugins/keepout_filter.rst costmap-plugins/speed_filter.rst costmap-plugins/binary_filter.rst + costmap-plugins/zone_parameter_filter.rst Example ******* diff --git a/configuration/packages/costmap-plugins/zone_parameter_filter.rst b/configuration/packages/costmap-plugins/zone_parameter_filter.rst new file mode 100644 index 000000000..f4b2c7fce --- /dev/null +++ b/configuration/packages/costmap-plugins/zone_parameter_filter.rst @@ -0,0 +1,170 @@ +.. _zone_parameter_filter: + +Zone Parameter Filter Parameters +================================ + +Zone Parameter Filter - is a Costmap Filter that applies a configurable +set of nav2 parameter overrides to one or more target nodes based on the +mask value at the robot's current pose. The filter is the mechanism; the +use-case lives in YAML — winter roads, school zones, indoor/outdoor +transitions, and construction zones all reduce to the same plugin with +different state maps. + +The mask value is interpreted as a state ID. State ``0`` is reserved as +the special "reset" state, which restores all overridden parameters to +their YAML-declared nominal values. Each non-zero mask value (effective +range bounded by the ``int8_t`` ``OccupancyGrid`` transport, ``-128`` to +``127``; negative values are reserved for ``OCC_GRID_UNKNOWN`` and are +ignored) maps to a list of parameter overrides via the layer's +configuration. + +Parameter sets are issued asynchronously via ``AsyncParametersClient``; +the filter never calls ``wait_for_service`` in the hot path. If a target +node's parameter service is not ready, the filter logs a throttled warning +and skips that target — the costmap update loop is not blocked. + +``: is the corresponding plugin name selected for this type. + +:````.enabled: + + ====== ======= + Type Default + ------ ------- + bool True + ====== ======= + + Description + Whether it is enabled. + +:````.filter_info_topic: + + ====== ======= + Type Default + ------ ------- + string N/A + ====== ======= + + Description + Name of the incoming `CostmapFilterInfo `_ topic having filter-related information. Published by Costmap Filter Info Server along with filter mask topic. For more details about Map and Costmap Filter Info servers configuration please refer to the :ref:`configuring_map_server` configuration page. + +:````.transform_tolerance: + + ====== ======= + Type Default + ------ ------- + double 0.1 + ====== ======= + + Description + Time with which to post-date the transform that is published, to indicate that this transform is valid into the future. Used when filter mask and current costmap layer are in different frames. + +:````.target_nodes: + + ============== ======= + Type Default + -------------- ------- + vector [] + ============== ======= + + Description + Required. Explicit list of target node names the filter is allowed to mutate. The state-override parser does longest-prefix-match against this list, so nested-namespace targets parse unambiguously. Catches typos at config-load. Example: ``["controller_server", "local_costmap"]``. + +:````.state_ids: + + ============= ======= + Type Default + ------------- ------- + vector [] + ============= ======= + + Description + Required. List of mask values (each in ``[1, 127]``) that map to a configured state. Each listed value must have a corresponding ``state_`` block. State ``0`` is the implicit reset state and is not listed here. + +:````.state_..: + + ====== ======= + Type Default + ------ ------- + any N/A + ====== ======= + + Description + For each ``N`` in ``state_ids``, declare the parameter overrides to apply when the robot enters mask state ``N``. ```` must be one of the names listed in ``target_nodes``. ```` is the parameter name on that target node, dots and all (e.g., ``inflation_layer.inflation_radius``). The parameter type must match the target's declared type. Example: ``state_1.controller_server.FollowPath.max_vel_x: 0.5``. + +:````.nominal_defaults..: + + ====== ======= + Type Default + ------ ------- + any N/A + ====== ======= + + Description + Optional but strongly recommended. The value to restore for each parameter when the robot enters state ``0`` (reset). One entry per parameter that any state ``N`` overrides. Declarative rather than auto-captured because the underlying ``get_parameters`` and ``set_parameters`` services are separate ``services::Client`` instances on the target node — server-side ordering between a "capture-then-override" sequence is not guaranteed, so a late get response could capture the overridden value rather than the nominal. The filter logs a warning at config-load time for any state-N override that has no matching ``nominal_defaults`` entry; such parameters will not be restored on state-0 reset. + +:````.state_event_topic: + + ====== ======= + Type Default + ------ ------- + string "" + ====== ======= + + Description + Optional. If set to a non-empty topic name, the filter publishes a ``std_msgs::msg::UInt8`` message containing the new state ID on every state transition (including transitions to state ``0``). If left empty, no publisher is created. + +:````.on_unknown_state: + + ====== ======= + Type Default + ------ ------- + string "warn" + ====== ======= + + Description + Behavior when the mask value at the robot's pose is non-negative but not present in the configured ``state_ids`` map. Either ``"warn"`` (log a throttled warning, leave the current state unchanged) or ``"throw"`` (raise an exception, terminating the filter). + +:````.on_param_set_failure: + + ====== ======= + Type Default + ------ ------- + string "warn" + ====== ======= + + Description + Behavior when a target node's ``set_parameters`` call returns ``successful = false``. Either ``"warn"`` (log the failure and continue — the costmap update loop is preserved) or ``"throw"`` (raise an exception, terminating the filter). The default is ``"warn"`` because a hot-path exception in a costmap filter takes the entire navigation stack down; ``"throw"`` is offered for stacks that prefer hard correctness over operational continuity. + +Example Fully-Described YAML +---------------------------- + +.. code-block:: yaml + + local_costmap: + ros__parameters: + plugins: ["voxel_layer", "inflation_layer"] + filters: ["zone_parameter_filter"] + zone_parameter_filter: + plugin: "nav2_costmap_2d::ZoneParameterFilter" + enabled: true + filter_info_topic: "/zone_filter_info" + state_event_topic: "/zone_filter_state" # optional + on_unknown_state: "warn" # or "throw" + on_param_set_failure: "warn" # or "throw" + target_nodes: [controller_server, local_costmap] + state_ids: [1, 2] + state_1: # winter / icy zone + controller_server: + FollowPath.max_vel_x: 0.5 + local_costmap: + inflation_layer.inflation_radius: 0.8 + state_2: # construction zone + controller_server: + FollowPath.max_vel_x: 0.2 + local_costmap: + inflation_layer.inflation_radius: 1.2 + nominal_defaults: # state-0 restores these + controller_server: + FollowPath.max_vel_x: 1.0 + local_costmap: + inflation_layer.inflation_radius: 0.55 diff --git a/plugins/index.rst b/plugins/index.rst index 17dacb4a2..4adedc206 100644 --- a/plugins/index.rst +++ b/plugins/index.rst @@ -96,22 +96,27 @@ Costmap Layers Costmap Filters =============== -+--------------------+--------------------+-----------------------------------+ -| Plugin Name | Creator | Description | -+====================+====================+===================================+ -| `Keepout Filter`_ | Alexey Merzlyakov | Maintains keep-out/safety zones | -| | | and preferred lanes for moving | -+--------------------+--------------------+-----------------------------------+ -| `Speed Filter`_ | Alexey Merzlyakov | Limits maximum velocity of robot | -| | | in speed restriction areas | -+--------------------+--------------------+-----------------------------------+ -| `Binary Filter`_ | Alexey Merzlyakov | Enables binary (boolean) mask | -| | | behavior to trigger actions. | -+--------------------+--------------------+-----------------------------------+ ++--------------------------+--------------------+-----------------------------------+ +| Plugin Name | Creator | Description | ++==========================+====================+===================================+ +| `Keepout Filter`_ | Alexey Merzlyakov | Maintains keep-out/safety zones | +| | | and preferred lanes for moving | ++--------------------------+--------------------+-----------------------------------+ +| `Speed Filter`_ | Alexey Merzlyakov | Limits maximum velocity of robot | +| | | in speed restriction areas | ++--------------------------+--------------------+-----------------------------------+ +| `Binary Filter`_ | Alexey Merzlyakov | Enables binary (boolean) mask | +| | | behavior to trigger actions. | ++--------------------------+--------------------+-----------------------------------+ +| `Zone Parameter Filter`_ | aki1770-del | Applies a configured set of nav2 | +| | | parameter overrides per mask | +| | | state. | ++--------------------------+--------------------+-----------------------------------+ .. _Keepout Filter: https://github.com/ros-navigation/navigation2/tree/main/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp .. _Speed Filter: https://github.com/ros-navigation/navigation2/tree/main/nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp .. _Binary Filter: https://github.com/ros-navigation/navigation2/tree/main/nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp +.. _Zone Parameter Filter: https://github.com/ros-navigation/navigation2/tree/main/nav2_costmap_2d/plugins/costmap_filters/zone_parameter_filter.cpp Controllers =========== From 9e709b99110e23cc706fa7ac6c2fb716cdad0742 Mon Sep 17 00:00:00 2001 From: Akihiko Komada Date: Sat, 25 Apr 2026 17:05:26 +0900 Subject: [PATCH 2/5] docs(zone_parameter_filter): add Common Pitfalls section Five operational sharp edges that surfaced during nav2#6104 design + post-PR audit: - Target-node typos go silent at config-load until first transition - State-to-state transitions only apply the new state's overrides (only state 0 resets to nominal_defaults) - Hot path is non-blocking by design (no wait_for_service) - Effective state-ID range is [1, 127] (int8_t mask transport) - Longest-prefix matching with deterministic length-descending sort Co-Authored-By: Claude and aki1770-del Signed-off-by: Akihiko Komada --- .../costmap-plugins/zone_parameter_filter.rst | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/configuration/packages/costmap-plugins/zone_parameter_filter.rst b/configuration/packages/costmap-plugins/zone_parameter_filter.rst index f4b2c7fce..ea4a865f9 100644 --- a/configuration/packages/costmap-plugins/zone_parameter_filter.rst +++ b/configuration/packages/costmap-plugins/zone_parameter_filter.rst @@ -168,3 +168,23 @@ Example Fully-Described YAML FollowPath.max_vel_x: 1.0 local_costmap: inflation_layer.inflation_radius: 0.55 + +Common Pitfalls +--------------- + +These are the operational sharp edges that have surfaced during design and review: + +- **Target-node typos go silent at config-load until first transition.** + An override under a ``state_`` namespace whose first segment doesn't match an entry in ``target_nodes`` is rejected with a warning. The filter still becomes active and continues with the remaining valid overrides — but the typo'd parameter is never set. Always check the warn log on first activation. + +- **State-to-state transitions only apply the new state's overrides.** + If state 1 sets ``A`` and ``B`` and state 2 sets only ``A``, then a 1→2 transition writes the new value of ``A`` and leaves ``B`` at state 1's value. Only the special state ``0`` reset restores anything to ``nominal_defaults``. Plan ``nominal_defaults`` so any param touched by any state has a documented baseline. + +- **The hot path is non-blocking by design.** + If a target node's parameter service is not ready when ``process()`` runs (target node restarting, network blip, etc.), the override for that node is skipped that cycle and a throttled warning is logged. The filter does *not* call ``wait_for_service`` because that would stall the entire costmap update loop. Subsequent ``process()`` calls retry naturally. + +- **Effective state-ID range is [1, 127], not [1, 255].** + Although the documentation shows the conceptual range as 0–255, the underlying ``OccupancyGrid::data`` field is ``int8_t``, so values 128–255 arrive as their signed-negative complement. Negative mask values are reserved for ``OCC_GRID_UNKNOWN`` and are silently ignored at the robot's pose. If you need the full 0–255 range, wrap your mask publisher to reinterpret-cast unsigned to signed before publishing — but [1, 127] covers the vast majority of zone schemes. + +- **Longest-prefix matching applies to ``target_nodes`` ordering.** + When ``target_nodes`` contains both a node name and a namespace-prefixed sibling (e.g., ``["a", "a.b"]``), an override under ``state_.a.b.foo`` is routed to ``a.b`` (longer match), not to ``a`` (with parameter path ``b.foo``). The filter sorts ``target_nodes`` by length descending at config-load to make this deterministic. From 7b002d7704db4002ed35a77eb021692c367aeccf Mon Sep 17 00:00:00 2001 From: Akihiko Komada Date: Wed, 29 Apr 2026 07:54:37 +0900 Subject: [PATCH 3/5] docs(zone_parameter_filter): rework intro + trim Common Pitfalls + remove on_unknown_state MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Addresses Steve Macenski review on PR #907: - L11 (mechanical phrasing): rewrote the intro paragraph to 4 lines, stripped marketing-style framing. - L18 (int8_t/OCC_GRID_UNKNOWN parenthetical): removed; range stated as [1, 127] plainly. - L24 (AsyncParametersClient configuration paragraph): removed — not a configuration detail. - L70 (target_nodes longest-prefix-match prose): stripped from Description; the matching logic stays in code (see PR #6104 reply). - L116 (on_unknown_state parameter docs entry + YAML example line): removed for coherence with PR #6104 commit e61099a, which removed the parameter from the code (always-throw on unknown mask state per the C.2.a part of the review). Without this, the docs would describe a parameter that no longer exists. - L190 (Common Pitfalls section): renamed to "Notes" and trimmed from 5 bullets to 1 (the state-to-state transition behavior, which is a real configuration consideration). Items deferred to paired commits as the remaining PR #6104 changes ship: - L94 (nominal_defaults framing — depends on auto-capture refactor) - L114 (state_event_topic default — depends on code-side default flip) - L136 (on_param_set_failure — pushback substance restated in reply; docs default-flip pairs with code commit when it lands) Signed-off-by: Akihiko Komada --- .../costmap-plugins/zone_parameter_filter.rst | 58 ++++--------------- 1 file changed, 10 insertions(+), 48 deletions(-) diff --git a/configuration/packages/costmap-plugins/zone_parameter_filter.rst b/configuration/packages/costmap-plugins/zone_parameter_filter.rst index ea4a865f9..be13cf3aa 100644 --- a/configuration/packages/costmap-plugins/zone_parameter_filter.rst +++ b/configuration/packages/costmap-plugins/zone_parameter_filter.rst @@ -3,25 +3,13 @@ Zone Parameter Filter Parameters ================================ -Zone Parameter Filter - is a Costmap Filter that applies a configurable -set of nav2 parameter overrides to one or more target nodes based on the -mask value at the robot's current pose. The filter is the mechanism; the -use-case lives in YAML — winter roads, school zones, indoor/outdoor -transitions, and construction zones all reduce to the same plugin with -different state maps. - -The mask value is interpreted as a state ID. State ``0`` is reserved as -the special "reset" state, which restores all overridden parameters to -their YAML-declared nominal values. Each non-zero mask value (effective -range bounded by the ``int8_t`` ``OccupancyGrid`` transport, ``-128`` to -``127``; negative values are reserved for ``OCC_GRID_UNKNOWN`` and are -ignored) maps to a list of parameter overrides via the layer's -configuration. - -Parameter sets are issued asynchronously via ``AsyncParametersClient``; -the filter never calls ``wait_for_service`` in the hot path. If a target -node's parameter service is not ready, the filter logs a throttled warning -and skips that target — the costmap update loop is not blocked. +Zone Parameter Filter applies a configurable set of nav2 parameter +overrides to one or more target nodes based on the mask value at the +robot's current pose. Configure the per-state overrides in YAML. + +The mask value is interpreted as a state ID. State ``0`` is the reset +state and restores parameters to their YAML-declared nominal values. +Mask values in ``[1, 127]`` map to configured states. ``: is the corresponding plugin name selected for this type. @@ -67,7 +55,7 @@ and skips that target — the costmap update loop is not blocked. ============== ======= Description - Required. Explicit list of target node names the filter is allowed to mutate. The state-override parser does longest-prefix-match against this list, so nested-namespace targets parse unambiguously. Catches typos at config-load. Example: ``["controller_server", "local_costmap"]``. + Required. Explicit list of target node names the filter is allowed to mutate. Catches typos at config-load. Example: ``["controller_server", "local_costmap"]``. :````.state_ids: @@ -113,17 +101,6 @@ and skips that target — the costmap update loop is not blocked. Description Optional. If set to a non-empty topic name, the filter publishes a ``std_msgs::msg::UInt8`` message containing the new state ID on every state transition (including transitions to state ``0``). If left empty, no publisher is created. -:````.on_unknown_state: - - ====== ======= - Type Default - ------ ------- - string "warn" - ====== ======= - - Description - Behavior when the mask value at the robot's pose is non-negative but not present in the configured ``state_ids`` map. Either ``"warn"`` (log a throttled warning, leave the current state unchanged) or ``"throw"`` (raise an exception, terminating the filter). - :````.on_param_set_failure: ====== ======= @@ -149,7 +126,6 @@ Example Fully-Described YAML enabled: true filter_info_topic: "/zone_filter_info" state_event_topic: "/zone_filter_state" # optional - on_unknown_state: "warn" # or "throw" on_param_set_failure: "warn" # or "throw" target_nodes: [controller_server, local_costmap] state_ids: [1, 2] @@ -169,22 +145,8 @@ Example Fully-Described YAML local_costmap: inflation_layer.inflation_radius: 0.55 -Common Pitfalls ---------------- - -These are the operational sharp edges that have surfaced during design and review: - -- **Target-node typos go silent at config-load until first transition.** - An override under a ``state_`` namespace whose first segment doesn't match an entry in ``target_nodes`` is rejected with a warning. The filter still becomes active and continues with the remaining valid overrides — but the typo'd parameter is never set. Always check the warn log on first activation. +Notes +----- - **State-to-state transitions only apply the new state's overrides.** If state 1 sets ``A`` and ``B`` and state 2 sets only ``A``, then a 1→2 transition writes the new value of ``A`` and leaves ``B`` at state 1's value. Only the special state ``0`` reset restores anything to ``nominal_defaults``. Plan ``nominal_defaults`` so any param touched by any state has a documented baseline. - -- **The hot path is non-blocking by design.** - If a target node's parameter service is not ready when ``process()`` runs (target node restarting, network blip, etc.), the override for that node is skipped that cycle and a throttled warning is logged. The filter does *not* call ``wait_for_service`` because that would stall the entire costmap update loop. Subsequent ``process()`` calls retry naturally. - -- **Effective state-ID range is [1, 127], not [1, 255].** - Although the documentation shows the conceptual range as 0–255, the underlying ``OccupancyGrid::data`` field is ``int8_t``, so values 128–255 arrive as their signed-negative complement. Negative mask values are reserved for ``OCC_GRID_UNKNOWN`` and are silently ignored at the robot's pose. If you need the full 0–255 range, wrap your mask publisher to reinterpret-cast unsigned to signed before publishing — but [1, 127] covers the vast majority of zone schemes. - -- **Longest-prefix matching applies to ``target_nodes`` ordering.** - When ``target_nodes`` contains both a node name and a namespace-prefixed sibling (e.g., ``["a", "a.b"]``), an override under ``state_.a.b.foo`` is routed to ``a.b`` (longer match), not to ``a`` (with parameter path ``b.foo``). The filter sorts ``target_nodes`` by length descending at config-load to make this deterministic. From b0ef2bce95416b56650e2a3b256c9811bacbf889 Mon Sep 17 00:00:00 2001 From: Akihiko Komada Date: Wed, 29 Apr 2026 08:59:21 +0900 Subject: [PATCH 4/5] docs(zone_parameter_filter): paired updates for state_event_topic + on_param_set_failure defaults Pairs with PR #6104 commits db32b3c (state_event_topic default) and 1cf64e4 (on_param_set_failure default-flip). - L114 (state_event_topic): default flipped from "" to "zone_filter_state"; "Optional" framing dropped; description now states the publisher is always created. - L136 (on_param_set_failure): default flipped from "warn" to "throw"; description rewritten to explain the safety rationale (fail-safe on persistent faults) and the warn-escape for transient-RPC environments. - Example YAML: state_event_topic value updated to match new default; on_param_set_failure value updated to "throw" with comment noting it is the new default. Signed-off-by: Akihiko Komada --- .../costmap-plugins/zone_parameter_filter.rst | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/configuration/packages/costmap-plugins/zone_parameter_filter.rst b/configuration/packages/costmap-plugins/zone_parameter_filter.rst index be13cf3aa..36640eac4 100644 --- a/configuration/packages/costmap-plugins/zone_parameter_filter.rst +++ b/configuration/packages/costmap-plugins/zone_parameter_filter.rst @@ -92,25 +92,25 @@ Mask values in ``[1, 127]`` map to configured states. :````.state_event_topic: - ====== ======= + ====== ==================== Type Default - ------ ------- - string "" - ====== ======= + ------ -------------------- + string "zone_filter_state" + ====== ==================== Description - Optional. If set to a non-empty topic name, the filter publishes a ``std_msgs::msg::UInt8`` message containing the new state ID on every state transition (including transitions to state ``0``). If left empty, no publisher is created. + Topic name on which the filter publishes a ``std_msgs::msg::UInt8`` message containing the new state ID on every state transition (including transitions to state ``0``). The publisher is always created. :````.on_param_set_failure: ====== ======= Type Default ------ ------- - string "warn" + string "throw" ====== ======= Description - Behavior when a target node's ``set_parameters`` call returns ``successful = false``. Either ``"warn"`` (log the failure and continue — the costmap update loop is preserved) or ``"throw"`` (raise an exception, terminating the filter). The default is ``"warn"`` because a hot-path exception in a costmap filter takes the entire navigation stack down; ``"throw"`` is offered for stacks that prefer hard correctness over operational continuity. + Behavior when a target node's ``set_parameters`` call returns ``successful = false``. Either ``"throw"`` (raise an exception, terminating the filter) or ``"warn"`` (log the failure and continue — the costmap update loop is preserved). The default is ``"throw"`` for fail-safe behavior on persistent set-parameter faults; ``"warn"`` is offered for environments where transient RPC faults (target node mid-restart, parameter-service overloaded) are common and continuing through them is preferred over the lifecycle-stopping exception. Example Fully-Described YAML ---------------------------- @@ -125,8 +125,8 @@ Example Fully-Described YAML plugin: "nav2_costmap_2d::ZoneParameterFilter" enabled: true filter_info_topic: "/zone_filter_info" - state_event_topic: "/zone_filter_state" # optional - on_param_set_failure: "warn" # or "throw" + state_event_topic: "zone_filter_state" # default + on_param_set_failure: "throw" # default; or "warn" target_nodes: [controller_server, local_costmap] state_ids: [1, 2] state_1: # winter / icy zone From aca0d41d9d52dc024687ae9185f26b5c5d4d17ae Mon Sep 17 00:00:00 2001 From: Akihiko Komada Date: Wed, 29 Apr 2026 09:19:47 +0900 Subject: [PATCH 5/5] docs(zone_parameter_filter): trim nominal_defaults description for consistency Pairs with the PR #6104 Theme B comment scrub and clarifies the answer to Steve Macenski's L94 inline comment ("Can we not 'get' each value at startup so we have those rather than configuring them?"). The honest answer is: we tried, and the underlying services::Client FIFO race makes auto-capture unreliable. The original docs paragraph already explained this; the production code keeps the declarative-YAML approach. Trimmed the docs paragraph to match the more concise comment shape on the cpp side after the PR #6104 Theme B scrub: - Drops the "Optional but strongly recommended" hedge framing. - Drops "One entry per parameter..." (self-evident from the parameter shape declaration above the Description). - Keeps the race-condition reason in one sentence (the answer to Steve's question). - Keeps the warn-on-gap behavior note. Signed-off-by: Akihiko Komada --- .../packages/costmap-plugins/zone_parameter_filter.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/costmap-plugins/zone_parameter_filter.rst b/configuration/packages/costmap-plugins/zone_parameter_filter.rst index 36640eac4..d5fb4120b 100644 --- a/configuration/packages/costmap-plugins/zone_parameter_filter.rst +++ b/configuration/packages/costmap-plugins/zone_parameter_filter.rst @@ -88,7 +88,7 @@ Mask values in ``[1, 127]`` map to configured states. ====== ======= Description - Optional but strongly recommended. The value to restore for each parameter when the robot enters state ``0`` (reset). One entry per parameter that any state ``N`` overrides. Declarative rather than auto-captured because the underlying ``get_parameters`` and ``set_parameters`` services are separate ``services::Client`` instances on the target node — server-side ordering between a "capture-then-override" sequence is not guaranteed, so a late get response could capture the overridden value rather than the nominal. The filter logs a warning at config-load time for any state-N override that has no matching ``nominal_defaults`` entry; such parameters will not be restored on state-0 reset. + Value to restore for each parameter on state ``0`` (reset). Declared rather than auto-captured because ``get_parameters`` and ``set_parameters`` use separate underlying ``services::Client`` instances on the target node, so a "capture-then-override" sequence cannot guarantee FIFO ordering at the server. The filter logs a warning at config-load for any state-N override without a matching ``nominal_defaults`` entry; such parameters will not be restored on state-0 reset. :````.state_event_topic: