-
Notifications
You must be signed in to change notification settings - Fork 8
/
example_h264.launch
38 lines (30 loc) · 1.83 KB
/
example_h264.launch
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
<launch>
<!-- Use different namespaces for the 2nd camera or greater -->
<group ns="usb_cam">
<!-- USB camera driver + controller manager -->
<node name="hardware" pkg="nodelet" type="nodelet"
args="standalone usb_cam_hardware/USBCamHardware" output="screen">
<remap from="camera_info_controller/camera_info" to="camera_info"/>
<remap from="h264_controller/image" to="image"/>
<remap from="compressed_packet_controller/packet" to="packet/h264"/>
<param name="video_device" value="/dev/video1"/>
<param name="image_width" value="1920"/>
<param name="image_height" value="960"/>
<param name="pixel_format" value="h264"/>
<param name="framerate" value="30"/>
</node>
<!-- Controller starter that asks the manager to start -->
<node name="controller_starter" pkg="controller_manager" type="controller_manager"
args="spawn camera_info_controller compressed_packet_controller h264_controller" output="screen"/>
<!-- Recommendation: use controllers you actually required -->
<!-- camera_info_controller publishes camera infos synchronized with images -->
<!-- compressed_packet_controller publishes packets from the camera (so requires subscriber-side decoding) -->
<!-- h264_controller does server-side decoding (usually heavy) and publishes images -->
<!-- Parameters for controllers -->
<param name="camera_info_controller/type" value="usb_cam_controllers/CameraInfoController"/>
<param name="camera_info_controller/camera_frame_id" value="insta360"/>
<param name="compressed_packet_controller/type" value="usb_cam_controllers/CompressedPacketController"/>
<param name="compressed_packet_controller/format" value="h264"/>
<param name="h264_controller/type" value="usb_cam_controllers/H264Controller"/>
</group>
</launch>