From 83f97a8d653e1e4f9863af77a3d90aa274156e28 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Fri, 29 Mar 2024 10:43:00 +0100 Subject: [PATCH] update --- __pycache__/webcam.launch.cpython-310.pyc | Bin 0 -> 1938 bytes docker-compose.yaml | 30 ++++++-- webcam.launch.py | 88 ++++++++++++++++++++++ 3 files changed, 113 insertions(+), 5 deletions(-) create mode 100644 __pycache__/webcam.launch.cpython-310.pyc create mode 100644 webcam.launch.py diff --git a/__pycache__/webcam.launch.cpython-310.pyc b/__pycache__/webcam.launch.cpython-310.pyc new file mode 100644 index 0000000000000000000000000000000000000000..f06859683252fb4cb06b3a45eb59af324b8a397f GIT binary patch literal 1938 zcmb_dTW{k;6t*4PNo?oV%kHwJ)UbdQ3AI%St9?KS)KXLlx|Q}KZCGTvo=Ix0Z<-m0 z*780T9xL$!_yhc&hX55@Kz;EQv6sHw1j5 z{}f-aC;1s=ADP_d0vX7JzywkOwNM*b5@~>J zeBx*Ai zx#(TA$uzWarGiwYG^A`vX-nCava%7ff!;$8uGN_aYwk+jeJQuERP_GO7O;aW(4r5n zjn@{_OQlpxt!$KfX_RK!EL&x}v}W*bDCCDH+?j_6ryj!dFu;Yq2a`QX?H7aRLgiK} zH}ly!l%#|3)XyX4&HX6H+(ygVb0-TgaO6!>68ntnFP^=4UO1mWd$*ZDwAgx?!n_N z8#KP-1T33moLkKZ7di(x3J+*VeL7LxbqT|Ar8T5N#pEnK-l|87och z`DDiXtF0=T^;@ke$?mcNE2BCYi)NE#Z>5zav2nX!sl=0XX)Pe_zXPRjpXsWn_cp)8BSmqFzi(vZ0MUaxdjX9Parf+S2flA zSJVHe(a_+1@J7{az*FD-der|i9qkYEAMIXcbz7Q$l25>?lVO*emD93Ze65avq;%I0 z#HmhYS$Ve(cR`AR^NpIMD}Mo6b$}`KgIXUf{v(t$fhQs? literal 0 HcmV?d00001 diff --git a/docker-compose.yaml b/docker-compose.yaml index e700faa..58310b1 100644 --- a/docker-compose.yaml +++ b/docker-compose.yaml @@ -227,13 +227,33 @@ services: - ./config/foxglove/default.json:/foxglove/default-layout.json # USB Camera Stream - cam: + # cam: + # extends: overlay + # command: > + # ros2 run ros2_cam_openCV cam_node + # devices: + # - /dev/video0:/dev/video0 + + # cam: + # extends: overlay + # command: > + # ros2 launch ffmpeg_image_transport cam.launch.py + # devices: + # - /dev/video0:/dev/video0 + # - /dev/dri:/dev/dri + webcam: extends: overlay - command: > - ros2 run ros2_cam_openCV cam_node + image: husarion/image-transport:humble-4.2.0 devices: - /dev/video0:/dev/video0 - + - /dev/dri:/dev/dri + volumes: + - ./:/repo + command: > + ros2 launch /repo/webcam.launch.py + ffmpeg_encoding:=libx264 + ffmpeg_preset:=ultrafast + ffmpeg_tune:=zerolatency # ROS2 Frontier exploration explorer: @@ -369,7 +389,7 @@ services: ros1bridge: image: husarion/ros1-bridge:foxy-0.9.6-20230327-stable command: | - ros2 run ros1_bridge dynamic_bridge + sh /opt/ros/noetic/setup.sh && ros2 run ros1_bridge dynamic_bridge network_mode: host ipc: host environment: diff --git a/webcam.launch.py b/webcam.launch.py new file mode 100644 index 0000000..10e14c4 --- /dev/null +++ b/webcam.launch.py @@ -0,0 +1,88 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import DeclareLaunchArgument +from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir +from launch.conditions import IfCondition, UnlessCondition +from launch.substitutions import TextSubstitution + +def generate_launch_description(): + # Declare launch arguments + video_device_arg = DeclareLaunchArgument( + 'video_device', default_value='/dev/video0', + description='Video device path') + + pixel_format_arg = DeclareLaunchArgument( + 'pixel_format', default_value='YUYV', + description='Pixel format') + + output_encoding_arg = DeclareLaunchArgument( + 'output_encoding', default_value='yuv422_yuy2', + description='Output encoding') + + image_size_arg = DeclareLaunchArgument( + 'image_size', default_value='[640, 480]', + description='Image size') + + camera_frame_id_arg = DeclareLaunchArgument( + 'camera_frame_id', default_value='camera_optical_link', + description='Camera frame ID') + + params_file_arg = DeclareLaunchArgument( + 'params_file', default_value='', + description='Path to the parameters file') + + device_namespace_arg = DeclareLaunchArgument( + 'device_namespace', default_value='camera', + description='Device namespace') + + ffmpeg_encoding_arg = DeclareLaunchArgument( + 'ffmpeg_encoding', default_value='libx264', + description='FFMPEG encoding') + + ffmpeg_preset_arg = DeclareLaunchArgument( + 'ffmpeg_preset', default_value='ultrafast', + description='FFMPEG preset') + + ffmpeg_tune_arg = DeclareLaunchArgument( + 'ffmpeg_tune', default_value='zerolatency', + description='FFMPEG tune') + + # v4l2_camera node configuration + v4l2_camera_node = Node( + package='v4l2_camera', + executable='v4l2_camera_node', + name='camera', + namespace=LaunchConfiguration('device_namespace'), + parameters=[ + { + 'video_device': LaunchConfiguration('video_device'), + 'pixel_format': LaunchConfiguration('pixel_format'), + 'output_encoding': LaunchConfiguration('output_encoding'), + 'image_size': LaunchConfiguration('image_size'), + 'camera_frame_id': LaunchConfiguration('camera_frame_id'), + 'camera_name': LaunchConfiguration('device_namespace'), + 'camera_link_frame_id': [LaunchConfiguration('device_namespace'), TextSubstitution(text='_link')], + 'ffmpeg_image_transport.encoding': LaunchConfiguration('ffmpeg_encoding'), + 'ffmpeg_image_transport.preset': LaunchConfiguration('ffmpeg_preset'), + 'ffmpeg_image_transport.tune': LaunchConfiguration('ffmpeg_tune'), + }, + LaunchConfiguration('params_file') + ], + # Add any necessary remappings here + ) + + # Assemble the launch description + return LaunchDescription([ + video_device_arg, + pixel_format_arg, + output_encoding_arg, + image_size_arg, + camera_frame_id_arg, + params_file_arg, + device_namespace_arg, + ffmpeg_encoding_arg, + ffmpeg_preset_arg, + ffmpeg_tune_arg, + v4l2_camera_node + ]) +