Skip to content

Commit 6f96a63

Browse files
committed
capture window
1 parent 3769f4e commit 6f96a63

File tree

8 files changed

+165
-10
lines changed

8 files changed

+165
-10
lines changed

.github/workflows/test_build.yml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -447,7 +447,8 @@ jobs:
447447
export -n CYCLONEDDS_URI
448448
export ROS_DOMAIN_ID=2
449449
export IGN_PARTITION=${HOSTNAME}:${GITHUB_RUN_ID}
450-
make test_scenario_execution_gazebo_test
450+
# shellcheck disable=SC1083
451+
scenario_batch_execution -i test/scenario_execution_gazebo_test/scenarios/ -o test_scenario_execution_gazebo --ignore-process-return-value -- ros2 launch tb4_sim_scenario sim_nav_scenario_launch.py scenario:={SCENARIO} output_dir:={OUTPUT_DIR} headless:=True use_rviz:=False
451452
- name: Upload result
452453
uses: actions/upload-artifact@0b2256b8c012f0828dc542b3febcab082c67f72b # v4.3.4
453454
if: always()

Makefile

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,4 +47,4 @@ test_scenario_execution_nav2_test:
4747
scenario_batch_execution -i test/scenario_execution_nav2_test/scenarios/ -o test_scenario_execution_nav2 --ignore-process-return-value -- ros2 run scenario_execution_ros scenario_execution_ros {SCENARIO} -o {OUTPUT_DIR} -t
4848

4949
test_scenario_execution_gazebo_test:
50-
scenario_batch_execution -i test/scenario_execution_gazebo_test/scenarios/ -o test_scenario_execution_gazebo --ignore-process-return-value -- ros2 launch tb4_sim_scenario sim_nav_scenario_launch.py scenario:={SCENARIO} output_dir:={OUTPUT_DIR} headless:=True use_rviz:=False navigation:=false
50+
scenario_batch_execution -i test/scenario_execution_gazebo_test/scenarios/ -o test_scenario_execution_gazebo --ignore-process-return-value -- ros2 launch tb4_sim_scenario sim_nav_scenario_launch.py scenario:={SCENARIO} output_dir:={OUTPUT_DIR} headless:=True use_rviz:=False navigation:=false

libs/scenario_execution_x11/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414
<depend>scenario_execution</depend>
1515

1616
<exec_depend>ffmpeg</exec_depend>
17+
<exec_depend>python-xlib</exec_depend>
18+
<exec_depend>recordmydesktop</exec_depend>
1719

1820
<export>
1921
<build_type>ament_python</build_type>
Lines changed: 138 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,138 @@
1+
# Copyright (C) 2025 Frederik Pasch
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing,
10+
# software distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions
13+
# and limitations under the License.
14+
#
15+
# SPDX-License-Identifier: Apache-2.0
16+
17+
from enum import Enum
18+
import py_trees
19+
import os
20+
from scenario_execution.actions.base_action import ActionError
21+
from scenario_execution.actions.run_process import RunProcess
22+
from Xlib.display import Display
23+
from Xlib import error
24+
25+
26+
class CaptureWindowState(Enum):
27+
IDLE = 1
28+
WAITING_FOR_WINDOW = 2
29+
CAPTURING = 3
30+
DONE = 11
31+
FAILURE = 12
32+
33+
34+
class CaptureWindow(RunProcess):
35+
36+
def __init__(self):
37+
super().__init__()
38+
self.current_state = None
39+
self.output_dir = "."
40+
self.video_size = None
41+
self.window_name = None
42+
self.root_display = None
43+
44+
def setup(self, **kwargs):
45+
if "DISPLAY" not in os.environ:
46+
raise ActionError("capture_window() requires environment variable 'DISPLAY' to be set.", action=self)
47+
48+
if kwargs['output_dir']:
49+
if not os.path.exists(kwargs['output_dir']):
50+
raise ActionError(
51+
f"Specified destination dir '{kwargs['output_dir']}' does not exist", action=self)
52+
self.output_dir = kwargs['output_dir']
53+
54+
self.root_display = Display().screen().root
55+
56+
def execute(self, window_name: str, output_filename: str, frame_rate: float): # pylint: disable=arguments-differ
57+
super().execute(None, wait_for_shutdown=True)
58+
self.window_name = window_name
59+
self.frame_rate = frame_rate
60+
self.output_filename = output_filename
61+
self.current_state = CaptureWindowState.WAITING_FOR_WINDOW
62+
63+
def update(self) -> py_trees.common.Status:
64+
if self.current_state == CaptureWindowState.WAITING_FOR_WINDOW:
65+
self.feedback_message = f"Waiting for window {self.window_name}..." # pylint: disable= attribute-defined-outside-init
66+
67+
video_size = self.get_window(self.root_display, self.window_name, "")
68+
if video_size is not None:
69+
self.video_size = video_size
70+
self.feedback_message = f"Found window (size {self.video_size})..." # pylint: disable= attribute-defined-outside-init
71+
self.current_state = CaptureWindowState.IDLE
72+
73+
cmd = ["ffmpeg",
74+
"-video_size", f"{self.video_size[2]}x{self.video_size[3]}",
75+
"-f", "x11grab",
76+
"-draw_mouse", "0",
77+
"-framerate", str(self.frame_rate),
78+
"-i", f"{os.environ["DISPLAY"]}+{self.video_size[0]},{self.video_size[1]}",
79+
"-c:v", "libx264",
80+
"-preset", "veryfast",
81+
"-f", "mp4",
82+
"-nostdin",
83+
"-y", os.path.join(self.output_dir, self.output_filename)]
84+
self.set_command(cmd)
85+
return py_trees.common.Status.RUNNING
86+
else:
87+
return super().update()
88+
89+
def get_logger_stdout(self):
90+
return self.logger.debug
91+
92+
def get_logger_stderr(self):
93+
return self.logger.debug
94+
95+
def on_executed(self):
96+
self.current_state = CaptureWindowState.CAPTURING
97+
self.feedback_message = f"Capturing window..." # pylint: disable= attribute-defined-outside-init
98+
99+
def on_process_finished(self, ret):
100+
if self.current_state == CaptureWindowState.CAPTURING:
101+
self.feedback_message = f"Capturing window failed. {self.output[-1]}" # pylint: disable= attribute-defined-outside-init
102+
return py_trees.common.Status.FAILURE
103+
return py_trees.common.Status.SUCCESS
104+
105+
106+
107+
def get_window(self, window, window_name, indent):
108+
children = window.query_tree().children
109+
splits = window_name.split('/')
110+
if splits:
111+
for w in children:
112+
try:
113+
if len(splits) == 1:
114+
name = w.get_wm_name()
115+
wm_class = w.get_wm_class()
116+
if (name is not None and splits[0] in str(name)) or (wm_class is not None and splits[0] in wm_class):
117+
geom = w.get_geometry()
118+
window_pos = (geom.x, geom.y, geom.width, geom.height)
119+
return window_pos
120+
else:
121+
continue
122+
else:
123+
name = w.get_wm_name()
124+
wm_class = w.get_wm_class()
125+
if (name is not None and splits[0] in str(name)) or (wm_class is not None and splits[0] in wm_class):
126+
return self.get_window(w, "/".join(splits[1:]), indent + " ")
127+
else:
128+
found = self.get_window(w, window_name, indent + " ")
129+
if found:
130+
geom = w.get_geometry()
131+
current_window_pos = (geom.x, geom.y, geom.width, geom.height)
132+
return (current_window_pos[0] + found[0],
133+
current_window_pos[1] + found[1],
134+
found[2],
135+
found[3])
136+
except (error.BadWindow, error.XError):
137+
continue
138+
return None

