Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding docs for loopback sim #580

Merged
merged 2 commits into from
Aug 9, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions configuration/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -34,4 +34,5 @@ the best navigation performance.
packages/configuring-velocity-smoother.rst
packages/configuring-collision-monitor.rst
packages/configuring-waypoint-follower.rst
packages/configuring-loopback-sim.rst
packages/configuring-docking-server.rst
82 changes: 82 additions & 0 deletions configuration/packages/configuring-loopback-sim.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
.. _configuring_loopback_sim:

Loopback Simulator
##################

Source code on Github_.

.. _Github: https://github.com/ros-navigation/navigation2/tree/main/nav2_loopback_sim


The ``nav2_loopback_sim`` is a stand-alone simulator to create a "loopback" for non-physical simulation to replace robot hardware, physics simulators (Gazebo, Bullet, Isaac Sim, etc).
It computes the robot's odometry based on the command velocity's output request to create a perfect 'frictionless plane'-style simulation for unit testing, system testing, R&D on higher level systems, testing behaviors without concerning yourself with localization accuracy or system dynamics, and multirobot simulations.

Parameters
**********

:update_duration:

============== ==============
Type Default
-------------- --------------
double 0.01
============== ==============

Description
The duration between updates (s)

:base_frame_id:

============== ==============
Type Default
-------------- --------------
string "base_link"
============== ==============

Description
The base frame to use.

:odom_frame_id:

============== ==============
Type Default
-------------- --------------
string "odom"
============== ==============

Description
The odom frame to use.

:map_frame_id:

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

Description
The map frame to use.

:scan_frame_id:

============== ==============
Type Default
-------------- --------------
string "base_scan"
============== ==============

Description
The scan frame to use to publish a scan for collision monitor's happiness

Example
*******
.. code-block:: yaml

loopback_simulator:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
map_frame_id: "map"
scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link'
update_duration: 0.02
5 changes: 5 additions & 0 deletions migration/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,11 @@ Jazzy to K-Turtle

Moving from ROS 2 Jazzy to K-Turtle, a number of stability improvements were added that we will not specifically address here.

New Nav2 Loopback Simulator
***************************

The ``nav2_looback_sim`` is a stand-alone simulator to create a "loopback" for non-physical simulation to replace robot hardware, physics simulators (Gazebo, Bullet, Isaac Sim, etc).
It computes the robot's odometry based on the command velocity's output request to create a perfect 'frictionless plane'-style simulation for unit testing, system testing, R&D on higher level systems, testing behaviors without concerning yourself with localization accuracy or system dynamics, and multirobot simulations.

New RViz panel for Docking
**************************
Expand Down