Skip to content

Commit eba858b

Browse files
committed
front and bottom camera recorder
1 parent 2be809e commit eba858b

File tree

10 files changed

+170
-19
lines changed

10 files changed

+170
-19
lines changed
Lines changed: 92 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
from launch import LaunchDescription
2+
from launch.actions import DeclareLaunchArgument
3+
from launch.substitutions import LaunchConfiguration
4+
from launch_ros.actions import Node
5+
from launch.conditions import IfCondition
6+
7+
8+
def generate_launch_description():
9+
# Аргументы для фронтальной камеры
10+
front_camera_topic_arg = DeclareLaunchArgument(
11+
"front_camera_topic", default_value='/stingray/topics/camera/front'
12+
)
13+
front_camera_info_topic_arg = DeclareLaunchArgument(
14+
"front_camera_info_topic", default_value='/stingray/topics/camera/front/camera_info'
15+
)
16+
front_camera_path_arg = DeclareLaunchArgument(
17+
"front_camera_path", default_value='/dev/video0'
18+
)
19+
front_camera_calibration_path_arg = DeclareLaunchArgument(
20+
"front_camera_calibration_path", default_value="package://welt_cam/configs/front_camera.yaml"
21+
)
22+
# Аргументы для нижней камеры
23+
bottom_camera_topic_arg = DeclareLaunchArgument(
24+
"bottom_camera_topic", default_value='/stingray/topics/camera/bottom'
25+
)
26+
bottom_camera_info_topic_arg = DeclareLaunchArgument(
27+
"bottom_camera_info_topic", default_value='/stingray/topics/camera/bottom/camera_info'
28+
)
29+
bottom_camera_path_arg = DeclareLaunchArgument(
30+
"bottom_camera_path", default_value='/dev/video4'
31+
)
32+
bottom_camera_calibration_path_arg = DeclareLaunchArgument(
33+
"bottom_camera_calibration_path", default_value="package://welt_cam/configs/bottom_camera.yaml"
34+
)
35+
enable_bottom_camera_arg = DeclareLaunchArgument(
36+
"enable_bottom_camera", default_value="true",
37+
description="Включить (true) или отключить (false) ноду нижней камеры"
38+
)
39+
40+
return LaunchDescription([
41+
front_camera_topic_arg,
42+
front_camera_info_topic_arg,
43+
front_camera_path_arg,
44+
front_camera_calibration_path_arg,
45+
bottom_camera_topic_arg,
46+
bottom_camera_info_topic_arg,
47+
bottom_camera_path_arg,
48+
bottom_camera_calibration_path_arg,
49+
enable_bottom_camera_arg,
50+
51+
# Нода фронтальной камеры
52+
Node(
53+
package='usb_cam',
54+
executable='usb_cam_node_exe',
55+
name='front_camera_node',
56+
remappings=[
57+
('/image_raw', LaunchConfiguration("front_camera_topic")),
58+
('/camera_info', LaunchConfiguration("front_camera_info_topic")),
59+
],
60+
parameters=[
61+
{'video_device': LaunchConfiguration("front_camera_path")},
62+
{'camera_info_url': LaunchConfiguration(
63+
"front_camera_calibration_path")},
64+
{'camera_name': 'front_camera'},
65+
{'image_width': 640},
66+
{'image_height': 480},
67+
],
68+
respawn=True,
69+
respawn_delay=1,
70+
),
71+
# Нода нижней камеры (запускается при enable_bottom_camera==true)
72+
Node(
73+
package='usb_cam',
74+
executable='usb_cam_node_exe',
75+
name='bottom_camera_node',
76+
remappings=[
77+
('/image_raw', LaunchConfiguration("bottom_camera_topic")),
78+
('/camera_info', LaunchConfiguration("bottom_camera_info_topic")),
79+
],
80+
parameters=[
81+
{'video_device': LaunchConfiguration("bottom_camera_path")},
82+
{'camera_info_url': LaunchConfiguration(
83+
"bottom_camera_calibration_path")},
84+
{'camera_name': 'bottom_camera'},
85+
{'image_width': 640},
86+
{'image_height': 480},
87+
],
88+
respawn=True,
89+
respawn_delay=1,
90+
condition=IfCondition(LaunchConfiguration('enable_bottom_camera'))
91+
),
92+
])

src/sauvc_launch/launch/missions.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
def generate_launch_description():
1818
# object detection
1919
bbox_array_topic_arg = DeclareLaunchArgument(
20-
"bbox_array_topic", default_value='/stingray/topics/front_camera/bbox_array'
20+
"bbox_array_topic", default_value='/stingray/topics/camera/front/bbox_array'
2121
)
2222