libs/scenario_execution_x11/scenario_execution_x11/lib_osc/x11.osc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,9 @@ action capture_screen:
44
# Capture the screen content within a video
55
output_filename: string = "capture.mp4" # name of the resulting video file (use ``--output-dir`` command-line argument to store the file within a specific directory)
66
frame_rate: float = 25.0 # frame-rate of the resulting video
7+
8+
action capture_window:
9+
# Capture a specific window. Capturing is delayed until window exists.
10+
window_name: string # name of window to capture
11+
output_filename: string = "capture.mp4" # name of the resulting video file (use ``--output-dir`` command-line argument to store the file within a specific directory)
12+
frame_rate: float = 25.0 # frame-rate of the resulting video

libs/scenario_execution_x11/setup.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
entry_points={
3939
'scenario_execution.actions': [
4040
'capture_screen = scenario_execution_x11.actions.capture_screen:CaptureScreen',
41+
'capture_window = scenario_execution_x11.actions.capture_window:CaptureWindow',
4142
],
4243
'scenario_execution.osc_libraries': [
4344
'x11 = '

test/scenario_execution_nav2_test/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313

1414
<exec_depend>rclpy</exec_depend>
1515
<exec_depend>scenario_execution_nav2</exec_depend>
16+
<exec_depend>scenario_execution_x11</exec_depend>
1617
<exec_depend>nav2_bringup</exec_depend>
1718
<exec_depend>nav2_loopback_sim</exec_depend>
1819

Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,23 @@
11
import osc.helpers
22
import osc.ros
33
import osc.nav2
4+
import osc.x11
45

56
scenario example_nav2:
67
timeout(900s)
78
robot: differential_drive_robot
8-
do serial:
9-
ros_launch("nav2_bringup", "tb4_loopback_simulation.launch.py", [
9+
do parallel:
10+
capture_window(".rviz - RViz/rviz2")
11+
serial:
12+
ros_launch("nav2_bringup", "tb4_loopback_simulation.launch.py", [
1013
key_value('map', ament.get_package_share_directory("tb4_sim_scenario") + "/maps/maze.yaml")
1114
], wait_for_shutdown: false)
12-
bag_record(['/tf', '/tf_static', '/scenario_execution/snapshots', '/map', '/local_costmap/costmap'], use_sim_time: true)
13-
robot.init_nav2(pose_3d(position_3d(x: 0.0m, y: 0.0m)), wait_for_amcl: false)
14-
serial:
15-
repeat(2)
16-
robot.nav_through_poses([pose_3d(position_3d(x: 0.75m, y: -0.75m)), pose_3d(position_3d(x: 1.5m, y: -1.5m))])
17-
robot.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m)))
15+
#bag_record(['/tf', '/tf_static', '/scenario_execution/snapshots', '/map', '/local_costmap/costmap'], use_sim_time: true)
16+
#robot.init_nav2(pose_3d(position_3d(x: 0.0m, y: 0.0m)), wait_for_amcl: false)
17+
#run_process("xwininfo -root -children -tree")
18+
#serial:
19+
#repeat(2)
20+
# robot.nav_through_poses([pose_3d(position_3d(x: 0.75m, y: -0.75m)), pose_3d(position_3d(x: 1.5m, y: -1.5m))])
21+
#robot.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m)))
22+
wait elapsed(10s)
23+
emit end

0 commit comments

Comments
 (0)