-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathrealsense_d435i.launch.py
executable file
·45 lines (36 loc) · 1.18 KB
/
realsense_d435i.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
realsense_launch_dir=os.path.join(get_package_share_directory('realsense2_camera'), 'launch')
camera_launch_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(realsense_launch_dir, 'rs_launch.py')
),
launch_arguments={
'pointcloud.enable': 'True',
}.items()
)
image_compressed = Node(
package='image_transport',
executable='republish',
name ='cam_compressed',
output = 'screen',
remappings= [
('in', '/camera/color/image_raw'),
('out', '/image')
],
parameters=[
{'input_transport':'raw',
'output_transport': 'compressed'
}
]
)
return LaunchDescription([
camera_launch_cmd,
image_compressed
]
)