update
This commit is contained in:
parent
33eba8fcfb
commit
83f97a8d65
BIN
__pycache__/webcam.launch.cpython-310.pyc
Normal file
BIN
__pycache__/webcam.launch.cpython-310.pyc
Normal file
Binary file not shown.
@ -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:
|
||||
|
88
webcam.launch.py
Normal file
88
webcam.launch.py
Normal file
@ -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
|
||||
])
|
||||
|
Loading…
Reference in New Issue
Block a user