Skip to content
Snippets Groups Projects
Unverified Commit 99c83081 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by GitHub
Browse files

Merge pull request #90 from gabrielebndn/refactoring

[refactoring] Restructure Python tests
parents 8b6d1398 d4c9674d
No related branches found
No related tags found
No related merge requests found
...@@ -5,6 +5,7 @@ env: ...@@ -5,6 +5,7 @@ env:
- CTEST_PARALLEL_LEVEL=4 - CTEST_PARALLEL_LEVEL=4
- CTEST_OUTPUT_ON_FAILURE=1 - CTEST_OUTPUT_ON_FAILURE=1
- CXX_FLAGS_DEBUG="-O1" - CXX_FLAGS_DEBUG="-O1"
- BUILD_PYTHON_INTERFACE=ON
matrix: matrix:
include: include:
...@@ -87,13 +88,17 @@ matrix: ...@@ -87,13 +88,17 @@ matrix:
- eigen - eigen
- octomap - octomap
before_install:
- if [ "$TRAVIS_OS_NAME" = "linux" ]; then source travis_custom/custom_before_install_linux.sh ; fi
- if [ "$TRAVIS_OS_NAME" = "osx" ]; then source travis_custom/custom_before_install_osx.sh ; fi
script: script:
# Create build directory # Create build directory
- mkdir build - mkdir build
- cd build - cd build
# Configure # Configure
- cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DCMAKE_CXX_FLAGS=-w -DCMAKE_CXX_FLAGS_DEBUG=${CXX_FLAGS_DEBUG} .. - cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DCMAKE_CXX_FLAGS=-w -DCMAKE_CXX_FLAGS_DEBUG=${CXX_FLAGS_DEBUG} -DBUILD_PYTHON_INTERFACE=${BUILD_PYTHON_INTERFACE} ..
# Build # Build
- make -j4 - make -j4
......
...@@ -58,7 +58,7 @@ IF(APPLE) ...@@ -58,7 +58,7 @@ IF(APPLE)
endif("${isSystemDir}" STREQUAL "-1") endif("${isSystemDir}" STREQUAL "-1")
ENDIF(APPLE) ENDIF(APPLE)
OPTION(BUILD_PYTHON_INTERFACE OFF) OPTION(BUILD_PYTHON_INTERFACE "Build the python bindings" OFF)
# Tell CMake that we compute the PROJECT_VERSION manually. # Tell CMake that we compute the PROJECT_VERSION manually.
CMAKE_POLICY(SET CMP0048 OLD) CMAKE_POLICY(SET CMP0048 OLD)
......
...@@ -114,7 +114,9 @@ void exposeShapes () ...@@ -114,7 +114,9 @@ void exposeShapes ()
("Box", init<>()) ("Box", init<>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL>()) .def (init<FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<Vec3f>()) .def (init<Vec3f>())
.def_readwrite ("halfSide", &Box::halfSide) .add_property("halfSide",
make_getter(&Box::halfSide, return_value_policy<return_by_value>()),
make_setter(&Box::halfSide, return_value_policy<return_by_value>()));
; ;
class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> > class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> >
......
...@@ -69,9 +69,6 @@ void exposeMaths () ...@@ -69,9 +69,6 @@ void exposeMaths ()
if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>()) if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
eigenpy::exposeAngleAxis(); eigenpy::exposeAngleAxis();
eigenpy::enableEigenPySpecific<Matrix3f>();
eigenpy::enableEigenPySpecific<Vec3f >();
class_ <Transform3f> ("Transform3f", init<>()) class_ <Transform3f> ("Transform3f", init<>())
.def (init<Matrix3f, Vec3f>()) .def (init<Matrix3f, Vec3f>())
.def (init<Quaternion3f, Vec3f>()) .def (init<Quaternion3f, Vec3f>())
......
...@@ -57,3 +57,8 @@ endif(HPP_FCL_HAVE_OCTOMAP) ...@@ -57,3 +57,8 @@ endif(HPP_FCL_HAVE_OCTOMAP)
## Benchmark ## Benchmark
add_executable(test-benchmark benchmark.cpp) add_executable(test-benchmark benchmark.cpp)
target_link_libraries(test-benchmark hpp-fcl ${Boost_LIBRARIES} utility) target_link_libraries(test-benchmark hpp-fcl ${Boost_LIBRARIES} utility)
## Python tests
IF(BUILD_PYTHON_INTERFACE)
ADD_SUBDIRECTORY(python_unit)
ENDIF(BUILD_PYTHON_INTERFACE)
SET(${PROJECT_NAME}_PYTHON_TESTS
geometric_shapes
)
FOREACH(TEST ${${PROJECT_NAME}_PYTHON_TESTS})
ADD_PYTHON_UNIT_TEST("py-${TEST}" "test/python_unit/${TEST}.py" "python")
ENDFOREACH(TEST ${${PROJECT_NAME}_PYTHON_TESTS})
import unittest
import hppfcl
hppfcl.switchToNumpyMatrix()
import numpy as np
class TestGeometricShapes(unittest.TestCase):
def test_capsule(self):
capsule = hppfcl.Capsule(1.,2.)
self.assertIsInstance(capsule, hppfcl.Capsule)
self.assertIsInstance(capsule, hppfcl.ShapeBase)
self.assertIsInstance(capsule, hppfcl.CollisionGeometry)
self.assertEqual(capsule.getNodeType(), hppfcl.NODE_TYPE.GEOM_CAPSULE)
self.assertEqual(capsule.radius,1.)
self.assertEqual(capsule.lz,2.)
capsule.radius = 3.
capsule.lz = 4.
self.assertEqual(capsule.radius,3.)
self.assertEqual(capsule.lz,4.)
def test_box1(self):
box = hppfcl.Box(np.matrix([1.,2.,3.]).T)
self.assertIsInstance(box, hppfcl.Box)
self.assertIsInstance(box, hppfcl.ShapeBase)
self.assertIsInstance(box, hppfcl.CollisionGeometry)
self.assertEqual(box.getNodeType(), hppfcl.NODE_TYPE.GEOM_BOX)
self.assertTrue(np.array_equal(box.halfSide,np.matrix([.5,1.,1.5]).T))
box.halfSide = np.matrix([4.,5.,6.]).T
self.assertTrue(np.array_equal(box.halfSide,np.matrix([4.,5.,6.]).T))
def test_box2(self):
box = hppfcl.Box(1.,2.,3)
self.assertIsInstance(box, hppfcl.Box)
self.assertIsInstance(box, hppfcl.ShapeBase)
self.assertIsInstance(box, hppfcl.CollisionGeometry)
self.assertEqual(box.getNodeType(), hppfcl.NODE_TYPE.GEOM_BOX)
self.assertEqual(box.halfSide[0],0.5)
self.assertEqual(box.halfSide[1],1.0)
self.assertEqual(box.halfSide[2],1.5)
box.halfSide[0] = 4.
box.halfSide[0] = 5.
box.halfSide[0] = 6.
# self.assertEqual(box.halfSide[0],4.)
# self.assertEqual(box.halfSide[1],5.)
# self.assertEqual(box.halfSide[2],6.)
def test_sphere(self):
sphere = hppfcl.Sphere(1.)
self.assertIsInstance(sphere, hppfcl.Sphere)
self.assertIsInstance(sphere, hppfcl.ShapeBase)
self.assertIsInstance(sphere, hppfcl.CollisionGeometry)
self.assertEqual(sphere.getNodeType(), hppfcl.NODE_TYPE.GEOM_SPHERE)
self.assertEqual(sphere.radius,1.)
sphere.radius = 2.
self.assertEqual(sphere.radius,2.)
def test_cylinder(self):
cylinder = hppfcl.Cylinder(1.,2.)
self.assertIsInstance(cylinder, hppfcl.Cylinder)
self.assertIsInstance(cylinder, hppfcl.ShapeBase)
self.assertIsInstance(cylinder, hppfcl.CollisionGeometry)
self.assertEqual(cylinder.getNodeType(), hppfcl.NODE_TYPE.GEOM_CYLINDER)
self.assertEqual(cylinder.radius,1.)
self.assertEqual(cylinder.lz,2.)
def test_cone(self):
cone = hppfcl.Cone(1.,2.)
self.assertIsInstance(cone, hppfcl.Cone)
self.assertIsInstance(cone, hppfcl.ShapeBase)
self.assertIsInstance(cone, hppfcl.CollisionGeometry)
self.assertEqual(cone.getNodeType(), hppfcl.NODE_TYPE.GEOM_CONE)
self.assertEqual(cone.radius,1.)
self.assertEqual(cone.lz,2.)
cone.radius = 3.
cone.lz = 4.
self.assertEqual(cone.radius,3.)
self.assertEqual(cone.lz,4.)
if __name__ == '__main__':
unittest.main()
\ No newline at end of file
File moved
File moved
File moved
File moved
File moved
File moved
File moved
# Add robotpkg
sudo sh -c "echo \"deb [arch=amd64] http://robotpkg.openrobots.org/packages/debian/pub $(lsb_release -cs) robotpkg\" >> /etc/apt/sources.list"
curl http://robotpkg.openrobots.org/packages/debian/robotpkg.key | sudo apt-key add -
sudo apt-get update
# install eigenpy
sudo apt-get -qqy install robotpkg-py27-eigenpy
# set environment variables
export PKG_CONFIG_PATH="${PKG_CONFIG_PATH}:/opt/openrobots/lib/pkgconfig"
export LD_LIBRARY_PATH="${LD_LIBRARY_PATH}:/opt/openrobots/lib"
\ No newline at end of file
# Add gepetto tap
brew tap gepetto/homebrew-gepetto
# install eigenpy
brew install eigenpy
# set environment variables
export PKG_CONFIG_PATH="${PKG_CONFIG_PATH}:/opt/openrobots/lib/pkgconfig"
export LD_LIBRARY_PATH="${LD_LIBRARY_PATH}:/opt/openrobots/lib"
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment