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

Giving high priority to params given in YAML config file #2893

Open
wants to merge 1 commit into
base: ros2-development
Choose a base branch
from
Open
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
38 changes: 38 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -369,6 +369,10 @@ User can set the camera name and camera namespace, to distinguish between camera
- double, positive values set the period between diagnostics updates on the `/diagnostics` topic.
- 0 or negative values mean no diagnostics topic is published. Defaults to 0.</br>
The `/diagnostics` topic includes information regarding the device temperatures and actual frequency of the enabled streams.
- **json_file_path**:
- JSON file with advanced configurations like depth presets.
- The user can get predefined depth presets from 'realsense-viewer' or https://dev.intelrealsense.com/docs/d400-series-visual-presets based on their usecase.
- Note: Once these configurations are loaded, it will remain in the device until there is a reset or power cycle.

<hr>

Expand Down Expand Up @@ -604,6 +608,40 @@ The launch file accepts a parameter, `intra_process_comms`, controlling whether
ros2 launch realsense2_camera rs_intra_process_demo_launch.py intra_process_comms:=true
```

<hr>

### Providing launch params in YAML file:
Generally, the launch params can be provided in 'ros2 launch' command. For example:
```bash
ros2 launch realsense2_camera rs_launch.py enable_depth:=true enable_color:=true
```

Alternatively, they can be defined in a YAML file and that YAML file can be passed through 'config_file' param.
For example:
```bash
ros2 launch realsense2_camera rs_launch.py config_file:='/full/path/to/config.yaml'
```

The yaml file should have the launch params' in the following syntax:
- <`param_name`>: <`value`>

Example `config.yaml` file:
```bash
enable_depth: true
enable_color: true
rgb_camera.color_format: RGB8
tf_publish_rate: 10.0
```

Note:
- If a same param is set in both YAML file and in ros2 launch command, the value set in YAML will have high priority. For example:
- Let's say, in command line, 'enable_depth' is set to true:
- `ros2 launch realsense2_camera rs_launch.py config_file:='/full/path/to/config.yaml' enable_depth:=true`
- And in config.yaml, 'enable_depth' is set to false:
- `enable_depth: false`
- The param provided in command line during launch will be overwritten by the value provided in YAML file.
- So, the result will be `enable_depth = false`

</details>


Expand Down
20 changes: 12 additions & 8 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -96,16 +96,20 @@ def yaml_to_dict(path_to_yaml):
def launch_setup(context, params, param_name_suffix=''):
_config_file = LaunchConfiguration('config_file' + param_name_suffix).perform(context)
params_from_file = {} if _config_file == "''" else yaml_to_dict(_config_file)

# Overwrite the params with the values provided in YAML config file
params.update(params_from_file)

return [
launch_ros.actions.Node(
package='realsense2_camera',
namespace=LaunchConfiguration('camera_namespace' + param_name_suffix),
name=LaunchConfiguration('camera_name' + param_name_suffix),
executable='realsense2_camera_node',
parameters=[params, params_from_file],
output=LaunchConfiguration('output' + param_name_suffix),
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level' + param_name_suffix)],
emulate_tty=True,
package = 'realsense2_camera',
namespace = params['camera_namespace'],
name = params['camera_name'],
executable = 'realsense2_camera_node',
parameters = [params],
output = params['output'],
arguments = ['--ros-args', '--log-level', params['log_level']],
emulate_tty = True,
)
]

Expand Down
Loading