Skip to content

Commit

Permalink
Add note on multirobot refactor to migration guide (#609)
Browse files Browse the repository at this point in the history
* Add note on multirobot refactor to migration guide

Signed-off-by: Luca Della Vedova <[email protected]>

* Add example for configuration of sensor topic

Signed-off-by: Luca Della Vedova <[email protected]>

* Add notes to topic configuration guides

Signed-off-by: Luca Della Vedova <[email protected]>

* Fix formatting

Signed-off-by: Luca Della Vedova <[email protected]>

* Remove use_namespace parameter

Signed-off-by: Luca Della Vedova <[email protected]>

* Remove map_topic parameter and add migration note

Signed-off-by: Luca Della Vedova <[email protected]>

* Update Jazzy.rst

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

* Add migration note on Costmap2DROS constructors

Signed-off-by: Luca Della Vedova <[email protected]>

* Change all literals to double backtick

Signed-off-by: Luca Della Vedova <[email protected]>

* Grammar

Signed-off-by: Luca Della Vedova <[email protected]>

* Update default value / remove reference to global param

Signed-off-by: Luca Della Vedova <[email protected]>

---------

Signed-off-by: Luca Della Vedova <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
luca-della-vedova and SteveMacenski authored Dec 3, 2024
1 parent 4ed69b6 commit f7e5776
Show file tree
Hide file tree
Showing 7 changed files with 102 additions and 16 deletions.
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
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
68 changes: 67 additions & 1 deletion migration/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -108,4 +108,70 @@ In `PR #4752 <https://github.com/ros-navigation/navigation2/pull/4752>`_ an opti

Default value:

- true
- true

Revamped multirobot bringup and config files to use namespaces
**************************************************************

In `PR #4715 <https://github.com/ros-navigation/navigation2/pull/4715>`_ multirobot bringup and the use of namespaces were overhauled to be compatible out of the box with ROS namespaces and remove custom logic, specifically:

* The ``use_namespace`` parameter has been removed from ``nav2_bringup`` launch files. The ``namespace`` parameter will now always be used and default to ``/`` for "global namespace".
* There is now a single rviz config file for both normal and namespaced robots. Topics have been changed to a relative path (i.e. ``/map`` -> ``map``) and the rviz ``namespace`` will be added automatically.
* There is now a single ``nav2_params.yaml`` config file for both single and multirobot bringup. All the topics have been changed to relative (i.e. ``/scan`` -> ``scan``).

Note that some plugins / nodes might have their own local namespace. This is the case for ``CostmapLayer`` which will be in a ``/ns/[layer_name]`` namespace. For these, a new function ``joinWithParentNamespace`` has been added to make sure joining relative paths results in ``/ns/topic_name`` rather than ``/ns/[layer_name]/topic_name``.

If your use case doesn't require multiple robots, keeping absolute paths in your ``nav2_params.yaml`` config file and rviz config file will preserve existing behavior.

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

Removed global map_topic from Costmap node
******************************************

In `PR #4715 <https://github.com/ros-navigation/navigation2/pull/4715>`_ the global ``map_topic`` parameter has been removed from the ``Costmap2DROS`` node. This parameterwas only used in the ``StaticLayer`` and should be defined as a parameter local to the ``StaticLayer`` instead, for example:

.. code-block:: yaml
global_costmap:
global_costmap:
ros__parameters:
[...]
# Not supported anymore
map_topic: my_map
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
# Do this instead
map_topic: my_map
Simplified Costmap2DROS constructors
************************************

The following constructors for ``Costmap2DROS`` have been removed:

.. code-block:: cpp
explicit Costmap2DROS(
const std::string & name,
const std::string & parent_namespace,
const std::string & local_namespace,
const bool & use_sim_time);
explicit Costmap2DROS(const std::string & name, const bool & use_sim_time = false);
They have been consolidated into a single one:

.. code-block:: cpp
explicit Costmap2DROS(
const std::string & name,
const std::string & parent_namespace = "/",
const bool & use_sim_time = false);
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.
3 changes: 1 addition & 2 deletions tuning/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,7 @@ Within ``nav2_bringup``, there is a main entryfile ``tb3_simulation_launch.py``.
- ``use_robot_state_pub`` : Whether or not to start the robot state publisher to publish the robot's URDF transformations to TF2. Defaults to ``true`` to publish the robot's TF2 transformations.
- ``use_rviz`` : Whether or not to launch rviz for visualization. Defaults to ``true`` to show rviz.
- ``headless`` : Whether or not to launch the Gazebo front-end alongside the background Gazebo simulation. Defaults to ``true`` to display the Gazebo window.
- ``namespace`` : The namespace to launch robots into, if need be.
- ``use_namespace`` : Whether or not to launch robots into this namespace. Default ``false`` and uses global namespace for single robot.
- ``namespace`` : The namespace to launch robots into.
- ``robot_name`` : The name of the robot to launch.
- ``robot_sdf`` : The filepath to the robot's gazebo configuration file containing the Gazebo plugins and setup to simulate the robot system.
- ``x_pose``, ``y_pose``, ``z_pose``, ``roll``, ``pitch``, ``yaw`` : Parameters to set the initial position of the robot in the simulation.
Expand Down

0 comments on commit f7e5776

Please sign in to comment.