Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into update-goal-updater…
Browse files Browse the repository at this point in the history
…-docs
  • Loading branch information
tonynajjar committed Jan 10, 2025
2 parents 239fb87 + a77b51d commit 849a0af
Show file tree
Hide file tree
Showing 40 changed files with 483 additions and 106 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,4 @@
_build
lib/
bin/
pyvenv.cfg
29 changes: 29 additions & 0 deletions about/roscon.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
.. _roscon:

ROSCon Talks
############

Below is a list of ROSCon talks that have been given by the Nav2 team and the community which describe important features, tuning and configuration advice, and how to work with them in your applications.

Nav2 Developer Talks
--------------------

- `ROSCon 2024: On Use of Nav2 Docking <https://vimeo.com/1024971348>`_
- `ROSCon FR 2023: Nav2 Whys over What's: Navigating the Philosophies Behind the Features <https://www.youtube.com/watch?v=2W3zWO-msEo>`_
- `ROSCon 2023: On Use of Nav2 MPPI Controller <https://vimeo.com/879001391>`_
- `ROSCon 2023: Bidirectional navigation with Nav2 <https://vimeo.com/879000809>`_
- `ROSCon 2022: On Use of Nav2 Smac Planners <https://vimeo.com/showcase/9954564/video/767157646>`_
- `ROSCon JP 2021: The Past, Present, and Future of Navigation <https://vimeo.com/638041661/a5306a02ab>`_
- `ROSCon 2021: Chronicles of Caching and Containerising CI for Nav2 <https://vimeo.com/649647161>`_
- `ROSCon 2020: Navigation2: The Next Generation Navigation System <https://vimeo.com/showcase/7812155/video/480604621>`_
- `ROSCon 2019: On Use of SLAM Toolbox <https://vimeo.com/378682207>`_
- `ROSCon 2019: Navigation 2 Overview <https://vimeo.com/378682188>`_
- `ROSCon 2018: On Use of the Spatio-Temporal Voxel Layer <https://vimeo.com/292699571>`_

Community's Talks
-----------------

- `ROSCon ES 2024: Navegación robusta en ROS2 <https://vimeo.com/showcase/11453818/video/1029492785>`_
- `ROSCon 2022: BehaviorTree.CPP 4.0. What is new and roadmap <https://vimeo.com/showcase/9954564/video/767160437>`_
- `ROSCon 2024: Mobile Robotics Scale-up Leveraging ROS <https://vimeo.com/1024971160>`_
- `ROSCon 2024: Radar Tracks for Path Planning in the presence of Dynamic Obstacles <https://vimeo.com/1024971565>`_
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"/>
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,11 @@ Input Ports

:goals:

============================================= =======
Type Default
--------------------------------------------- -------
vector<geometry_msgs::msg::PoseStamped> N/A
============================================= =======
===================================== =======
Type Default
------------------------------------- -------
geometry_msgs::msg::PoseStampedArray N/A
===================================== =======

Description
Goal poses. Takes in a blackboard variable, e.g. "{goals}".
Expand Down
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"/>
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@ Input Ports

:goals:

============================================= =======
Type Default
--------------------------------------------- -------
vector<geometry_msgs::msg::PoseStamped> N/A
============================================= =======
==================================== =======
Type Default
------------------------------------ -------
geometry_msgs::msg::PoseStampedArray N/A
==================================== =======

Description
Goal poses. Takes in a blackboard variable, e.g. "{goals}".
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ Input Ports

:input_goals:

=============================== =======
Type Default
------------------------------- -------
geometry_msgs::msg::PoseStamped N/A
=============================== =======
==================================== =======
Type Default
------------------------------------ -------
geometry_msgs::msg::PoseStampedArray N/A
==================================== =======

Description
A vector of goals to check if in collision
Expand Down
20 changes: 10 additions & 10 deletions configuration/packages/bt-plugins/actions/RemovePassedGoals.rst
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@ Input Ports

:input_goals:

===================================== =======
Type Default
------------------------------------- -------
geometry_msgs::msg::PoseStamped N/A
===================================== =======
==================================== =======
Type Default
------------------------------------ -------
geometry_msgs::msg::PoseStampedArray N/A
==================================== =======

Description
A vector of goals to check if it passed any in the current iteration.
Expand All @@ -47,11 +47,11 @@ Output Ports

:output_goals:

===================================== =======
Type Default
------------------------------------- -------
geometry_msgs::msg::PoseStamped N/A
===================================== =======
==================================== =======
Type Default
------------------------------------ -------
geometry_msgs::msg::PoseStampedArray N/A
==================================== =======

Description
A vector of goals with goals removed in proximity to the robot
Expand Down
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"/>
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@ Input Ports

:goals:

============================================ =========
Type Default
-------------------------------------------- ---------
std::vector<geometry_msgs::msg::PoseStamped> "{goals}"
============================================ =========
==================================== =========
Type Default
------------------------------------ ---------
geometry_msgs::msg::PoseStampedArray "{goals}"
==================================== =========

Description
Vector of goals to check. Takes in a blackboard variable, "{goals}" if not specified.
Expand Down
10 changes: 5 additions & 5 deletions configuration/packages/bt-plugins/conditions/GoalUpdated.rst
Original file line number Diff line number Diff line change
Expand Up @@ -22,11 +22,11 @@ Input Ports

:goals:

============================================ =========
Type Default
-------------------------------------------- ---------
std::vector<geometry_msgs::msg::PoseStamped> "{goals}"
============================================ =========
==================================== =========
Type Default
------------------------------------ ---------
geometry_msgs::msg::PoseStampedArray "{goals}"
==================================== =========

Description
Vector of goals to check. Takes in a blackboard variable, "{goals}" if not specified.
Expand Down
10 changes: 5 additions & 5 deletions configuration/packages/bt-plugins/decorators/SpeedController.rst
Original file line number Diff line number Diff line change
Expand Up @@ -79,11 +79,11 @@ Input Ports

:goals:

============================================ =========
Type Default
-------------------------------------------- ---------
std::vector<geometry_msgs::msg::PoseStamped> "{goals}"
============================================ =========
==================================== =========
Type Default
------------------------------------ ---------
geometry_msgs::msg::PoseStampedArray "{goals}"
==================================== =========

Description
Vector of goals to check. Takes in a blackboard variable, "{goals}" if not specified.
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
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
12 changes: 1 addition & 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 Expand Up @@ -360,6 +349,7 @@ Plugin Parameters
costmap-plugins/voxel.rst
costmap-plugins/range.rst
costmap-plugins/denoise.rst
costmap-plugins/plugin_container.rst

Costmap Filters Parameters
**************************
Expand Down
Loading

0 comments on commit 849a0af

Please sign in to comment.