-
Notifications
You must be signed in to change notification settings - Fork 262
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
5
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.
Open
Changes from all commits
Commits
Show all changes
5 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 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
152 changes: 152 additions & 0 deletions
152
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,152 @@ | ||
| .. _zone_parameter_filter: | ||
|
|
||
| Zone Parameter Filter Parameters | ||
| ================================ | ||
|
|
||
| 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. | ||
|
|
||
| `<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. Catches typos at config-load. Example: ``["controller_server", "local_costmap"]``. | ||
|
|
||
| :``<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>: | ||
|
|
||
| ====== ======= | ||
| Type Default | ||
| ------ ------- | ||
| any N/A | ||
| ====== ======= | ||
|
|
||
| Description | ||
| 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. | ||
|
|
||
| :``<filter name>``.state_event_topic: | ||
|
|
||
| ====== ==================== | ||
| Type Default | ||
| ------ -------------------- | ||
| string "zone_filter_state" | ||
| ====== ==================== | ||
|
|
||
| Description | ||
| 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. | ||
|
|
||
| :``<filter name>``.on_param_set_failure: | ||
|
|
||
| ====== ======= | ||
| Type Default | ||
| ------ ------- | ||
| string "throw" | ||
| ====== ======= | ||
|
|
||
| Description | ||
| 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 | ||
| ---------------------------- | ||
|
|
||
| .. 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" # default | ||
| on_param_set_failure: "throw" # default; or "warn" | ||
| 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 | ||
|
|
||
| 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. | ||
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.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can we not 'get' each value at startup so we have those rather than configuring them?