2323
# missions
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
import os
2+
from launch import LaunchDescription
3+
from launch_ros.actions import Node
4+
from launch.actions import DeclareLaunchArgument
5+
from launch.substitutions import LaunchConfiguration
6+
from launch.conditions import IfCondition
7+
8+
def generate_launch_description():
9+
return LaunchDescription([
10+
# Аргументы для первой камеры
11+
DeclareLaunchArgument('output_width', default_value='640',
12+
description='Ширина видео'),
13+
DeclareLaunchArgument('output_height', default_value='480',
14+
description='Высота видео'),
15+
DeclareLaunchArgument('output_fps', default_value='15',
16+
description='Частота кадров видео'),
17+
DeclareLaunchArgument('output_format', default_value='h264',
18+
description='Формат видео (FourCC)'),
19+
DeclareLaunchArgument('record_dir', default_value='./records/',
20+
description='Путь к папке для сохранения записей'),
21+
# Аргументы для первой камеры
22+
DeclareLaunchArgument('front_camera_topic', default_value='/stingray/topics/camera/front',
23+
description='Топик с изображениями для первой камеры'),
24+
# Аргументы для второй камеры
25+
DeclareLaunchArgument('enable_bottom_camera', default_value='true',
26+
description='Включить (true) или отключить (false) запуск второй камеры'),
27+
DeclareLaunchArgument('bottom_camera_topic', default_value='/stingray/topics/camera/bottom',
28+
description='Топик с изображениями для второй камеры'),
29+
30+
# Нода для первой камеры
31+
Node(
32+
package='stingray_recorder', # замените на имя вашего пакета
33+
executable='video_recorder_node', # имя исполняемого файла ноды
34+
name='front_camera_video_recorder',
35+
parameters=[
36+
{'source_topic': LaunchConfiguration('front_camera_topic')},
37+
{'output_width': LaunchConfiguration('output_width')},
38+
{'output_height': LaunchConfiguration('output_height')},
39+
{'output_fps': LaunchConfiguration('output_fps')},
40+
{'output_format': LaunchConfiguration('output_format')},
41+
{'record_dir': LaunchConfiguration('record_dir')},
42+
]
43+
),
44+
# Нода для второй камеры (запускается только если enable_second_camera == "true")
45+
Node(
46+
package='stingray_recorder', # замените на имя вашего пакета
47+
executable='video_recorder_node',
48+
name='bottom_camera_video_recorder',
49+
parameters=[
50+
{'source_topic': LaunchConfiguration('bottom_camera_topic')},
51+
{'output_width': LaunchConfiguration('output_width')},
52+
{'output_height': LaunchConfiguration('output_height')},
53+
{'output_fps': LaunchConfiguration('output_fps')},
54+
{'output_format': LaunchConfiguration('output_format')},
55+
{'record_dir': LaunchConfiguration('record_dir')},
56+
],
57+
condition=IfCondition(LaunchConfiguration('enable_bottom_camera'))
58+
)
59+
])

src/sauvc_launch/launch/vision_yolov5.launch.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,15 +13,15 @@
1313
def generate_launch_description():
1414
# zbar camera
1515
zbar_camera_topic_arg = DeclareLaunchArgument(
16-
"zbar_camera_topic", default_value='/stingray/topics/front_camera'
16+
"zbar_camera_topic", default_value='/stingray/topics/camera/front'
1717
)
1818

