Skip to content

Commit d30411c

Browse files
committed
CI: skip python tests
- with asan - with clang builds
1 parent 75988a4 commit d30411c

File tree

3 files changed

+14
-2
lines changed

3 files changed

+14
-2
lines changed

.github/workflows/ci.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ jobs:
2222
# - IMAGE: rolling-source
2323
# NAME: ccov
2424
# TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"
25+
- IMAGE: rolling-source
2526
- IMAGE: rolling-source
2627
CLANG_TIDY: pedantic
2728
- IMAGE: jazzy-source

core/python/CMakeLists.txt

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,7 @@ add_subdirectory(pybind11)
2424
# C++ wrapper code
2525
add_subdirectory(bindings)
2626

27-
28-
if(BUILD_TESTING)
27+
if(BUILD_TESTING AND NOT DEFINED ENV{PRELOAD})
2928
find_package(ament_cmake_pytest REQUIRED)
3029
find_package(launch_testing_ament_cmake)
3130
set(_pytest_tests test/test_mtc.py)

core/python/test/test_mtc.py

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
# -*- coding: utf-8 -*-
33

44
import sys
5+
import pytest
56
import unittest
67
import rclcpp
78
from geometry_msgs.msg import Pose, PoseStamped, PointStamped, TwistStamped, Vector3Stamped
@@ -13,6 +14,15 @@ def setUpModule():
1314
rclcpp.init()
1415

1516

17+
def pybind11_versions():
18+
return [k for k in __builtins__.keys() if k.startswith("__pybind11_internals_v")]
19+
20+
21+
incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions: " + "\n- ".join(
22+
pybind11_versions()
23+
)
24+
25+
1626
class TestPropertyMap(unittest.TestCase):
1727
def setUp(self):
1828
self.node = rclcpp.Node("test_mtc_props")
@@ -33,6 +43,7 @@ def test_assign(self):
3343
# MotionPlanRequest is not registered as property type and should raise
3444
self.assertRaises(TypeError, self._check, "request", MotionPlanRequest())
3545

46+
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
3647
def test_assign_in_reference(self):
3748
planner = core.PipelinePlanner(self.node)
3849
props = planner.properties
@@ -115,6 +126,7 @@ def test_allow_collisions(self):
115126

116127

117128
class TestStages(unittest.TestCase):
129+
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
118130
def setUp(self):
119131
self.node = rclcpp.Node("test_mtc_stages")
120132
self.planner = core.PipelinePlanner(self.node)

0 commit comments

Comments
 (0)