From 9e830c01e3b55f160e94c4d427b88f647446bd68 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Wed, 3 Nov 2021 17:41:31 -0700 Subject: [PATCH 1/5] Add python bindings for Joint::getWrenchTo{Child|Parent}BodyNode --- python/dartpy/dynamics/Joint.cpp | 8 + python/dartpy/dynamics/SimpleFrame.cpp | 12 +- python/dartpy/eigen_geometry_pybind.cpp | 3 + python/dartpy/utils/SdfParser.cpp | 4 +- python/tests/CMakeLists.txt | 1 + python/tests/integration/__init__.py | 0 .../integration/test_joint_force_torque.py | 292 ++++++++++++++++++ .../comprehensive/test_JointForceTorque.cpp | 38 +-- 8 files changed, 328 insertions(+), 30 deletions(-) create mode 100644 python/tests/integration/__init__.py create mode 100644 python/tests/integration/test_joint_force_torque.py diff --git a/python/dartpy/dynamics/Joint.cpp b/python/dartpy/dynamics/Joint.cpp index fcaab244636be..1b84f448d2fe8 100644 --- a/python/dartpy/dynamics/Joint.cpp +++ b/python/dartpy/dynamics/Joint.cpp @@ -892,6 +892,14 @@ void Joint(py::module& m) +[](const dart::dynamics::Joint* self) -> Eigen::Vector6d { return self->getBodyConstraintWrench(); }) + .def( + "getWrenchToChildBodyNode", + &dart::dynamics::Joint::getWrenchToChildBodyNode, + ::py::arg("withRespectTo") = nullptr) + .def( + "getWrenchToParentBodyNode", + &dart::dynamics::Joint::getWrenchToParentBodyNode, + ::py::arg("withRespectTo") = nullptr) .def( "notifyPositionUpdated", +[](dart::dynamics::Joint* self) diff --git a/python/dartpy/dynamics/SimpleFrame.cpp b/python/dartpy/dynamics/SimpleFrame.cpp index 79b923601fc57..1d4142cbfe779 100644 --- a/python/dartpy/dynamics/SimpleFrame.cpp +++ b/python/dartpy/dynamics/SimpleFrame.cpp @@ -48,20 +48,14 @@ void SimpleFrame(py::module& m) dart::dynamics::ShapeFrame, dart::dynamics::Detachable, std::shared_ptr >(m, "SimpleFrame") - .def(::py::init<>()) - .def(::py::init(), ::py::arg("refFrame")) - .def( - ::py::init(), - ::py::arg("refFrame"), - ::py::arg("name")) .def( ::py::init< dart::dynamics::Frame*, const std::string&, const Eigen::Isometry3d&>(), - ::py::arg("refFrame"), - ::py::arg("name"), - ::py::arg("relativeTransform")) + ::py::arg("refFrame") = dart::dynamics::Frame::World(), + ::py::arg("name") = "simple_frame", + ::py::arg("relativeTransform") = Eigen::Isometry3d::Identity()) .def( "setName", +[](dart::dynamics::SimpleFrame* self, const std::string& _name) diff --git a/python/dartpy/eigen_geometry_pybind.cpp b/python/dartpy/eigen_geometry_pybind.cpp index b10bb0646ebf0..22bd86d24977e 100644 --- a/python/dartpy/eigen_geometry_pybind.cpp +++ b/python/dartpy/eigen_geometry_pybind.cpp @@ -167,6 +167,9 @@ void eigen_geometry(pybind11::module& parent_m) .def("matrix", [](const Class* self) -> Eigen::Matrix { return self->matrix(); }) + .def("set_identity", [](Class* self) { + self->setIdentity(); + }) .def("set_matrix", [](Class* self, const Eigen::Matrix& matrix) { Class update(matrix); CheckIsometry(update); diff --git a/python/dartpy/utils/SdfParser.cpp b/python/dartpy/utils/SdfParser.cpp index 91536cb42bd46..bfd8365c623b2 100644 --- a/python/dartpy/utils/SdfParser.cpp +++ b/python/dartpy/utils/SdfParser.cpp @@ -43,11 +43,11 @@ void SdfParser(py::module& m) { auto sm = m.def_submodule("SdfParser"); - ::py::enum_(m, "RootJointType") + ::py::enum_(sm, "RootJointType") .value("FLOATING", utils::SdfParser::RootJointType::FLOATING) .value("FIXED", utils::SdfParser::RootJointType::FIXED); - ::py::class_(m, "Options") + ::py::class_(sm, "Options") .def( ::py::init< common::ResourceRetrieverPtr, diff --git a/python/tests/CMakeLists.txt b/python/tests/CMakeLists.txt index b404d559e523b..4cdd5768ae8ff 100644 --- a/python/tests/CMakeLists.txt +++ b/python/tests/CMakeLists.txt @@ -50,6 +50,7 @@ function(dartpy_add_test test_name) # ARGN for source file COMMAND PYTHONPATH=${DART_DARTPY_BUILD_DIR} ${PYTHON_EXECUTABLE} ${source} WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} SOURCES ${source} + DEPENDS dartpy ) endfunction() diff --git a/python/tests/integration/__init__.py b/python/tests/integration/__init__.py new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/python/tests/integration/test_joint_force_torque.py b/python/tests/integration/test_joint_force_torque.py new file mode 100644 index 0000000000000..dbf16375522de --- /dev/null +++ b/python/tests/integration/test_joint_force_torque.py @@ -0,0 +1,292 @@ +import pytest +import math +import numpy as np +import dartpy as dart + + +def read_world(uri: dart.common.Uri): + options = dart.utils.SdfParser.Options() + options.mDefaultRootJointType = dart.utils.SdfParser.RootJointType.FIXED + world = dart.utils.SdfParser.readWorld(uri, options) + for i in range(world.getNumSkeletons()): + skel = world.getSkeleton(i) + for j in range(skel.getNumJoints()): + joint = skel.getJoint(j) + joint.setLimitEnforcement(True) + return world + + +def test_static(): + # Load world + world = read_world("dart://sample/sdf/test/force_torque_test.world") + assert world is not None + assert world.getNumSkeletons() == 1 + + # Check if the world is correctly loaded + model_1 = world.getSkeleton(0) + assert model_1 is not None + assert model_1.getName() == "model_1" + assert model_1.getNumBodyNodes() == 2 + assert model_1.getNumJoints() == 2 + + world.setGravity([0, 0, -50]) + + # Simulate 1 step + world.step() + t = world.getTime() + + # Get time step size + dt = world.getTimeStep() + assert dt > 0 + assert t == pytest.approx(dt) + + # Get joint and get force torque + link_1 = model_1.getBodyNode("link_1") + assert link_1 is not None + link_2 = model_1.getBodyNode("link_2") + assert link_2 is not None + joint_01 = model_1.getJoint("joint_01") + assert joint_01 is not None + joint_12 = model_1.getJoint("joint_12") + assert joint_12 is not None + + tf = dart.math.Isometry3() + + # Run 10 steps + for _ in range(10): + world.step() + + #---------------------- + # Test joint_01 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_01.getTransformFromParentBodyNode().translation()) + parent_frame01 = dart.dynamics.SimpleFrame(dart.dynamics.Frame.World(), "parent_frame01", tf) + tf.set_identity() + tf.set_translation(joint_01.getTransformFromChildBodyNode().translation()) + child_frame01 = dart.dynamics.SimpleFrame(link_1, "child_frame01", tf) + + parent_f01 = joint_01.getWrenchToParentBodyNode(parent_frame01) + assert (parent_f01 == [0, 0, 0, 0, 0, 1000]).all() + + child_f01 = joint_01.getWrenchToChildBodyNode(child_frame01) + assert (child_f01 == -parent_f01).all() + + #---------------------- + # Test joint_12 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_12.getTransformFromParentBodyNode().translation()) + parent_frame12 = dart.dynamics.SimpleFrame(link_1, "parent_frame12", tf) + tf.set_identity() + tf.set_translation(joint_12.getTransformFromChildBodyNode().translation()) + child_frame12 = dart.dynamics.SimpleFrame(link_2, "child_frame12", tf) + + parent_f12 = joint_12.getWrenchToParentBodyNode(parent_frame12) + assert (parent_f12 == [0, 0, 0, 0, 0, 500]).all() + + child_f12 = joint_12.getWrenchToChildBodyNode(child_frame12) + assert (child_f12 == -parent_f12).all() + + +def test_force_torque_at_joint_limits(): + # Load world + world = read_world("dart://sample/sdf/test/force_torque_test.world") + assert world is not None + assert world.getNumSkeletons() == 1 + + # Check if the world is correctly loaded + model_1 = world.getSkeleton(0) + assert model_1 is not None + assert model_1.getName() == "model_1" + assert model_1.getNumBodyNodes() == 2 + assert model_1.getNumJoints() == 2 + + world.setGravity([0, 0, -50]) + + # Simulate 1 step + world.step() + t = world.getTime() + + # Get time step size + dt = world.getTimeStep() + assert dt > 0 + assert t == pytest.approx(dt) + + # Get joint and get force torque + link_1 = model_1.getBodyNode("link_1") + assert link_1 is not None + link_2 = model_1.getBodyNode("link_2") + assert link_2 is not None + joint_01 = model_1.getJoint("joint_01") + assert joint_01 is not None + joint_12 = model_1.getJoint("joint_12") + assert joint_12 is not None + + # Change gravity so that the top link topples over, then remeasure + world.setGravity([-30, 10, -50]) + + # Wait for dynamics to be stabilized + for i in range(2000): + world.step() + + tf = dart.math.Isometry3() + + # Run 5 steps + for _ in range(5): + world.step() + + #---------------------- + # Test joint_01 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_01.getTransformFromParentBodyNode().translation()) + parent_frame01 = dart.dynamics.SimpleFrame(dart.dynamics.Frame.World(), "parent_frame01", tf) + tf.set_identity() + tf.set_translation(joint_01.getTransformFromChildBodyNode().translation()) + child_frame01 = dart.dynamics.SimpleFrame(link_1, "child_frame01", tf) + + parent_f01 = joint_01.getWrenchToParentBodyNode(parent_frame01) + assert np.isclose(parent_f01, [750, 0, -450, 600, -200, 1000], rtol=0.1, atol=4.5).all() + + child_f01 = joint_01.getWrenchToChildBodyNode(child_frame01) + assert np.isclose(child_f01, [-750, -450, 0, -600, 1000, 200], rtol=0.1, atol=4.5).all() + + #---------------------- + # Test joint_12 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_12.getTransformFromParentBodyNode().translation()) + parent_frame12 = dart.dynamics.SimpleFrame(link_1, "parent_frame12", tf) + tf.set_identity() + tf.set_translation(joint_12.getTransformFromChildBodyNode().translation()) + child_frame12 = dart.dynamics.SimpleFrame(link_2, "child_frame12", tf) + + parent_f12 = joint_12.getWrenchToParentBodyNode(parent_frame12) + assert np.isclose(parent_f12, [250, 150, 0, 300, -500, -100], rtol=0.1, atol=0.1).all() + + child_f12 = joint_12.getWrenchToChildBodyNode(child_frame12) + assert np.isclose(child_f12, [-250, -150, 0, -300, 500, 100], rtol=0.1, atol=0.1).all() + + +def test_force_torque_at_joint_limits_with_external_forces(): + # Load world + world = read_world("dart://sample/sdf/test/force_torque_test2.world") + assert world is not None + assert world.getNumSkeletons() == 1 + + # Check if the world is correctly loaded + model_1 = world.getSkeleton(0) + assert model_1 is not None + assert model_1.getName() == "boxes" + assert model_1.getNumBodyNodes() == 3 + assert model_1.getNumJoints() == 3 + assert model_1.getNumDofs() == 2 + + # The first joint is fixed joint + assert model_1.getRootJoint().getType() == dart.dynamics.WeldJoint.getStaticType() + + world.setGravity([0, 0, -50]) + + # Simulate 1 step + world.step() + t = world.getTime() + + # Get time step size + dt = world.getTimeStep() + assert dt > 0 + assert t == pytest.approx(dt) + + # Get joint and get force torque + link_1 = model_1.getBodyNode("link1") + assert link_1 is not None + link_2 = model_1.getBodyNode("link2") + assert link_2 is not None + link_3 = model_1.getBodyNode("link3") + assert link_3 is not None + joint_12 = model_1.getJoint("joint1") + assert joint_12 is not None + joint_23 = model_1.getJoint("joint2") + assert joint_23 is not None + + tf = dart.math.Isometry3() + + # Run 45005 steps + kp1 = 5e+4 + kp2 = 1e+4 + target1 = 0 + target2 = -0.25 * math.pi + steps = 4500 + for _ in range(steps): + # PD control + j1_state = joint_12.getPosition(0) + j2_state = joint_23.getPosition(0) + p1_error = target1 - j1_state + p2_error = target2 - j2_state + effort1 = kp1 * p1_error + effort2 = kp2 * p2_error + joint_12.setForce(0, effort1) + joint_23.setForce(0, effort2) + + world.step() + + assert joint_12.getPosition(0) == pytest.approx(target1, abs=1e-1) + assert joint_23.getPosition(0) == pytest.approx(target2, abs=1e-1) + + tol = 2 + + #---------------------- + # Test joint_12 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_12.getTransformFromParentBodyNode().translation()) + parent_frame01 = dart.dynamics.SimpleFrame(link_1, "parent_frame01", tf) + tf.set_identity() + tf.set_translation(joint_12.getTransformFromChildBodyNode().translation()) + child_frame01 = dart.dynamics.SimpleFrame(link_2, "child_frame01", tf) + + parent_f01 = joint_12.getWrenchToParentBodyNode(parent_frame01) + assert np.isclose(parent_f01, [25, -175, 0, 0, 0, 300], rtol=0.01, atol=tol).all() + + child_f01 = joint_12.getWrenchToChildBodyNode(child_frame01) + assert np.isclose(child_f01, [-25, 175, 0, 0, 0, -300], rtol=0.01, atol=tol).all() + + #---------------------- + # Test joint_23 wrench + #---------------------- + + # Reference adjustment for the difference of the joint frame conventions + # between Gazebo and DART + tf.set_identity() + tf.set_translation(joint_23.getTransformFromParentBodyNode().translation()) + parent_frame12 = dart.dynamics.SimpleFrame(link_2, "parent_frame12", tf) + tf.set_identity() + tf.set_translation(joint_23.getTransformFromChildBodyNode().translation()) + child_frame12 = dart.dynamics.SimpleFrame(link_3, "child_frame12", tf) + + parent_f12 = joint_23.getWrenchToParentBodyNode(parent_frame12) + assert np.isclose(parent_f12, [25, 0, 0, 0, 0, 50], rtol=0.01, atol=tol).all() + + child_f12 = joint_23.getWrenchToChildBodyNode(child_frame12) + assert np.isclose(child_f12, [-17.678, 0, 17.679, -35.355, 0, -35.355], rtol=0.01, atol=tol).all() + + + + +if __name__ == "__main__": + pytest.main() diff --git a/unittests/comprehensive/test_JointForceTorque.cpp b/unittests/comprehensive/test_JointForceTorque.cpp index 2ded70d49d64c..5a721732f8284 100644 --- a/unittests/comprehensive/test_JointForceTorque.cpp +++ b/unittests/comprehensive/test_JointForceTorque.cpp @@ -70,9 +70,9 @@ TEST(JointForceTorqueTest, Static) // Load world WorldPtr world = readWorld("dart://sample/sdf/test/force_torque_test.world"); ASSERT_NE(world, nullptr); - - // Check if the world is correct loaded ASSERT_EQ(world->getNumSkeletons(), 1); + + // Check if the world is correctly loaded SkeletonPtr model_1 = world->getSkeleton(0); ASSERT_NE(model_1, nullptr); EXPECT_EQ(model_1->getName(), "model_1"); @@ -113,8 +113,8 @@ TEST(JointForceTorqueTest, Static) // Test joint_01 wrench //---------------------- - // Reference adjustment for different joint frame conventions between Gazebo - // and DART + // Reference adjustment for the difference of the joint frame conventions + // between Gazebo and DART tf.setIdentity(); tf.translation() = joint_01->getTransformFromParentBodyNode().translation(); SimpleFramePtr parentFrame01 @@ -141,8 +141,8 @@ TEST(JointForceTorqueTest, Static) // Test joint_12 wrench //---------------------- - // Reference adjustment for different joint frame conventions between Gazebo - // and DART + // Reference adjustment for the difference of the joint frame conventions + // between Gazebo and DART tf.setIdentity(); tf.translation() = joint_12->getTransformFromParentBodyNode().translation(); SimpleFramePtr parentFrame12 @@ -168,14 +168,14 @@ TEST(JointForceTorqueTest, Static) } //============================================================================== -TEST(JointForceTorqueTest, ForceTorqeAtJointLimits) +TEST(JointForceTorqueTest, ForceTorqueAtJointLimits) { // Load world WorldPtr world = readWorld("dart://sample/sdf/test/force_torque_test.world"); ASSERT_NE(world, nullptr); - - // Check if the world is correct loaded ASSERT_EQ(world->getNumSkeletons(), 1); + + // Check if the world is correctly loaded SkeletonPtr model_1 = world->getSkeleton(0); ASSERT_NE(model_1, nullptr); EXPECT_EQ(model_1->getName(), "model_1"); @@ -225,8 +225,8 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimits) // Test joint_01 wrench //---------------------- - // Reference adjustment for different joint frame conventions between Gazebo - // and DART + // Reference adjustment for the difference of the joint frame conventions + // between Gazebo and DART tf.setIdentity(); tf.translation() = joint_01->getTransformFromParentBodyNode().translation(); SimpleFramePtr parentFrame01 @@ -258,8 +258,8 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimits) // Test joint_12 wrench //---------------------- - // Reference adjustment for different joint frame conventions between Gazebo - // and DART + // Reference adjustment for the difference of the joint frame conventions + // between Gazebo and DART tf.setIdentity(); tf.translation() = joint_12->getTransformFromParentBodyNode().translation(); SimpleFramePtr parentFrame12 @@ -290,9 +290,9 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimitsWithExternalForces) // Load world WorldPtr world = readWorld("dart://sample/sdf/test/force_torque_test2.world"); ASSERT_NE(world, nullptr); - - // Check if the world is correct loaded ASSERT_EQ(world->getNumSkeletons(), 1); + + // Check if the world is correctly loaded SkeletonPtr model_1 = world->getSkeleton(0); ASSERT_NE(model_1, nullptr); ASSERT_EQ(model_1->getName(), "boxes"); @@ -331,7 +331,7 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimitsWithExternalForces) Eigen::Isometry3d tf = Eigen::Isometry3d::Identity(); - // Run 5 steps + // Run 4500 steps const double kp1 = 5e+4; const double kp2 = 1e+4; const double target1 = 0; @@ -358,7 +358,7 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimitsWithExternalForces) const double tol = 2; //---------------------- - // Test joint_01 wrench + // Test joint_12 wrench //---------------------- // Reference adjustment for different joint frame conventions between Gazebo @@ -374,7 +374,7 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimitsWithExternalForces) const Eigen::Vector6d parentF01 = joint_12->getWrenchToParentBodyNode(parentFrame01.get()); - EXPECT_NEAR(parentF01[0], 25, tol); // torque + EXPECT_NEAR(parentF01[0], 25, tol); // torque EXPECT_NEAR(parentF01[1], -175, tol); EXPECT_NEAR(parentF01[2], 0, tol); EXPECT_NEAR(parentF01[3], 0, tol); // force @@ -386,7 +386,7 @@ TEST(JointForceTorqueTest, ForceTorqeAtJointLimitsWithExternalForces) EXPECT_TRUE(childF01.isApprox(-parentF01, tol)); //---------------------- - // Test joint_12 wrench + // Test joint_23 wrench //---------------------- // Reference adjustment for different joint frame conventions between Gazebo From 31a780e8ef5e9782662da2238c721d2b9ecc35bd Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 4 Nov 2021 09:33:44 -0700 Subject: [PATCH 2/5] Revert SimpleFrame constructor bindings --- python/dartpy/dynamics/SimpleFrame.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/python/dartpy/dynamics/SimpleFrame.cpp b/python/dartpy/dynamics/SimpleFrame.cpp index 1d4142cbfe779..166a5a825fd2d 100644 --- a/python/dartpy/dynamics/SimpleFrame.cpp +++ b/python/dartpy/dynamics/SimpleFrame.cpp @@ -47,15 +47,21 @@ void SimpleFrame(py::module& m) dart::dynamics::SimpleFrame, dart::dynamics::ShapeFrame, dart::dynamics::Detachable, - std::shared_ptr >(m, "SimpleFrame") + std::shared_ptr>(m, "SimpleFrame") + .def(::py::init<>()) + .def(::py::init(), ::py::arg("refFrame")) + .def( + ::py::init(), + ::py::arg("refFrame"), + ::py::arg("name")) .def( ::py::init< dart::dynamics::Frame*, const std::string&, const Eigen::Isometry3d&>(), - ::py::arg("refFrame") = dart::dynamics::Frame::World(), - ::py::arg("name") = "simple_frame", - ::py::arg("relativeTransform") = Eigen::Isometry3d::Identity()) + ::py::arg("refFrame"), + ::py::arg("name"), + ::py::arg("relativeTransform")) .def( "setName", +[](dart::dynamics::SimpleFrame* self, const std::string& _name) From f70e100fc519434d8baf22ef3cdaebeb25344f32 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 4 Nov 2021 09:35:20 -0700 Subject: [PATCH 3/5] Update changelog --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 4770841859777..103cba38122ce 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -6,6 +6,10 @@ * Fixed bullet header include: [#1620](https://github.com/dartsim/dart/pull/1620) +* dartpy + + * Added Python bindings for Joint::getWrenchTo{Child|Parent}BodyNode: [#1621](https://github.com/dartsim/dart/pull/1621) + ### [DART 6.12.0 (2021-11-1)](https://github.com/dartsim/dart/milestone/66?closed=1) * API Breaking Changes From 5cb19aa2044a26b2428bf304eb5842c9b38e1fdc Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 4 Nov 2021 09:49:13 -0700 Subject: [PATCH 4/5] Remove install-dartpy in favor of install; using pybind11 find module to find python packages --- CMakeLists.txt | 2 +- python/dartpy/CMakeLists.txt | 40 +++++++++++++++++------------------- 2 files changed, 20 insertions(+), 22 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6c9db8ae16d3a..100bfb8b59beb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -608,7 +608,7 @@ message(STATUS "Run 'make view_docs' to see the API documentation") message(STATUS "Run 'make install' to install all the C++ components") if(TARGET dartpy) message(STATUS "Run 'make dartpy' to build dartpy") - message(STATUS "Run 'make install-dartpy' to install dartpy") + message(STATUS "Run 'make install' to install dartpy") endif() #=============================================================================== diff --git a/python/dartpy/CMakeLists.txt b/python/dartpy/CMakeLists.txt index 8d7a357fef86d..8952be0aef306 100644 --- a/python/dartpy/CMakeLists.txt +++ b/python/dartpy/CMakeLists.txt @@ -10,34 +10,33 @@ if(NOT DARTPY_PYTHON_VERSION) set(DARTPY_PYTHON_VERSION 3.4 CACHE STRING "Choose the target Python version (e.g., 3.4, 2.7)" FORCE) endif() -find_package(PythonInterp ${DARTPY_PYTHON_VERSION} QUIET) -execute_process(COMMAND ${PYTHON_EXECUTABLE} -c - "from distutils.sysconfig import get_python_lib;\ - print(get_python_lib(plat_specific=True, prefix=''))" - OUTPUT_VARIABLE PYTHON_SITE_PACKAGES - OUTPUT_STRIP_TRAILING_WHITESPACE -) -if(NOT IS_ABSOLUTE PYTHON_SITE_PACKAGES) - set(PYTHON_SITE_PACKAGES "${CMAKE_INSTALL_PREFIX}/${PYTHON_SITE_PACKAGES}") +# Find pybind11, including PythonInterp and PythonLibs +# Needs to set PYBIND11_PYTHON_VERSION before finding pybind11 +set(PYBIND11_PYTHON_VERSION ${DARTPY_PYTHON_VERSION}) +find_package(pybind11 2.2.0 QUIET) +if(NOT pybind11_FOUND) + message(WARNING "Disabling [dartpy] due to missing pybind11 >= 2.2.0.") + return() endif() + if(NOT PythonInterp_FOUND AND NOT PYTHONINTERP_FOUND) message(WARNING "Disabling [dartpy] due to missing [PythonInterp].") return() endif() -find_package(PythonLibs ${DARTPY_PYTHON_VERSION} QUIET) if(NOT PythonLibs_FOUND AND NOT PYTHONLIBS_FOUND) message(WARNING "Disabling [dartpy] due to missing [PythonLibs].") return() endif() -# Find pybind11 -# Needs to set PYBIND11_PYTHON_VERSION before finding pybind11 -set(PYBIND11_PYTHON_VERSION ${DARTPY_PYTHON_VERSION}) -find_package(pybind11 2.2.0 QUIET) -if(NOT pybind11_FOUND) - message(WARNING "Disabling [dartpy] due to missing pybind11 >= 2.2.0.") - return() +execute_process(COMMAND ${PYTHON_EXECUTABLE} -c + "from distutils.sysconfig import get_python_lib;\ + print(get_python_lib(plat_specific=True, prefix=''))" + OUTPUT_VARIABLE PYTHON_SITE_PACKAGES + OUTPUT_STRIP_TRAILING_WHITESPACE +) +if(NOT IS_ABSOLUTE PYTHON_SITE_PACKAGES) + set(PYTHON_SITE_PACKAGES "${CMAKE_INSTALL_PREFIX}/${PYTHON_SITE_PACKAGES}") endif() file(GLOB_RECURSE dartpy_headers "*.h" "*.hpp") @@ -99,10 +98,9 @@ if(BUILD_SHARED_LIBS) "Install the shared libraries to be able to import ${pybind_module}." ) endif() -add_custom_target(install-${pybind_module} - COMMENT "${install_comment}" - COMMAND ${CMAKE_COMMAND} -E copy ${PYBIND_MODULE} ${PYTHON_SITE_PACKAGES} - DEPENDS ${install_dartpy_deps} +# Install the pybind module to site-packages directory +install(TARGETS ${pybind_module} + LIBRARY DESTINATION "${PYTHON_SITE_PACKAGES}" ) list(REMOVE_ITEM dartpy_headers From 80e4b2c710684cfad0dc8c56120bd5e54536fdad Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 4 Nov 2021 10:59:59 -0700 Subject: [PATCH 5/5] Update build script --- .ci/build.sh | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/.ci/build.sh b/.ci/build.sh index 0790941cebb4b..0c6172f2413a0 100755 --- a/.ci/build.sh +++ b/.ci/build.sh @@ -164,15 +164,14 @@ if [ "$BUILD_TUTORIALS" = "ON" ]; then make -j$num_threads all tutorials fi -make -j$num_threads install - # dartpy: build, test, and install if [ "$BUILD_DARTPY" = "ON" ]; then make -j$num_threads dartpy make pytest - make -j$num_threads install-dartpy fi +make -j$num_threads install + # Codecov if [ "$CODECOV" = "ON" ]; then lcov --directory . --capture --output-file coverage.info