Skip to content

Commit

Permalink
Merge branch 'master' into plugin_container_layer_docs
Browse files Browse the repository at this point in the history
  • Loading branch information
alexanderjyuen committed Dec 11, 2024
2 parents 2b05cdb + 57dc73e commit cce5446
Show file tree
Hide file tree
Showing 20 changed files with 196 additions and 34 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"/>
2 changes: 1 addition & 1 deletion configuration/packages/bt-plugins/conditions/IsStopped.rst
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ Input Port
======= =======
Type Default
------- -------
double N/A
double 0.01
======= =======

Description
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -200,12 +200,13 @@ Parameters
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

Polygons parameters
===================
Expand Down Expand Up @@ -608,7 +609,7 @@ Here is an example of configuration YAML for the Collision Monitor.
source_timeout: 5.0
base_shift_correction: True
stop_pub_timeout: 2.0
enable_stamped_cmd_vel: False
enable_stamped_cmd_vel: True # False for Jazzy or older
use_realtime_priority: false
polygons: ["PolygonStop", "PolygonSlow", "FootprintApproach"]
PolygonStop:
Expand Down
14 changes: 9 additions & 5 deletions configuration/packages/configuring-behavior-server.rst
Original file line number Diff line number Diff line change
Expand Up @@ -233,12 +233,13 @@ Spin distance is given from the action request
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.


BackUp Behavior Parameters
Expand All @@ -262,12 +263,13 @@ Backup distance, speed and time_allowance is given from the action request.
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

DriveOnHeading Behavior Parameters
**********************************
Expand All @@ -290,12 +292,13 @@ DriveOnHeading distance, speed and time_allowance is given from the action reque
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

:bond_heartbeat_period:

Expand Down Expand Up @@ -351,12 +354,13 @@ AssistedTeleop time_allowance is given in the action request
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

Example
*******
Expand Down Expand Up @@ -388,4 +392,4 @@ Example
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
enable_stamped_cmd_vel: false
enable_stamped_cmd_vel: true # default false in Jazzy or older
1 change: 1 addition & 0 deletions configuration/packages/configuring-bt-xml.rst
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ Condition Plugins
bt-plugins/conditions/GloballyUpdatedGoal.rst
bt-plugins/conditions/InitialPoseReceived.rst
bt-plugins/conditions/IsStuck.rst
bt-plugins/conditions/IsStopped.rst
bt-plugins/conditions/TimeExpired.rst
bt-plugins/conditions/IsBatteryLow.rst
bt-plugins/conditions/IsPathValid.rst
Expand Down
3 changes: 2 additions & 1 deletion configuration/packages/configuring-controller-server.rst
Original file line number Diff line number Diff line change
Expand Up @@ -210,12 +210,13 @@ Parameters
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

:bond_heartbeat_period:

Expand Down
11 changes: 0 additions & 11 deletions configuration/packages/configuring-costmaps.rst
Original file line number Diff line number Diff line change
Expand Up @@ -90,17 +90,6 @@ Costmap2D ROS Parameters
Description
Minimum cost of an occupancy grid map to be considered a lethal obstacle.

:map_topic:

============== =======
Type Default
-------------- -------
string "map"
============== =======

Description
Topic of map from map_server or SLAM.

:map_vis_z:

============== =======
Expand Down
5 changes: 3 additions & 2 deletions configuration/packages/configuring-loopback-sim.rst
Original file line number Diff line number Diff line change
Expand Up @@ -74,11 +74,12 @@ Parameters
============== ==============
Type Default
-------------- --------------
string false
string True
============== ==============

Description
Whether cmd_vel is stamped or unstamped (i.e. Twist or TwistStamped)
Whether cmd_vel is stamped or unstamped (i.e. Twist or TwistStamped).
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

:scan_publish_dur:

Expand Down
3 changes: 2 additions & 1 deletion configuration/packages/configuring-velocity-smoother.rst
Original file line number Diff line number Diff line change
Expand Up @@ -153,12 +153,13 @@ Velocity Smoother Parameters
============== =============================
Type Default
-------------- -----------------------------
bool false
bool true
============== =============================

Description
Whether to use geometry_msgs::msg::Twist or geometry_msgs::msg::TwistStamped velocity data.
True uses TwistStamped, false uses Twist.
Note: This parameter is default ``false`` in Jazzy or older! Kilted or newer uses ``TwistStamped`` by default.

:bond_heartbeat_period:

Expand Down
8 changes: 8 additions & 0 deletions configuration/packages/costmap-plugins/obstacle.rst
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,14 @@ This costmap layer implements a plugin that uses 2D raycasting for 2D lidars, de
Description
Topic of data.

Relative topics will be relative to the node's parent namespace.
For example, if you specify `topic: scan` in the `obstacle_layer` of a `local_costmap` and you launch your bringup with a `tb4` namespace:

* User chosen namespace is `tb4`.
* User chosen topic is `scan`.
* Topic will be remapped to `/tb4/scan` without `local_costmap`.
* Use global topic `/scan` if you do not wish the node namespace to apply.

:``<obstacle layer>``. ``<data source>``.sensor_frame:

====== =======
Expand Down
8 changes: 8 additions & 0 deletions configuration/packages/costmap-plugins/range.rst
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,14 @@ This costmap layer implements a plugin that processes sonar, IR, or other 1-D se
Description
Range topics to subscribe to.

Relative topics will be relative to the node's parent namespace.
For example, if you specify `topics: [range1, /range2]` in the `range_layer` of a `local_costmap` and you launch your bringup with a `tb4` namespace:

* User chosen namespace is `tb4`.
* User chosen topics are [`range1`, `/range2`].
* Topic will be remapped to `/tb4/range1`, without `local_costmap`, and `/range2`.
* Use global topics such as `/range2` if you do not wish the node namespace to apply.

:``<range layer>``.phi:

====== =======
Expand Down
12 changes: 10 additions & 2 deletions configuration/packages/costmap-plugins/static.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,16 @@ This implements a costmap layer taking in a map from either SLAM or ``map_server
====== =======
Type Default
------ -------
string ""
string "map"
====== =======

Description
Map topic to subscribe to. If left empty the map topic will default to the global `map_topic` parameter in `costmap_2d_ros`.
Map topic to subscribe to.

Relative topics will be relative to the node's parent namespace.
For example, if you specify `map_topic: map` in the `static_layer` of a `global_costmap` and you launch your bringup with a `tb4` namespace:

* User chosen namespace is `tb4`.
* User chosen topic is `map`.
* Topic will be remapped to `/tb4/map` without `global_costmap`.
* Use global topic `/map` if you do not wish the node namespace to apply.
8 changes: 8 additions & 0 deletions configuration/packages/costmap-plugins/voxel.rst
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,14 @@ This costmap layer implements a plugin that uses 3D raycasting for depth, 3D, or
Description
Topic of data.

Relative topics will be relative to the node's parent namespace.
For example, if you specify `topic: scan` in the `voxel_layer` of a `local_costmap` and you launch your bringup with a `tb4` namespace:

* User chosen namespace is `tb4`.
* User chosen topic is `scan`.
* Topic will be remapped to `/tb4/scan` without `local_costmap`.
* Use global topic `/scan` if you do not wish the node namespace to apply.

:``<voxel layer>``. ``<data source>``.sensor_frame:

====== =======
Expand Down
Loading

0 comments on commit cce5446

Please sign in to comment.