-
Notifications
You must be signed in to change notification settings - Fork 266
docs(costmap-filters): add Zone Parameter Filter configuration page #907
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Open
aki1770-del
wants to merge
8
commits into
ros-navigation:master
Choose a base branch
from
aki1770-del:feat/zone-parameter-filter-docs
base: master
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
+170
−12
Open
Changes from 2 commits
Commits
Show all changes
8 commits
Select commit
Hold shift + click to select a range
ef89e55
docs(costmap-filters): add Zone Parameter Filter configuration page
aki1770-del 9e709b9
docs(zone_parameter_filter): add Common Pitfalls section
aki1770-del 7b002d7
docs(zone_parameter_filter): rework intro + trim Common Pitfalls + re…
aki1770-del b0ef2bc
docs(zone_parameter_filter): paired updates for state_event_topic + o…
aki1770-del aca0d41
docs(zone_parameter_filter): trim nominal_defaults description for co…
aki1770-del 5778b95
docs(zone_parameter_filter): document N-only reset on N→M transitions
aki1770-del b52d2ee
docs(zone_parameter_filter): strengthen nominal_defaults declaration …
aki1770-del 6c04135
docs(zone_parameter_filter): trim nominal_defaults rationale per review
aki1770-del File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
190 changes: 190 additions & 0 deletions
190
configuration/packages/costmap-plugins/zone_parameter_filter.rst
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,190 @@ | ||
| .. _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 | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
| 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. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
|
|
||
| `<filter name>`: is the corresponding plugin name selected for this type. | ||
|
|
||
| :``<filter name>``.enabled: | ||
|
|
||
| ====== ======= | ||
| Type Default | ||
| ------ ------- | ||
| bool True | ||
| ====== ======= | ||
|
|
||
| Description | ||
| Whether it is enabled. | ||
|
|
||
| :``<filter name>``.filter_info_topic: | ||
|
|
||
| ====== ======= | ||
| Type Default | ||
| ------ ------- | ||
| string N/A | ||
| ====== ======= | ||
|
|
||
| Description | ||
| Name of the incoming `CostmapFilterInfo <https://github.com/ros-navigation/navigation2/blob/main/nav2_msgs/msg/CostmapFilterInfo.msg>`_ 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. | ||
|
|
||
| :``<filter name>``.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. | ||
|
|
||
| :``<filter name>``.target_nodes: | ||
|
|
||
| ============== ======= | ||
| Type Default | ||
| -------------- ------- | ||
| vector<string> [] | ||
| ============== ======= | ||
|
|
||
| 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"]``. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
|
|
||
| :``<filter name>``.state_ids: | ||
|
|
||
| ============= ======= | ||
| Type Default | ||
| ------------- ------- | ||
| vector<int> [] | ||
| ============= ======= | ||
|
|
||
| Description | ||
| Required. List of mask values (each in ``[1, 127]``) that map to a configured state. Each listed value must have a corresponding ``state_<N>`` block. State ``0`` is the implicit reset state and is not listed here. | ||
|
|
||
| :``<filter name>``.state_<N>.<target_node>.<parameter_path>: | ||
|
|
||
| ====== ======= | ||
| 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``. ``<target_node>`` must be one of the names listed in ``target_nodes``. ``<parameter_path>`` 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``. | ||
|
|
||
| :``<filter name>``.nominal_defaults.<target_node>.<parameter_path>: | ||
|
SteveMacenski marked this conversation as resolved.
|
||
|
|
||
| ====== ======= | ||
| 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. | ||
|
|
||
| :``<filter name>``.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. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
|
|
||
| :``<filter name>``.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). | ||
|
|
||
| :``<filter name>``.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. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
|
|
||
| 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 | ||
|
|
||
| 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_<N>`` 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. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
|
|
||
| - **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_<N>.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. | ||
|
SteveMacenski marked this conversation as resolved.
Outdated
|
||
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.