From fe1900917106135d41c0b3a0e413c5edf9769b81 Mon Sep 17 00:00:00 2001 From: David Brown Date: Tue, 10 Dec 2024 20:51:36 +0100 Subject: [PATCH] document the new disable_collision_checks param (#617) * document the new disable_collision_checks param Signed-off-by: David Brown * Update migration/Jazzy.rst Signed-off-by: Steve Macenski --------- Signed-off-by: David Brown Signed-off-by: Steve Macenski Co-authored-by: Steve Macenski --- commander_api/index.rst | 9 ++++++--- .../packages/bt-plugins/actions/BackUp.rst | 13 ++++++++++++- .../packages/bt-plugins/actions/DriveOnHeading.rst | 13 ++++++++++++- configuration/packages/bt-plugins/actions/Spin.rst | 13 ++++++++++++- migration/Jazzy.rst | 10 ++++++++++ 5 files changed, 52 insertions(+), 6 deletions(-) diff --git a/commander_api/index.rst b/commander_api/index.rst index f895985e7..9b518d00d 100644 --- a/commander_api/index.rst +++ b/commander_api/index.rst @@ -74,13 +74,16 @@ New as of September 2023: the simple navigator constructor will accept a `namesp | goal_checker_id='') | ``PoseStamped``, ``nav_msgs/Path``. | +---------------------------------------+----------------------------------------------------------------------------+ | spin(spin_dist=1.57, | Requests the robot to performs an in-place rotation by a given angle. | -| time_allowance=10) | | +| time_allowance=10, | | +| disable_collision_checks=False) | | +---------------------------------------+----------------------------------------------------------------------------+ | driveOnHeading(dist=0.15, | Requests the robot to drive on heading by a given distance. | -| speed=0.025, time_allowance=10) | | +| speed=0.025, time_allowance=10, | | +| disable_collision_checks=False) | | +---------------------------------------+----------------------------------------------------------------------------+ | backup(backup_dist=0.15, | Requests the robot to back up by a given distance. | -| backup_speed=0.025, time_allowance=10)| | +| backup_speed=0.025, time_allowance=10,| | +| disable_collision_checks=False) | | +---------------------------------------+----------------------------------------------------------------------------+ | assistedTeleop(time_allowance=30) | Requests the robot to run the assisted teleop action. | +---------------------------------------+----------------------------------------------------------------------------+ diff --git a/configuration/packages/bt-plugins/actions/BackUp.rst b/configuration/packages/bt-plugins/actions/BackUp.rst index 67ea2125d..69b8ce572 100644 --- a/configuration/packages/bt-plugins/actions/BackUp.rst +++ b/configuration/packages/bt-plugins/actions/BackUp.rst @@ -67,6 +67,17 @@ Input Ports Description Action server timeout (ms). +:disable_collision_checks: + + ====== ======= + Type Default + ------ ------- + bool false + ====== ======= + + Description + Disable collision checking. + Output Ports ------------ @@ -86,4 +97,4 @@ Example .. code-block:: xml - + diff --git a/configuration/packages/bt-plugins/actions/DriveOnHeading.rst b/configuration/packages/bt-plugins/actions/DriveOnHeading.rst index 79c6fcc4e..5039a0d84 100644 --- a/configuration/packages/bt-plugins/actions/DriveOnHeading.rst +++ b/configuration/packages/bt-plugins/actions/DriveOnHeading.rst @@ -66,6 +66,17 @@ Input Ports Description Action server timeout (ms). +:disable_collision_checks: + + ====== ======= + Type Default + ------ ------- + bool false + ====== ======= + + Description + Disable collision checking. + Output Ports ------------ @@ -85,4 +96,4 @@ Example .. code-block:: xml - + diff --git a/configuration/packages/bt-plugins/actions/Spin.rst b/configuration/packages/bt-plugins/actions/Spin.rst index df89009d0..33da57000 100644 --- a/configuration/packages/bt-plugins/actions/Spin.rst +++ b/configuration/packages/bt-plugins/actions/Spin.rst @@ -67,6 +67,17 @@ Input Ports Description True if the action is being used as a recovery. +:disable_collision_checks: + + ====== ======= + Type Default + ------ ------- + bool false + ====== ======= + + Description + Disable collision checking. + Output Ports ------------ @@ -86,5 +97,5 @@ Example .. code-block:: xml - + diff --git a/migration/Jazzy.rst b/migration/Jazzy.rst index f645c84ee..fef61808e 100644 --- a/migration/Jazzy.rst +++ b/migration/Jazzy.rst @@ -189,3 +189,13 @@ They have been consolidated into a single one: The ``local_namespace`` parameter has been removed and is now automatically set to the node's name (which is what the second removed constructor did). Parameters ``parent_namespace`` / ``use_sim_time`` both provide default values to maintain the ability of creating a ``Costmap2DROS`` object by just specifying a name. + +Option to disable collision checking in DriveOnHeading, BackUp and Spin Actions +******************************************************************************* + +In `PR #4785 `_ a new boolean parameter named `disable_collision_checks` was added to the `DriveOnHeading`, `BackUp` and `Spin` actions to optionally disable collision checking. +This can be useful, for example, in cases where you want to move the robot even in the presence of known obstacles. + +Default value: + +- false \ No newline at end of file