Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 9 additions & 3 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -150,8 +150,8 @@ jobs:
fail-fast: false
matrix:
# Stream 2 expands this list one PR at a time as each sim gains a
# pytest entry. Today only lab_sim has one.
config_package: [lab_sim]
# pytest entry.
config_package: [lab_sim, hangar_sim]
permissions:
# contents: read for checkout; id-token: write so the reusable workflow
# can assume the LFS S3 cache IAM role via OIDC (moveit_pro_ci v0.5.x).
Expand Down Expand Up @@ -306,7 +306,13 @@ jobs:
# Keep in sync with `integration-test.matrix.config_package` above and
# with the reusable workflow's internal ros_distro matrix. Stream 2
# expands `config_package` per sim; this matrix expands alongside.
config_package: [lab_sim]
# NOTE: the publish-and-comment job below is still pinned to lab_sim
# (see the `integration-test-report-lab_sim-*` downloads), so reports
# for other sims are produced as artifacts here but not yet surfaced in
# the PR comment. Merge gating is unaffected — the aggregate
# `example_ws / integration` status covers every config_package. The
# follow-up templates publish-and-comment over config_package.
config_package: [lab_sim, hangar_sim]
ros_distro: [humble, jazzy]
steps:
- uses: actions/checkout@de0fac2e4500dabe0009e67214ff5f5447ce83dd # v6.0.2
Expand Down
11 changes: 11 additions & 0 deletions src/hangar_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,19 @@ install(IMPORTED_RUNTIME_ARTIFACTS moveit_studio_plugins::dummy_controller_handl
lib)

if(BUILD_TESTING)
find_package(ament_cmake_pytest REQUIRED)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
# Redirect ROS node logs into the test_results tree so the test-results CI
# artifact ships them back too. Default would be ~/.ros/log/, which lives
# on the doomed container filesystem and never gets uploaded -- making
# post-mortem of objective failures impossible.
ament_add_pytest_test(
objectives_integration_test test/objectives_integration_test.py
TIMEOUT 600
ENV MOVEIT_CONFIG_PACKAGE=hangar_sim
MOVEIT_HOST_USER_WORKSPACE=${CMAKE_SOURCE_DIR}
ROS_LOG_DIR=${CMAKE_CURRENT_BINARY_DIR}/test_results/${PROJECT_NAME}/ros_logs)
endif()

ament_package()
6 changes: 6 additions & 0 deletions src/hangar_sim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@
<exec_depend>picknik_ur_base_config</exec_depend>
<exec_depend>realsense2_camera</exec_depend>
<exec_depend>realsense2_description</exec_depend>
<exec_depend>ridgeback_description</exec_depend>
<exec_depend>robotiq_description</exec_depend>
<exec_depend>clearpath_mecanum_drive_controller</exec_depend>
<exec_depend>slam_toolbox</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>velocity_force_controller</exec_depend>
Expand All @@ -39,6 +42,9 @@
<test_depend>ament_cmake_lint_cmake</test_depend>
<test_depend>picknik_ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>rclpy</test_depend>
<test_depend>rcl_interfaces</test_depend>
<test_depend>control_msgs</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
116 changes: 116 additions & 0 deletions src/hangar_sim/test/capture_rosout.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
# Copyright 2026 PickNik Inc.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
#
# * Neither the name of the PickNik Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Standalone /rosout → NDJSON capture, invoked as a subprocess from
the sibling conftest.py.

Runs in its own process so no rclpy state lives in the pytest process. The
integration test's ``execute_objective_resource`` fixture (in
moveit_pro_test_utils/objective_test_fixture.py) launches the backend via
``multiprocessing.Process(target=run_launch_files).start()`` — on Linux that
forks pytest. If pytest has called ``rclpy.init()`` at fork time, the child
inherits the DDS participant's FDs but not its spinner thread, leaving DDS
discovery half-initialized; /robot_description then never reaches
move_group / objective_server_node and BehaviorContext SIGABRTs on boot.

