Skip to content

Commit

Permalink
document the new disable_collision_checks param (#617)
Browse files Browse the repository at this point in the history
* document the new disable_collision_checks param

Signed-off-by: David Brown <[email protected]>

* Update migration/Jazzy.rst

Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: David Brown <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
david-wb and SteveMacenski authored Dec 10, 2024
1 parent a9d4deb commit fe19009
Show file tree
Hide file tree
Showing 5 changed files with 52 additions and 6 deletions.
9 changes: 6 additions & 3 deletions commander_api/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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. |
+---------------------------------------+----------------------------------------------------------------------------+
Expand Down
13 changes: 12 additions & 1 deletion configuration/packages/bt-plugins/actions/BackUp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,17 @@ Input Ports
Description
Action server timeout (ms).

:disable_collision_checks:

====== =======
Type Default
------ -------
bool false
====== =======

Description
Disable collision checking.

Output Ports
------------

Expand All @@ -86,4 +97,4 @@ Example

.. code-block:: xml
<BackUp backup_dist="-0.2" backup_speed="0.05" server_name="backup_server" server_timeout="10" error_code_id="{backup_error_code}"/>
<BackUp backup_dist="-0.2" backup_speed="0.05" server_name="backup_server" server_timeout="10" error_code_id="{backup_error_code}" disable_collision_checks="false"/>
13 changes: 12 additions & 1 deletion configuration/packages/bt-plugins/actions/DriveOnHeading.rst
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,17 @@ Input Ports
Description
Action server timeout (ms).

:disable_collision_checks:

====== =======
Type Default
------ -------
bool false
====== =======

Description
Disable collision checking.

Output Ports
------------

Expand All @@ -85,4 +96,4 @@ Example

.. code-block:: xml
<DriveOnHeading dist_to_travel="0.2" speed="0.05" server_name="backup_server" server_timeout="10" error_code_id="{drive_on_heading_error_code}"/>
<DriveOnHeading dist_to_travel="0.2" speed="0.05" server_name="backup_server" server_timeout="10" error_code_id="{drive_on_heading_error_code}" disable_collision_checks="false"/>
13 changes: 12 additions & 1 deletion configuration/packages/bt-plugins/actions/Spin.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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
------------

Expand All @@ -86,5 +97,5 @@ Example

.. code-block:: xml
<Spin spin_dist="1.57" server_name="spin" server_timeout="10" is_recovery="true" error_code_id="{spin_error_code}"/>
<Spin spin_dist="1.57" server_name="spin" server_timeout="10" is_recovery="true" error_code_id="{spin_error_code}" disable_collision_checks="false"/>
10 changes: 10 additions & 0 deletions migration/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://github.com/ros-navigation/navigation2/pull/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

0 comments on commit fe19009

Please sign in to comment.