Skip to content

Commit

Permalink
Merge branch 'bulletphysics:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
stephengold authored Feb 13, 2024
2 parents 0309615 + 6bb8d11 commit 7824fc7
Show file tree
Hide file tree
Showing 1,090 changed files with 158,706 additions and 15,455 deletions.
38 changes: 38 additions & 0 deletions .github/workflows/cmake.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
name: CMake

on:
push:
branches: [ master ]
pull_request:
branches: [ master ]

env:
# Customize the CMake build type here (Release, Debug, RelWithDebInfo, etc.)
BUILD_TYPE: Release

jobs:
build:
# The CMake configure and build commands are platform agnostic and should work equally
# well on Windows or Mac. You can convert this to a matrix build if you need
# cross-platform coverage.
# See: https://docs.github.com/en/free-pro-team@latest/actions/learn-github-actions/managing-complex-workflows#using-a-build-matrix
runs-on: ubuntu-latest

steps:
- uses: actions/checkout@v2

- name: Configure CMake
# Configure CMake in a 'build' subdirectory. `CMAKE_BUILD_TYPE` is only required if you are using a single-configuration generator such as make.
# See https://cmake.org/cmake/help/latest/variable/CMAKE_BUILD_TYPE.html?highlight=cmake_build_type
run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}}

- name: Build
# Build your program with the given configuration
run: cmake --build ${{github.workspace}}/build --config ${{env.BUILD_TYPE}}

- name: Test
working-directory: ${{github.workspace}}/build
# Execute tests defined by the CMake configuration.
# See https://cmake.org/cmake/help/latest/manual/ctest.1.html for more detail
run: ctest -C ${{env.BUILD_TYPE}}

4 changes: 4 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -36,3 +36,7 @@ CTestTestFile.cmake

# vim temp files
*.swp

.vscode/
.idea/
cmake-build-debug/
51 changes: 0 additions & 51 deletions .travis.yml

This file was deleted.

5 changes: 4 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ OPTION(BUILD_SHARED_LIBS "Use shared libraries" OFF)
OPTION(USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD "Use btSoftMultiBodyDynamicsWorld" ON)
OPTION(USE_OPENVR "Use OpenVR for virtual reality" OFF)

OPTION(ENABLE_VHACD "Use VHACD in BulletRobotics and pybullet" ON)

OPTION(BULLET2_MULTITHREADING "Build Bullet 2 libraries with mutex locking around certain operations (required for multi-threading)" OFF)
IF (BULLET2_MULTITHREADING)
OPTION(BULLET2_USE_OPEN_MP_MULTITHREADING "Build Bullet 2 with support for multi-threading with OpenMP (requires a compiler with OpenMP support)" OFF)
Expand Down Expand Up @@ -252,7 +254,8 @@ IF(BULLET2_MULTITHREADING)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
ENDIF (NOT MSVC)
IF (NOT WIN32)
LINK_LIBRARIES( pthread )
FIND_PACKAGE(Threads)
LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} )
ENDIF (NOT WIN32)
ENDIF (BULLET2_MULTITHREADING)

Expand Down
164 changes: 101 additions & 63 deletions Extras/BulletRobotics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@ INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
)
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)



SET(BulletRobotics_INCLUDES
../../examples/CommonInterfaces/Common2dCanvasInterface.h
Expand Down Expand Up @@ -94,69 +97,102 @@ SET(BulletRobotics_INCLUDES
)

SET(BulletRobotics_SRCS ${BulletRobotics_INCLUDES}
../../examples/OpenGLWindow/SimpleCamera.cpp

../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp

../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.cpp

../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/b3Clock.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/ChromeTraceUtil.cpp

../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp
../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp
../../examples/ThirdPartyLibs/BussIK/Misc.cpp
../../examples/ThirdPartyLibs/BussIK/Node.cpp
../../examples/ThirdPartyLibs/BussIK/Tree.cpp
../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp

../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp

../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h

../../examples/OpenGLWindow/SimpleCamera.cpp

../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp

../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.cpp

../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/b3Clock.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/ChromeTraceUtil.cpp

../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp
../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp
../../examples/ThirdPartyLibs/BussIK/Misc.cpp
../../examples/ThirdPartyLibs/BussIK/Node.cpp
../../examples/ThirdPartyLibs/BussIK/Tree.cpp
../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp

../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp

../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp


)

IF(ENABLE_VHACD)
ADD_DEFINITIONS(-DBT_ENABLE_VHACD)
SET(BulletRobotics_SRCS ${BulletRobotics_SRCS}
../../Extras/VHACD/test/src/main_vhacd.cpp
../../Extras/VHACD/src/VHACD.cpp
../../Extras/VHACD/src/vhacdICHull.cpp
../../Extras/VHACD/src/vhacdManifoldMesh.cpp
../../Extras/VHACD/src/vhacdMesh.cpp
../../Extras/VHACD/src/vhacdVolume.cpp
)
INCLUDE_DIRECTORIES(
../../Extras/VHACD/inc
../../Extras/VHACD/public
)
ENDIF(ENABLE_VHACD)

IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
Expand All @@ -180,7 +216,8 @@ ELSE(WIN32)
ENDIF(BUILD_CLSOCKET)

IF(NOT APPLE)
LINK_LIBRARIES( pthread ${DL} )
FIND_PACKAGE(Threads)
LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} )
ENDIF(NOT APPLE)
ENDIF(WIN32)

