pybullet: add option to use NumPy to speed up, thanks to moof2k

option is disabled by default. When using cmake, use
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=ON
then both testrender.py and testrender_np.py will work
without numpy only testrender.py works.
The numpy.reshape is likely a no-op when using numpy array,
so we could remove testrender_np.py...

See https://github.com/bulletphysics/bullet3/pull/774
This commit is contained in:
Erwin Coumans
2016-09-11 11:35:12 +01:00
parent 5c76b01659
commit 7df9b69039
5 changed files with 70 additions and 3 deletions

View File

@@ -194,11 +194,28 @@ ENDIF()
OPTION(BUILD_BULLET3 "Set when you want to build Bullet 3" ON)
FIND_PACKAGE(PythonLibs)
OPTION(BUILD_PYBULLET "Set when you want to build pybullet (experimental Python bindings for Bullet)" OFF)
IF(BUILD_PYBULLET)
FIND_PACKAGE(PythonLibs)
OPTION(BUILD_PYBULLET_NUMPY "Set when you want to build pybullet with NumPy support" OFF)
IF(BUILD_PYBULLET_NUMPY)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_LIST_DIR}/build3/cmake)
#include(FindNumPy)
FIND_PACKAGE(NumPy)
if (PYTHON_NUMPY_FOUND)
message("NumPy found")
add_definitions(-DPYBULLET_USE_NUMPY)
else()
message("NumPy not found")
endif()
ENDIF()
OPTION(BUILD_PYBULLET "Set when you want to build pybullet (experimental Python bindings for Bullet)" OFF)
IF(WIN32)
SET(BUILD_SHARED_LIBS OFF CACHE BOOL "Shared Libs" FORCE)
ELSE(WIN32)

View File

@@ -0,0 +1,41 @@
# Find the Python NumPy package
# PYTHON_NUMPY_INCLUDE_DIR
# PYTHON_NUMPY_FOUND
# will be set by this script
cmake_minimum_required(VERSION 2.6)
if(NOT PYTHON_EXECUTABLE)
if(NumPy_FIND_QUIETLY)
find_package(PythonInterp QUIET)
else()
find_package(PythonInterp)
set(__numpy_out 1)
endif()
endif()
if (PYTHON_EXECUTABLE)
# Find out the include path
execute_process(
COMMAND "${PYTHON_EXECUTABLE}" -c
"from __future__ import print_function\ntry: import numpy; print(numpy.get_include(), end='')\nexcept:pass\n"
OUTPUT_VARIABLE __numpy_path)
# And the version
execute_process(
COMMAND "${PYTHON_EXECUTABLE}" -c
"from __future__ import print_function\ntry: import numpy; print(numpy.__version__, end='')\nexcept:pass\n"
OUTPUT_VARIABLE __numpy_version)
elseif(__numpy_out)
message(STATUS "Python executable not found.")
endif(PYTHON_EXECUTABLE)
find_path(PYTHON_NUMPY_INCLUDE_DIR numpy/arrayobject.h
HINTS "${__numpy_path}" "${PYTHON_INCLUDE_PATH}" NO_DEFAULT_PATH)
if(PYTHON_NUMPY_INCLUDE_DIR)
set(PYTHON_NUMPY_FOUND 1 CACHE INTERNAL "Python numpy found")
endif(PYTHON_NUMPY_INCLUDE_DIR)
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(NumPy REQUIRED_VARS PYTHON_NUMPY_INCLUDE_DIR
VERSION_VAR __numpy_version)

View File

@@ -1131,7 +1131,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
else
{
if ((button == 33))
if (button == 33)
{
m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);

View File

@@ -5,6 +5,11 @@ INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${PYTHON_INCLUDE_DIRS}
)
IF(BUILD_PYBULLET_NUMPY)
INCLUDE_DIRECTORIES(
${PYTHON_NUMPY_INCLUDE_DIR}
)
ENDIF()
SET(pybullet_SRCS
pybullet.c

View File

@@ -1821,7 +1821,11 @@ static PyMethodDef SpamMethods[] = {
{"renderImage", pybullet_renderImage, METH_VARARGS,
"Render an image (given the pixel resolution width, height, camera view "
"matrix, projection matrix, near, and far values), and return the "
"8-8-8bit RGB pixel data and floating point depth values"},
"8-8-8bit RGB pixel data and floating point depth values"
#ifdef PYBULLET_USE_NUMPY
" as NumPy arrays"
#endif
},
{"getContactPointData", pybullet_getContactPointData, METH_VARARGS,
"Return the contact point information for all or some of pairwise "