diff --git a/README.md b/README.md
index 5706c732..4cf6656b 100644
--- a/README.md
+++ b/README.md
@@ -95,6 +95,37 @@ source install/setup.bash
ros2 launch rosbot_gazebo simulation.launch.py
```
+### Launch Arguments
+
+| Symbol | Meaning |
+| ------ | ---------------------------- |
+| đ¤ | Available for physical robot |
+| đĨī¸ | Available in simulation |
+
+| đ¤ | đĨī¸ | Argument | Description
***Type:*** `Default` |
+| --- | --- | ------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| â
| â
| `namespace` | Namespace for all topics and tfs.
***string:*** `env(ROBOT_NAMESPACE)` |
+| â
| â | `mecanum` | Whether to use mecanum drive controller (otherwise diff drive controller is used).
***bool:*** `False` |
+| â
| â | `microros` | Automatically connect with hardware using microros.
***bool:*** `True` |
+| â
| â | `serial_baudrate` | Baud rate for serial communication .
***string:*** `576000` |
+| â
| â | `serial_port` | Automatically connect with hardware using microros.
***string:*** `/dev/ttySERIAL` |
+| â
| â | `fastrtps_profiles` | Path to the Fast RTPS default profiles file for Micro-ROS agent for localhost only setup.
***string:*** [`microros_localhost_only.xml`](./rosbot_bringup/config/microros_localhost_only.xml) |
+| â | â
| `gz_gui` | Run simulation with specific GUI layout.
***string:*** [`teleop.config`](https://github.com/husarion/husarion_gz_worlds/blob/main/config/teleop.config) |
+| â | â
| `gz_headless_mode` | Run the simulation in headless mode. Useful when a GUI is not needed or to reduce the number of calculations.
***bool:*** `False` |
+| â | â
| `gz_log_level` | Adjust the level of console output.
***int:*** `1` (choices: `0`, `1`, `2`, `3`, `4`) |
+| â | â
| `gz_world` | Absolute path to SDF world file.
***string:*** [`husarion_world.sdf`](https://github.com/husarion/husarion_gz_worlds/blob/main/worlds/husarion_world.sdf) |
+| â | â
| `robots` | Spawning multiple robots at positions with yaw orientations e.g.robots:='robot1={x: 0.0, y: -1.0}; robot2={x: 1.0, y: -1.0};'
***string:*** `''` |
+| â | â
| `x` | Initial robot position in the global 'x' axis.
***float:*** `0.0` |
+| â | â
| `y` | Initial robot position in the global 'y' axis.
***float:***`-2.0` |
+| â | â
| `z` | Initial robot position in the global 'z' axis.
***float:*** `0.0` |
+| â | â
| `roll` | Initial robot 'roll' orientation.
***float:*** `0.0` |
+| â | â
| `pitch` | Initial robot 'pitch' orientation.
***float:*** `0.0` |
+| â | â
| `yaw` | Initial robot 'yaw' orientation.
***float:*** `0.0` |
+
+> [!TIP]
+>
+> To read the arguments for individual packages, add the `-s` flag to the `ros2 launch` command (e.g. `ros2 launch rosbot_bringup bringup.launch.py ââ-s`)
+
## đšī¸ Demo
Explore demos showcasing the capabilities of ROSbots:
diff --git a/ROS_API.md b/ROS_API.md
index ae4480a0..537db6a5 100644
--- a/ROS_API.md
+++ b/ROS_API.md
@@ -17,17 +17,6 @@ Package that contains launch, which starts all base functionalities with the mic
- `bringup.launch.py` - is responsible for communicating with firmware and activating all logic related to the robot's movement and processing of sensory data.
- `microros.launch.py` - establishes connection with the firmware.
-**Launch Params:**
-
-| PARAMETER | DESCRIPTION | VALUE |
-| ------------------------ | ----------------------------------------------------------------- | ---------- |
-| **camera_model** | Add camera model to the robot URDF | **None**\* |
-| **lidar_model** | Add LiDAR model to the robot URDF | **None**\* |
-| **include_camera_mount** | Whether to include camera mount to the robot URDF | **False** |
-| **mecanum** | Whether to use mecanum drive controller, otherwise use diff drive | **False** |
-| **namespace** | Namespace for all topics and tfs | **""** |
-
-> \*You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_bringup bringup.launch.py -s`).
### `rosbot_controller`
@@ -52,45 +41,10 @@ Launch files for Ignition Gazebo working with ROS2 control.
- `simulations.launch.py` - running a rosbot in Gazebo simulator and simulate all specified sensors.
-**Launch Params:**
-
-| PARAMETER | DESCRIPTION | VALUE |
-| ------------------------ | ----------------------------------------------------------------- | ----------------------------------------------------------- |
-| **camera_model** | Add camera model to the robot URDF | **None**\* |
-| **lidar_model** | Add LiDAR model to the robot URDF | **None**\* |
-| **include_camera_mount** | Whether to include camera mount to the robot URDF | **False** |
-| **mecanum** | Whether to use mecanum drive controller, otherwise use diff drive | **False** |
-| **namespace** | Namespace for all topics and tfs | **""** |
-| **world** | Path to SDF world file | **`husarion_gz_worlds/`
`worlds/husarion_world.sdf`** |
-| **headless** | Run Gazebo Ignition in the headless mode | **False** |
-| **robots** | List of robots that will be spawn in the simulation | **[]**\*\* |
-
-> \*You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_bringup bringup.launch.py -s`).
->
-> \*\*Example of use: `robots:='robot1={x: 0.0, y: -1.0}; robot2={x: 1.0, y: -1.0};'`
-
### `rosbot_utils`
This package contains the stable firmware version with the flash script.
-### `rosbot_navigation`
-
-Package that contains navigation configurations and launch files for ROSbot. It integrates with `nav2` for autonomous navigation.
-
-**Available Launch Files:**
-
-- `navigation.launch.py` - launches the navigation stack with predefined parameters.
-
-**Launch Params:**
-
-| PARAMETER | DESCRIPTION | VALUE |
-| ------------------------ | ----------------------------------------------------------------- | ---------- |
-| **map** | Path to the map file used for navigation | **""** |
-| **use_sim_time** | Whether to use simulation time | **False** |
-| **params_file** | Path to the parameters file for navigation stack | **""** |
-
-> You can check all available options using `-s`/`--show-args` flag. (e.g. `ros2 launch rosbot_navigation navigation.launch.py -s`).
-
## ROS API
### Available Nodes
diff --git a/rosbot_bringup/launch/microros.launch.py b/rosbot_bringup/launch/microros.launch.py
index 512419ba..2510a88e 100644
--- a/rosbot_bringup/launch/microros.launch.py
+++ b/rosbot_bringup/launch/microros.launch.py
@@ -37,9 +37,7 @@ def generate_microros_agent_node(context, *args, **kwargs):
serial_port = LaunchConfiguration("serial_port").perform(context)
serial_baudrate = LaunchConfiguration("serial_baudrate").perform(context)
- localhost_only_fastrtps_profiles_file = LaunchConfiguration(
- "localhost_only_fastrtps_profiles_file"
- ).perform(context)
+ fastrtps_profiles = LaunchConfiguration("fastrtps_profiles").perform(context)
if os.environ.get("ROS_LOCALHOST_ONLY") == "1":
env_setup_actions.extend(
@@ -47,14 +45,14 @@ def generate_microros_agent_node(context, *args, **kwargs):
LogInfo(
msg=[
"ROS_LOCALHOST_ONLY set to 1. Using FASTRTPS_DEFAULT_PROFILES_FILE=",
- localhost_only_fastrtps_profiles_file,
+ fastrtps_profiles,
".",
]
),
SetEnvironmentVariable(name="RMW_IMPLEMENTATION", value="rmw_fastrtps_cpp"),
SetEnvironmentVariable(
name="FASTRTPS_DEFAULT_PROFILES_FILE",
- value=localhost_only_fastrtps_profiles_file,
+ value=fastrtps_profiles,
),
]
)
@@ -92,12 +90,11 @@ def generate_launch_description():
fastrtps_profiles_file = PathJoinSubstitution(
[FindPackageShare("rosbot_bringup"), "config", "microros_localhost_only.xml"]
)
- declare_localhost_only_fastrtps_profiles_file_arg = DeclareLaunchArgument(
- "localhost_only_fastrtps_profiles_file",
+ declare_fastrtps_profiles_arg = DeclareLaunchArgument(
+ "fastrtps_profiles",
default_value=fastrtps_profiles_file,
description=(
- "Path to the Fast RTPS default profiles file for Micro-ROS agent for localhost only"
- " setup"
+ "Path to the Fast RTPS default profiles file for Micro-ROS agent for localhost only setup"
),
)
@@ -105,7 +102,7 @@ def generate_launch_description():
[
declare_serial_port_arg,
declare_serial_baudrate_arg,
- declare_localhost_only_fastrtps_profiles_file_arg,
+ declare_fastrtps_profiles_arg,
OpaqueFunction(function=generate_microros_agent_node),
]
)