Skip to content

Commit

Permalink
Update rs_launch.py
Browse files Browse the repository at this point in the history
add namespace launch argument
  • Loading branch information
hyunseok-yang committed Jun 6, 2023
1 parent dad99e5 commit 4c53382
Showing 1 changed file with 18 additions and 17 deletions.
35 changes: 18 additions & 17 deletions realsense2_camera/launch/rs_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@


configurable_parameters = [{'name': 'camera_name', 'default': 'camera', 'description': 'camera unique name'},
{'name': 'namespace', 'default': '', 'description': 'namespace for camera'},
{'name': 'serial_no', 'default': "''", 'description': 'choose device by serial number'},
{'name': 'usb_port_id', 'default': "''", 'description': 'choose device by usb port id'},
{'name': 'device_type', 'default': "''", 'description': 'choose device by type'},
Expand All @@ -30,7 +31,7 @@
{'name': 'json_file_path', 'default': "''", 'description': 'allows advanced configuration'},
{'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'},
{'name': 'output', 'default': 'screen', 'description': 'pipe node output [screen|log]'},
{'name': 'depth_module.profile', 'default': '0,0,0', 'description': 'depth module profile'},
{'name': 'depth_module.profile', 'default': '0,0,0', 'description': 'depth module profile'},
{'name': 'enable_depth', 'default': 'true', 'description': 'enable depth stream'},
{'name': 'rgb_camera.profile', 'default': '0,0,0', 'description': 'color image width'},
{'name': 'rgb_camera.enable_auto_exposure', 'default': 'true', 'description': 'enable/disable auto exposure for color image'},
Expand All @@ -41,22 +42,22 @@
{'name': 'enable_fisheye1', 'default': 'true', 'description': 'enable fisheye1 stream'},
{'name': 'enable_fisheye2', 'default': 'true', 'description': 'enable fisheye2 stream'},
{'name': 'enable_confidence', 'default': 'true', 'description': 'enable depth stream'},
{'name': 'gyro_fps', 'default': '0', 'description': "''"},
{'name': 'accel_fps', 'default': '0', 'description': "''"},
{'name': 'enable_gyro', 'default': 'false', 'description': "''"},
{'name': 'enable_accel', 'default': 'false', 'description': "''"},
{'name': 'enable_pose', 'default': 'true', 'description': "''"},
{'name': 'pose_fps', 'default': '200', 'description': "''"},
{'name': 'pointcloud.enable', 'default': 'false', 'description': ''},
{'name': 'gyro_fps', 'default': '0', 'description': "''"},
{'name': 'accel_fps', 'default': '0', 'description': "''"},
{'name': 'enable_gyro', 'default': 'false', 'description': "''"},
{'name': 'enable_accel', 'default': 'false', 'description': "''"},
{'name': 'enable_pose', 'default': 'true', 'description': "''"},
{'name': 'pose_fps', 'default': '200', 'description': "''"},
{'name': 'pointcloud.enable', 'default': 'false', 'description': ''},
{'name': 'pointcloud.stream_filter', 'default': '2', 'description': 'texture stream for pointcloud'},
{'name': 'pointcloud.stream_index_filter','default': '0', 'description': 'texture stream index for pointcloud'},
{'name': 'enable_sync', 'default': 'false', 'description': "''"},
{'name': 'align_depth.enable', 'default': 'false', 'description': "''"},
{'name': 'enable_sync', 'default': 'false', 'description': "''"},
{'name': 'align_depth.enable', 'default': 'false', 'description': "''"},
{'name': 'colorizer.enable', 'default': 'false', 'description': "''"},
{'name': 'clip_distance', 'default': '-2.', 'description': "''"},
{'name': 'linear_accel_cov', 'default': '0.01', 'description': "''"},
{'name': 'initial_reset', 'default': 'false', 'description': "''"},
{'name': 'allow_no_texture_points', 'default': 'false', 'description': "''"},
{'name': 'clip_distance', 'default': '-2.', 'description': "''"},
{'name': 'linear_accel_cov', 'default': '0.01', 'description': "''"},
{'name': 'initial_reset', 'default': 'false', 'description': "''"},
{'name': 'allow_no_texture_points', 'default': 'false', 'description': "''"},
{'name': 'pointcloud.ordered_pc', 'default': 'false', 'description': ''},
{'name': 'publish_tf', 'default': 'true', 'description': '[bool] enable/disable publishing static & dynamic TF'},
{'name': 'tf_publish_rate', 'default': '0.0', 'description': '[double] rate in Hz for publishing dynamic TF'},
Expand Down Expand Up @@ -94,7 +95,7 @@ def launch_setup(context, *args, **kwargs):
return [
launch_ros.actions.Node(
package='realsense2_camera',
node_namespace=LaunchConfiguration("camera_name"),
node_namespace=(LaunchConfiguration("namespace"), "/", LaunchConfiguration("camera_name")),
node_name=LaunchConfiguration("camera_name"),
node_executable='realsense2_camera_node',
prefix=['stdbuf -o L'],
Expand All @@ -109,7 +110,7 @@ def launch_setup(context, *args, **kwargs):
return [
launch_ros.actions.Node(
package='realsense2_camera',
namespace=LaunchConfiguration("camera_name"),
namespace=(LaunchConfiguration("namespace"), "/", LaunchConfiguration("camera_name")),
name=LaunchConfiguration("camera_name"),
executable='realsense2_camera_node',
parameters=[set_configurable_parameters(configurable_parameters)
Expand All @@ -120,7 +121,7 @@ def launch_setup(context, *args, **kwargs):
emulate_tty=True,
)
]

def generate_launch_description():
return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [
OpaqueFunction(function=launch_setup)
Expand Down

0 comments on commit 4c53382

Please sign in to comment.