1919
# object detection
2020
image_topic_list_arg = DeclareLaunchArgument(
21-
"image_topic_list", default_value='[/stingray/topics/front_camera, /stingray/topics/bottom_camera]'
21+
"image_topic_list", default_value='[/stingray/topics/camera/front, /stingray/topics/camera/bottom]'
2222
)
2323
camera_info_topic_list_arg = DeclareLaunchArgument(
24-
"camera_info_topic_list", default_value='[/stingray/topics/front_camera/camera_info, /stingray/topics/bottom_camera/camera_info]'
24+
"camera_info_topic_list", default_value='[/stingray/topics/camera/front/camera_info, /stingray/topics/camera/bottom/camera_info]'
2525
)
2626
weights_pkg_name_arg = DeclareLaunchArgument(
2727
"weights_pkg_name", default_value='sauvc_object_detection'

src/sauvc_launch/launch/vision_yolov8.launch.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -13,15 +13,15 @@
1313
def generate_launch_description():
1414
# zbar camera
1515
zbar_camera_topic_arg = DeclareLaunchArgument(
16-
"zbar_camera_topic", default_value='/stingray/topics/front_camera'
16+
"zbar_camera_topic", default_value='/stingray/topics/camera/front'
1717
)
1818

1919
# object detection
2020
image_topic_list_arg = DeclareLaunchArgument(
21-
"image_topic_list", default_value='[/stingray/topics/front_camera, /stingray/topics/bottom_camera]'
21+
"image_topic_list", default_value='[/stingray/topics/camera/front, /stingray/topics/camera/bottom]'
2222
)
2323
camera_info_topic_list_arg = DeclareLaunchArgument(
24-
"camera_info_topic_list", default_value='[/stingray/topics/front_camera/camera_info, /stingray/topics/bottom_camera/camera_info]'
24+
"camera_info_topic_list", default_value='[/stingray/topics/camera/front/camera_info, /stingray/topics/camera/bottom/camera_info]'
2525
)
2626
weights_pkg_name_arg = DeclareLaunchArgument(
2727
"weights_pkg_name", default_value='sauvc_object_detection'

src/sauvc_missions/configs/missions/blue_bowl.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,13 @@ states:
33
ENABLE_OBJECT_DETECTION:
44
action:
55
type: EnableObjectDetection
6-
camera_topic: /stingray/topics/front_camera
6+
camera_topic: /stingray/topics/camera/front
77
enable: true
88
MOVE_WITH_CENTERING:
99
action:
1010
type: BboxCenteringTwist
1111
bbox_name: blue_bowl
12-
bbox_topic: /stingray/topics/front_camera/bbox_array
12+
bbox_topic: /stingray/topics/camera/front/bbox_array
1313
distance_threshold: 1.5
1414
lost_threshold: 30
1515
avoid_bbox_name_array: []
@@ -25,7 +25,7 @@ states:
2525
DISABLE_OBJECT_DETECTION:
2626
action:
2727
type: EnableObjectDetection
28-
camera_topic: /stingray/topics/front_camera
28+
camera_topic: /stingray/topics/camera/front
2929
enable: false
3030
# определенное количество времени движения до тазика
3131
# необходимо подобрать благоприятную скорость, время движения, глубину

src/sauvc_missions/configs/missions/flares.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ states:
33
ENABLE_OBJECT_DETECTION:
44
action:
55
type: EnableObjectDetection
6-
camera_topic: /stingray/topics/front_camera
6+
camera_topic: /stingray/topics/camera/front
77
enable: true
88
WAIT_SEQUENCE:
99
action:
@@ -12,7 +12,7 @@ states:
1212
FLARES:
1313
action:
1414
type: SequencePunchBboxTwist
15-
bbox_topic: /stingray/topics/front_camera/bbox_array
15+
bbox_topic: /stingray/topics/camera/front/bbox_array
1616
first_clockwise: true
1717
found_threshold: 1
1818
distance_threshold: 0.5

src/sauvc_missions/configs/missions/gate.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ states:
33
ENABLE_OBJECT_DETECTION:
44
action:
55
type: EnableObjectDetection
6-
camera_topic: /stingray/topics/front_camera
6+
camera_topic: /stingray/topics/camera/front
77
enable: true
88
SUBMERGE:
99
action:
@@ -19,7 +19,7 @@ states:
1919
action:
2020
type: BboxCenteringTwist
2121
bbox_name: gate
22-
bbox_topic: /stingray/topics/front_camera/bbox_array
22+
bbox_topic: /stingray/topics/camera/front/bbox_array
2323
distance_threshold: 1.5
2424
lost_threshold: 30
2525
avoid_bbox_name_array: [orange_flare]

src/sauvc_missions/configs/missions/hydroacoustic_bowl.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,13 @@ states:
33
ENABLE_OBJECT_DETECTION:
44
action:
55
type: EnableObjectDetection
6-
camera_topic: /stingray/topics/front_camera
6+
camera_topic: /stingray/topics/camera/front
77
enable: true
88
MAT_CENTERING:
99
action:
1010
type: BboxCenteringTwist
1111
bbox_name: mat
12-
bbox_topic: /stingray/topics/front_camera/bbox_array
12+
bbox_topic: /stingray/topics/camera/front/bbox_array
1313
distance_threshold: 5.0
1414
lost_threshold: 30
1515
avoid_bbox_name_array: []
@@ -26,7 +26,7 @@ states:
2626
action:
2727
type: HydroacousticCenteringTwist
2828
bbox_name: red_bowl
29-
bbox_topic: /stingray/topics/front_camera/bbox_array
29+
bbox_topic: /stingray/topics/camera/front/bbox_array
3030
hydroacoustic_topic: /stingray/topics/angle_hydroacoustic
3131
angle_threshold: 10.0
3232
distance_threshold: 2.0
@@ -41,7 +41,7 @@ states:
4141
DISABLE_OBJECT_DETECTION:
4242
action:
4343
type: EnableObjectDetection
44-
camera_topic: /stingray/topics/front_camera
44+
camera_topic: /stingray/topics/camera/front
4545
enable: false
4646
# определенное количество времени движения до тазика
4747
# необходимо подобрать благоприятную скорость, время движения, глубину

0 commit comments

Comments
 (0)