From 9012251aec18af9a0777087f3c14672237a7f0f8 Mon Sep 17 00:00:00 2001 From: Enrico Sutera <51802424+enricosutera@users.noreply.github.com> Date: Tue, 5 Sep 2023 21:53:57 +0200 Subject: [PATCH 1/5] Added new parameters config guide --- .../costmap-plugins/binary_filter.rst | 69 ++++++++++++++++++- 1 file changed, 67 insertions(+), 2 deletions(-) diff --git a/configuration/packages/costmap-plugins/binary_filter.rst b/configuration/packages/costmap-plugins/binary_filter.rst index 5deecf3c53..42f06393b5 100644 --- a/configuration/packages/costmap-plugins/binary_filter.rst +++ b/configuration/packages/costmap-plugins/binary_filter.rst @@ -3,7 +3,7 @@ Binary Filter Parameters ======================== -Binary Filter - is a Costmap Filter that publishes a boolean topic, flipping binary state when the encoded filter space value (corresponding to the filter mask point where the robot is) is higher than given threshold. It then flips back when lower or equal. +Binary Filter - is a Costmap Filter that publishes a boolean topic, flipping binary state when the encoded filter space value (corresponding to the filter mask point where the robot is) is higher than given threshold. It then flips back when lower or equal. Along with publishing the state, the filter can change boolean ros parameters of other ros nodes. The parameters to be changed can be configured as ros paramters themselves. Filter space value is being calculated as: ``Fv = base + multiplier * mask_value``, where ``base`` and ``multiplier`` are being published in a filter info by Costmap Filter Info Server. The example of usage are include: camera operating on/off to turn off cameras in sensitive areas, headlights switch on/off for moving indoors to outdoors, smart house light triggering, etc. @@ -75,9 +75,64 @@ Filter space value is being calculated as: ``Fv = base + multiplier * mask_value double 50.0 ====== ======= - Descrioption + Description + Threshold for binary state flipping. Filter values higher than this threshold, will set binary state to non-default. + +:````.change_parameter_timeout: + + ====== ======= + Type Default + ------ ------- + int 10 + ====== ======= + + Description + Timeout for waiting `set_parameters` service in ms. Target ros parameter is not changed in case of timeout. + +:````.binary_parameters: + + ============== ======= + Type Default + -------------- ------- + vector {“”} + ============== ======= + + Description Threshold for binary state flipping. Filter values higher than this threshold, will set binary state to non-default. +:````.``binary_parameter``.node_name: + + ====== ======= + Type Default + ------ ------- + string "" + ====== ======= + + Description + Name of the node to which the ros parameter to be changed belong. + +:````.``binary_parameter``.param_name: + + ====== ======= + Type Default + ------ ------- + string "" + ====== ======= + + Description + Name of the parameter to be changed. This name should include also parameter namespace. + +:````.``binary_parameter``.default_state: + + ====== ======================================= + Type Default + ------ --------------------------------------- + bool Same as ````.default_state + ====== ======================================= + + Description + Parameter default state. If not specified, filter default state is used. + Example ******* .. code-block:: yaml @@ -97,3 +152,13 @@ Example default_state: False binary_state_topic: "/binary_state" flip_threshold: 50.0 + change_parameter_timeout: 10.0 + binary_parameters: ["param1", "param2"] + param1: + node_name: "node0" + param_name: "name.of.param1" + default_state: True + param2: + node_name: "node1" + param_name: "param2" + From 0afc07d75d0e0ef8b9b3a620bb753b7b50350273 Mon Sep 17 00:00:00 2001 From: enricosutera Date: Mon, 23 Oct 2023 21:01:37 +0200 Subject: [PATCH 2/5] Fixed copy paste description --- configuration/packages/costmap-plugins/binary_filter.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/costmap-plugins/binary_filter.rst b/configuration/packages/costmap-plugins/binary_filter.rst index 42f06393b5..48741ef4d7 100644 --- a/configuration/packages/costmap-plugins/binary_filter.rst +++ b/configuration/packages/costmap-plugins/binary_filter.rst @@ -98,7 +98,7 @@ Filter space value is being calculated as: ``Fv = base + multiplier * mask_value ============== ======= Description - Threshold for binary state flipping. Filter values higher than this threshold, will set binary state to non-default. + Namespaces of parameters to be changed. :````.``binary_parameter``.node_name: From 4ed01b2dd213b3a411fd31960b424a867aca040d Mon Sep 17 00:00:00 2001 From: Enrico Sutera <51802424+enricosutera@users.noreply.github.com> Date: Mon, 23 Oct 2023 21:03:06 +0200 Subject: [PATCH 3/5] Update configuration/packages/costmap-plugins/binary_filter.rst Co-authored-by: Steve Macenski --- configuration/packages/costmap-plugins/binary_filter.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/costmap-plugins/binary_filter.rst b/configuration/packages/costmap-plugins/binary_filter.rst index 48741ef4d7..10f3b27660 100644 --- a/configuration/packages/costmap-plugins/binary_filter.rst +++ b/configuration/packages/costmap-plugins/binary_filter.rst @@ -3,7 +3,7 @@ Binary Filter Parameters ======================== -Binary Filter - is a Costmap Filter that publishes a boolean topic, flipping binary state when the encoded filter space value (corresponding to the filter mask point where the robot is) is higher than given threshold. It then flips back when lower or equal. Along with publishing the state, the filter can change boolean ros parameters of other ros nodes. The parameters to be changed can be configured as ros paramters themselves. +Binary Filter - is a Costmap Filter that publishes a boolean topic, flipping binary state when the encoded filter space value (corresponding to the filter mask point where the robot is) is higher than given threshold. It then flips back when lower or equal. Along with publishing the state, the filter can change boolean ros parameters of other ros nodes. The parameters to be changed can be configured as ros parameters themselves. Filter space value is being calculated as: ``Fv = base + multiplier * mask_value``, where ``base`` and ``multiplier`` are being published in a filter info by Costmap Filter Info Server. The example of usage are include: camera operating on/off to turn off cameras in sensitive areas, headlights switch on/off for moving indoors to outdoors, smart house light triggering, etc. From 78a9bcb95832bde4fd75f0dc1f91993ea01cfb4c Mon Sep 17 00:00:00 2001 From: enricosutera Date: Mon, 23 Oct 2023 21:11:03 +0200 Subject: [PATCH 4/5] Added entry point in migratino guide --- migration/Iron.rst | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/migration/Iron.rst b/migration/Iron.rst index 1195c53f73..43e10d915c 100644 --- a/migration/Iron.rst +++ b/migration/Iron.rst @@ -72,3 +72,8 @@ New node in nav2_collision_monitor: Collision Detector In this `PR #3693 `_ A new node was introduced in the nav2_collision_monitor: Collision Detector. It works similarly to the Collision Monitor, but does not affect the robot's velocity. It will only inform that data from the configured sources has been detected within the configured polygons via message to the ``collision_detector_state`` topic that might be used by any external module (e.g. switching LED or sound alarm in case of collision). + +Binary Filter able to change boolean ros parameters +**************************************************** + +`PR #3796 `_ modifies the binary filter to make it able to change boolean ros parameters. \ No newline at end of file From 9794d61ae23d5735cbf7a092d4d0c06f6a4f2699 Mon Sep 17 00:00:00 2001 From: Enrico Sutera <51802424+enricosutera@users.noreply.github.com> Date: Mon, 27 Nov 2023 23:10:39 +0100 Subject: [PATCH 5/5] Update binary_filter.rst timeout is int --- configuration/packages/costmap-plugins/binary_filter.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/configuration/packages/costmap-plugins/binary_filter.rst b/configuration/packages/costmap-plugins/binary_filter.rst index 10f3b27660..d2bb147b0a 100644 --- a/configuration/packages/costmap-plugins/binary_filter.rst +++ b/configuration/packages/costmap-plugins/binary_filter.rst @@ -152,7 +152,7 @@ Example default_state: False binary_state_topic: "/binary_state" flip_threshold: 50.0 - change_parameter_timeout: 10.0 + change_parameter_timeout: 10 binary_parameters: ["param1", "param2"] param1: node_name: "node0"