Expand Down Expand Up @@ -267,6 +304,7 @@ INSTALL (
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)

IF(NOT MSVC)
SET(PKGCONFIG_INSTALL_PREFIX "lib${LIB_SUFFIX}/pkgconfig/" CACHE STRING "Base directory for pkgconfig files")
CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/bullet_robotics.pc.cmake
${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics.pc @ONLY)
INSTALL(
Expand Down
19 changes: 3 additions & 16 deletions Extras/BulletRoboticsGUI/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,21 +94,6 @@ SET(BulletRoboticsGUI_INCLUDES
)

SET(BulletRoboticsGUI_SRCS ${BulletRoboticsGUI_INCLUDES}

../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/GraphicsServerExample.cpp
../../examples/SharedMemory/GraphicsClientExample.cpp
Expand Down Expand Up @@ -146,7 +131,8 @@ ELSE(WIN32)
ENDIF(BUILD_CLSOCKET)

IF(NOT APPLE)
LINK_LIBRARIES( pthread ${DL} )
FIND_PACKAGE(Threads)
LINK_LIBRARIES( ${CMAKE_THREAD_LIBS_INIT} ${DL} )
ENDIF(NOT APPLE)
ENDIF(WIN32)

Expand Down Expand Up @@ -197,6 +183,7 @@ ENDIF (BUILD_SHARED_LIBS)
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)

IF(NOT MSVC)
SET(PKGCONFIG_INSTALL_PREFIX "lib${LIB_SUFFIX}/pkgconfig/" CACHE STRING "Base directory for pkgconfig files")
CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/bullet_robotics_gui.pc.cmake
${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics_gui.pc @ONLY)
INSTALL(
Expand Down
33 changes: 32 additions & 1 deletion Extras/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,36 @@
SUBDIRS( InverseDynamics BulletRoboticsGUI BulletRobotics obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils )
OPTION(BUILD_INVERSE_DYNAMIC_EXTRA "Build InverseDynamic extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_BULLET_ROBOTICS_GUI_EXTRA "Build BulletRoboticsGUI extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_BULLET_ROBOTICS_EXTRA "Build BulletRobotics extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_OBJ2SDF_EXTRA "Build obj2sdf extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_SERIALIZE_EXTRA "Build Serialize extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_CONVEX_DECOMPOSITION_EXTRA "Build ConvexDecomposition extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_HACD_EXTRA "Build HACD extra module, only applied when BUILD_EXTRAS is ON" ON)
OPTION(BUILD_GIMPACTUTILS_EXTRA "Build GIMPACTUtils extra module, only applied when BUILD_EXTRAS is ON" ON)

IF(BUILD_INVERSE_DYNAMIC_EXTRA)
SUBDIRS( InverseDynamics )
ENDIF()
IF(BUILD_BULLET_ROBOTICS_GUI_EXTRA)
SUBDIRS( BulletRoboticsGUI )
ENDIF()
IF(BUILD_BULLET_ROBOTICS_EXTRA)
SUBDIRS( BulletRobotics )
ENDIF()
IF(BUILD_OBJ2SDF_EXTRA)
SUBDIRS( obj2sdf )
ENDIF()
IF(BUILD_SERIALIZE_EXTRA)
SUBDIRS( Serialize )
ENDIF()
IF(BUILD_CONVEX_DECOMPOSITION_EXTRA)
SUBDIRS( ConvexDecomposition )
ENDIF()
IF(BUILD_HACD_EXTRA)
SUBDIRS( HACD )
ENDIF()
IF(BUILD_GIMPACTUTILS_EXTRA)
SUBDIRS( GIMPACTUtils )
ENDIF()


#Maya Dynamica plugin is moved to http://dynamica.googlecode.com
Expand Down
Loading

0 comments on commit 7824fc7

Please sign in to comment.