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

[ros2] Fix parameter loading in launch files (VLP16, VLP32C, VLS128)Fix launch file params #556

Closed
wants to merge 3 commits into from
Closed
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
8 changes: 6 additions & 2 deletions velodyne_driver/launch/velodyne_driver_node-VLP16-launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
"""Launch the velodyne driver node with default configuration."""

import os

import yaml
import ament_index_python.packages
import launch
import launch_ros.actions
Expand All @@ -43,7 +43,11 @@ def generate_launch_description():
config_directory = os.path.join(
ament_index_python.packages.get_package_share_directory('velodyne_driver'),
'config')
params = os.path.join(config_directory, 'VLP16-velodyne_driver_node-params.yaml')
param_config = os.path.join(config_directory, 'VLP16-velodyne_driver_node-params.yaml')

# Load the parameters from YAML file
with open(param_config, 'r') as f:
params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']
velodyne_driver_node = launch_ros.actions.Node(package='velodyne_driver',
executable='velodyne_driver_node',
output='both',
Expand Down
8 changes: 7 additions & 1 deletion velodyne_driver/launch/velodyne_driver_node-VLP32C-launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
"""Launch the velodyne driver node with default configuration."""

import os
import yaml

import ament_index_python.packages
import launch
Expand All @@ -43,7 +44,12 @@ def generate_launch_description():
config_directory = os.path.join(
ament_index_python.packages.get_package_share_directory('velodyne_driver'),
'config')
params = os.path.join(config_directory, 'VLP32C-velodyne_driver_node-params.yaml')
param_config = os.path.join(config_directory, 'VLP32C-velodyne_driver_node-params.yaml')

# Load the parameters from YAML file
with open(param_config, 'r') as f:
params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']

velodyne_driver_node = launch_ros.actions.Node(package='velodyne_driver',
executable='velodyne_driver_node',
output='both',
Expand Down
7 changes: 6 additions & 1 deletion velodyne_driver/launch/velodyne_driver_node-VLS128-launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
"""Launch the velodyne driver node with default configuration."""

import os
import yaml

import ament_index_python.packages
import launch
Expand All @@ -43,7 +44,11 @@ def generate_launch_description():
config_directory = os.path.join(
ament_index_python.packages.get_package_share_directory('velodyne_driver'),
'config')
params = os.path.join(config_directory, 'VLS128-velodyne_driver_node-params.yaml')
param_config = os.path.join(config_directory, 'VLS128-velodyne_driver_node-params.yaml')

# Load the parameters from YAML file
with open(param_config, 'r') as f:
params = yaml.safe_load(f)['velodyne_driver_node']['ros__parameters']
velodyne_driver_node = launch_ros.actions.Node(package='velodyne_driver',
executable='velodyne_driver_node',
output='both',
Expand Down