Skip to content

Commit

Permalink
CI: skip python tests
Browse files Browse the repository at this point in the history
- with asan
- with clang builds
  • Loading branch information
rhaschke committed Jul 13, 2024
1 parent 75988a4 commit 5519162
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 2 deletions.
1 change: 1 addition & 0 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ jobs:
# - IMAGE: rolling-source
# NAME: ccov
# TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage"
- IMAGE: rolling-source
- IMAGE: rolling-source
CLANG_TIDY: pedantic
- IMAGE: jazzy-source
Expand Down
3 changes: 1 addition & 2 deletions core/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ add_subdirectory(pybind11)
# C++ wrapper code
add_subdirectory(bindings)


if(BUILD_TESTING)
if(BUILD_TESTING AND NOT DEFINED ENV{PRELOAD})
find_package(ament_cmake_pytest REQUIRED)
find_package(launch_testing_ament_cmake)
set(_pytest_tests test/test_mtc.py)
Expand Down
21 changes: 21 additions & 0 deletions core/python/test/test_mtc.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
# -*- coding: utf-8 -*-

import sys
import pytest
import unittest
import rclcpp
from geometry_msgs.msg import Pose, PoseStamped, PointStamped, TwistStamped, Vector3Stamped
Expand All @@ -13,6 +14,24 @@ def setUpModule():
rclcpp.init()


# When py_binding_tools and MTC are compiled with different pybind11 versions,
# the corresponding classes are not interoperable.
def check_pybind11_incompatibility():
rclcpp.init([])
node = rclcpp.Node("dummy")
try:
core.PipelinePlanner(node)
except TypeError:
return True
finally:
rclcpp.shutdown()
return False


incompatible_pybind11 = check_pybind11_incompatibility()
incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions"


class TestPropertyMap(unittest.TestCase):
def setUp(self):
self.node = rclcpp.Node("test_mtc_props")
Expand All @@ -33,6 +52,7 @@ def test_assign(self):
# MotionPlanRequest is not registered as property type and should raise
self.assertRaises(TypeError, self._check, "request", MotionPlanRequest())

@unittest.skipIf(incompatible_pybind11, incompatible_pybind11_msg)
def test_assign_in_reference(self):
planner = core.PipelinePlanner(self.node)
props = planner.properties
Expand Down Expand Up @@ -115,6 +135,7 @@ def test_allow_collisions(self):


class TestStages(unittest.TestCase):
@unittest.skipIf(incompatible_pybind11, incompatible_pybind11_msg)
def setUp(self):
self.node = rclcpp.Node("test_mtc_stages")
self.planner = core.PipelinePlanner(self.node)
Expand Down

0 comments on commit 5519162

Please sign in to comment.