From 1b0f33f9d217da794bb8a48781467ddc1686fcef Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Wed, 8 Apr 2026 08:52:36 +0000 Subject: [PATCH 1/3] Docs for Loopback Simulator C++ migration Signed-off-by: Tony Najjar --- .../packages/configuring-loopback-sim.rst | 55 ++++++++++++++++++- migration/Kilted.rst | 13 +++++ 2 files changed, 65 insertions(+), 3 deletions(-) diff --git a/configuration/packages/configuring-loopback-sim.rst b/configuration/packages/configuring-loopback-sim.rst index c9cc015ddd..03a8e1f322 100644 --- a/configuration/packages/configuring-loopback-sim.rst +++ b/configuration/packages/configuring-loopback-sim.rst @@ -86,34 +86,68 @@ Parameters ============== ============== Type Default -------------- -------------- - string 0.1 + double 0.1 ============== ============== Description The duration between publishing scan (in sec) +:odom_publish_dur: + + ============== ============== + Type Default + -------------- -------------- + double + ============== ============== + + Description + The duration between publishing odometry (in sec). Defaults to ``update_duration``. + :publish_map_odom_tf: ============== ============== Type Default -------------- -------------- - string true + bool true ============== ============== Description Whether or not to publish tf from ``map_frame_id`` to ``odom_frame_id`` +:publish_scan: + + ============== ============== + Type Default + -------------- -------------- + bool true + ============== ============== + + Description + Whether or not to publish a fake laser scan. + :publish_clock: ============== ============== Type Default -------------- -------------- - string true + bool true ============== ============== Description Whether or not to publish simulated clock to ``/clock`` +:speed_factor: + + ============== ============== + Type Default + -------------- -------------- + double 1.0 + ============== ============== + + Description + Speed factor for the simulated clock, e.g. ``2.0`` runs simulation at 2x wall time. + Only used when ``publish_clock`` is ``true``. Dynamically reconfigurable. + :scan_range_min: ============== ============== @@ -181,6 +215,17 @@ Parameters Whether to use ``inf`` for out-of-range values. If ``false``, values are set to ``scan_range_max - 0.1`` instead. +:scan_noise_std: + + ============== ============== + Type Default + -------------- -------------- + double 0.01 + ============== ============== + + Description + Standard deviation of Gaussian noise added to scan ranges (in meters). + Example ******* .. code-block:: yaml @@ -192,9 +237,13 @@ Example map_frame_id: "map" scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link' update_duration: 0.02 + publish_scan: true + publish_clock: true + speed_factor: 1.0 scan_range_min: 0.05 scan_range_max: 30.0 scan_angle_min: -3.1415 scan_angle_max: 3.1415 scan_angle_increment: 0.02617 scan_use_inf: true + scan_noise_std: 0.01 diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 5156a9d81f..4bd4aacad0 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -908,3 +908,16 @@ Earlier, `nav2_constrained_smoother` was using a cost formulation of :math:`cost The internal squaring of `Ceres` is now considered and the cost formulation is corrected to :math:`cost = w_1 * cost_1^2 + w_2 * cost_2^2 + ...`. This makes the constrained smoother approximately 10x faster in testing and results in converged solutions and improved path quality. A detailed analysis of improvement is available in: `Issue #5072 `_ Values for the weights will need to be retuned for all users, unfortunately, but will get faster and more reliable results! + +Nav2 Loopback Simulator converted to C++ +----------------------------------------- + +`PR #6062 `_ converts ``nav2_loopback_sim`` from Python to C++ for improved performance and consistency with the rest of the Nav2 stack. + +Key changes: + +- The ``clock_publisher`` is no longer a separate node. It is now embedded within the ``loopback_simulator`` node. Launch files that previously launched both nodes should be updated to launch only the ``loopback_simulator`` node. +- A new ``speed_factor`` parameter (default ``1.0``) controls the simulated clock speed (e.g. ``2.0`` for 2x). This parameter is dynamically reconfigurable. +- New parameters ``publish_scan``, ``odom_publish_dur``, and ``scan_noise_std`` are available. + +See :ref:`configuring_loopback_sim` for full parameter documentation. From 5140f630d41b0671e27d9e4ff2391df90adb76d1 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Thu, 9 Apr 2026 09:20:22 +0000 Subject: [PATCH 2/3] Update odom_publish_dur parameter description for clarity and improve performance note for Loopback Simulator migration to C++ Signed-off-by: Tony Najjar --- configuration/packages/configuring-loopback-sim.rst | 6 +++--- migration/Kilted.rst | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/configuration/packages/configuring-loopback-sim.rst b/configuration/packages/configuring-loopback-sim.rst index 03a8e1f322..185447bfb4 100644 --- a/configuration/packages/configuring-loopback-sim.rst +++ b/configuration/packages/configuring-loopback-sim.rst @@ -94,11 +94,11 @@ Parameters :odom_publish_dur: - ============== ============== + ============== ================= Type Default - -------------- -------------- + -------------- ----------------- double - ============== ============== + ============== ================= Description The duration between publishing odometry (in sec). Defaults to ``update_duration``. diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 4bd4aacad0..8c0698e52d 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -912,7 +912,7 @@ Values for the weights will need to be retuned for all users, unfortunately, but Nav2 Loopback Simulator converted to C++ ----------------------------------------- -`PR #6062 `_ converts ``nav2_loopback_sim`` from Python to C++ for improved performance and consistency with the rest of the Nav2 stack. +`PR #6062 `_ converts ``nav2_loopback_sim`` from Python to C++ for improved performance and consistency with the rest of the Nav2 stack. This results in roughly a 2x improvement in CPU consumption. Key changes: From aa1a21bea5086ae2faed3bc7443143e06636f754 Mon Sep 17 00:00:00 2001 From: Tony Najjar Date: Thu, 9 Apr 2026 18:38:43 +0200 Subject: [PATCH 3/3] Update migration/Kilted.rst Co-authored-by: Steve Macenski Signed-off-by: Tony Najjar --- migration/Kilted.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 8c0698e52d..ff61b9637e 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -910,7 +910,7 @@ The internal squaring of `Ceres` is now considered and the cost formulation is c Values for the weights will need to be retuned for all users, unfortunately, but will get faster and more reliable results! Nav2 Loopback Simulator converted to C++ ------------------------------------------ +---------------------------------------- `PR #6062 `_ converts ``nav2_loopback_sim`` from Python to C++ for improved performance and consistency with the rest of the Nav2 stack. This results in roughly a 2x improvement in CPU consumption.