Subscribes to /rosout with the same QoS the rcl logging publisher uses
(depth=1000, RELIABLE, TRANSIENT_LOCAL, KEEP_LAST). Writes one JSON object
per line to ``$ROS_LOG_DIR/rosout.ndjson`` (fallback: current dir).
"""

import json
import os
import sys
import threading
from pathlib import Path

import rclpy
from rcl_interfaces.msg import Log
from rclpy.qos import DurabilityPolicy, HistoryPolicy, QoSProfile, ReliabilityPolicy

# Log message severity byte → ROS log level name. Use literal ints rather
# than `Log.DEBUG` etc. — the message constants are numpy uint8 in some
# rclpy builds, which hash differently from Python int and miss the dict
# lookup, leaving levels in the NDJSON as bare numbers like "30".
_LEVEL_NAMES = {10: "DEBUG", 20: "INFO", 30: "WARN", 40: "ERROR", 50: "FATAL"}

# Match the /rosout publisher's QoS exactly so a late-joining subscriber gets
# replayed history (TRANSIENT_LOCAL) up to the publisher's depth. ROS 2's rcl
# logging handler publishes /rosout with depth=1000 / RELIABLE /
# TRANSIENT_LOCAL / KEEP_LAST. If the subscriber is VOLATILE, no historical
# replay happens even if the publisher stores history — both ends must opt in.
_ROSOUT_QOS = QoSProfile(
depth=1000,
history=HistoryPolicy.KEEP_LAST,
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.TRANSIENT_LOCAL,
)


def main() -> int:
out_dir = Path(os.environ.get("ROS_LOG_DIR", "."))
out_dir.mkdir(parents=True, exist_ok=True)
out_path = out_dir / "rosout.ndjson"

write_lock = threading.Lock()

rclpy.init()
node = rclpy.create_node("test_rosout_capture")

with open(out_path, "w", encoding="utf-8") as out_file:

def on_log(msg: Log) -> None:
ts = msg.stamp.sec + msg.stamp.nanosec / 1e9
entry = {
"ts": ts,
"level": _LEVEL_NAMES.get(msg.level, str(msg.level)),
"node": msg.name,
"msg": msg.msg,
}
with write_lock:
out_file.write(json.dumps(entry, ensure_ascii=False) + "\n")
out_file.flush() # don't lose the last lines on a crash

node.create_subscription(Log, "/rosout", on_log, _ROSOUT_QOS)

# rclpy.spin returns when SIGINT triggers rclpy.shutdown(); some
# rclpy versions surface that as KeyboardInterrupt instead.
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
finally:
node.destroy_node()
if rclpy.ok():
rclpy.shutdown()

return 0


if __name__ == "__main__":
sys.exit(main())
112 changes: 112 additions & 0 deletions src/hangar_sim/test/conftest.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
# Copyright 2026 PickNik Inc.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
#
# * Neither the name of the PickNik Inc. nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

"""Live per-objective progress + structured /rosout capture for the
objectives integration test.

Pytest's default ``--capture=fd`` redirects fds 1 and 2, so when CTest kills
the test on timeout (TIMEOUT 600 in CMakeLists.txt) all per-test output is
lost and the CI log shows nothing past pytest's "collected N items" header.

The runtest hooks write directly to fd 2, bypassing the capture, so the CI
log always shows which objective was running when the timeout fired and how
long each completed objective took.

The ``capture_rosout`` fixture launches ``capture_rosout.py`` as a
subprocess so no rclpy state lives in the pytest process. The integration
test's ``execute_objective_resource`` fixture (in
moveit_pro_test_utils/objective_test_fixture.py) starts the backend via
``multiprocessing.Process(target=run_launch_files).start()`` — on Linux
that forks pytest. Any rclpy.init() called in pytest beforehand leaves the
forked child with a half-initialized DDS participant (FDs inherited, the
spinner thread does not survive fork), which breaks /robot_description
discovery and causes BehaviorContext to SIGABRT on backend boot.
"""

import os
import signal
import subprocess
import sys
import time
from pathlib import Path

import pytest

_started_at: dict[str, float] = {}


def pytest_runtest_logstart(nodeid, location):
_started_at[nodeid] = time.monotonic()
os.write(2, f" START {nodeid}\n".encode())


def pytest_runtest_logreport(report):
if report.when != "call":
return
nodeid = report.nodeid
start = _started_at.get(nodeid)
elapsed_str = f"{time.monotonic() - start:.1f}s" if start is not None else "n/a"
outcome = report.outcome.upper() # PASSED / FAILED / SKIPPED
line = f" {outcome:7s} {nodeid} ({elapsed_str})"
if report.failed and report.longrepr:
reason = str(report.longrepr).splitlines()[-1][:200]
line += f"\n └─ {reason}"
os.write(2, (line + "\n").encode())


@pytest.fixture(scope="session", autouse=True)
def capture_rosout():
"""Run capture_rosout.py as a subprocess to mirror /rosout to NDJSON.

Subprocess isolation is mandatory — see the module docstring for the
fork/DDS interaction that requires it. The subprocess has its own
process image, so any rclpy / DDS state it sets up never reaches the
pytest process that later gets forked by execute_objective_resource.

Creates ``$ROS_LOG_DIR`` synchronously here so the directory exists
before backend nodes (also writing into it) start, and so the
subprocess's first ``mkdir(exist_ok=True)`` has nothing to race on.
"""
out_dir = Path(os.environ.get("ROS_LOG_DIR", "."))
out_dir.mkdir(parents=True, exist_ok=True)

script = Path(__file__).parent / "capture_rosout.py"
proc = subprocess.Popen([sys.executable, str(script)])

try:
yield
finally:
# SIGINT triggers rclpy's default shutdown handler in the
# subprocess, which lets the script flush the NDJSON file before
# exiting. SIGKILL fallback in case the script wedges.
proc.send_signal(signal.SIGINT)
try:
proc.wait(timeout=10)
except subprocess.TimeoutExpired:
proc.kill()
proc.wait(timeout=5)
Loading
Loading