Skip to content

Commit 5519162

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

File tree

3 files changed

+23
-2
lines changed

3 files changed

+23
-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: 21 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,24 @@ def setUpModule():
1314
rclcpp.init()
1415

1516

17+
# When py_binding_tools and MTC are compiled with different pybind11 versions,
18+
# the corresponding classes are not interoperable.
19+
def check_pybind11_incompatibility():
20+
rclcpp.init([])
21+
node = rclcpp.Node("dummy")
22+
try:
23+
core.PipelinePlanner(node)
24+
except TypeError:
25+
return True
26+
finally:
27+
rclcpp.shutdown()
28+
return False
29+
30+
31+
incompatible_pybind11 = check_pybind11_incompatibility()
32+
incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions"
33+
34+
1635
class TestPropertyMap(unittest.TestCase):
1736
def setUp(self):
1837
self.node = rclcpp.Node("test_mtc_props")
@@ -33,6 +52,7 @@ def test_assign(self):
3352
# MotionPlanRequest is not registered as property type and should raise
3453
self.assertRaises(TypeError, self._check, "request", MotionPlanRequest())
3554

55+
@unittest.skipIf(incompatible_pybind11, incompatible_pybind11_msg)
3656
def test_assign_in_reference(self):
3757
planner = core.PipelinePlanner(self.node)
3858
props = planner.properties
@@ -115,6 +135,7 @@ def test_allow_collisions(self):
115135

116136

117137
class TestStages(unittest.TestCase):
138+
@unittest.skipIf(incompatible_pybind11, incompatible_pybind11_msg)
118139
def setUp(self):
119140
self.node = rclcpp.Node("test_mtc_stages")
120141
self.planner = core.PipelinePlanner(self.node)

0 commit comments

Comments
 (0)