mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
CI: skip python tests
- with asan - with clang builds
This commit is contained in:
parent
75988a4a1c
commit
5519162b40
1
.github/workflows/ci.yaml
vendored
1
.github/workflows/ci.yaml
vendored
@ -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
|
||||
|
||||
@ -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)
|
||||
|
||||
@ -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
|
||||
@ -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")
|
||||
@ -33,6 +52,7 @@ class TestPropertyMap(unittest.TestCase):
|
||||
# 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
|
||||
@ -115,6 +135,7 @@ class TestModifyPlanningScene(unittest.TestCase):
|
||||
|
||||
|
||||
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)
|
||||
|
||||
Loading…
Reference in New Issue
Block a user