Merge pull request #2677 from erwincoumans/master

pybullet removeAllParameters, getMeshData
This commit is contained in:
erwincoumans 2020-03-17 00:58:18 -07:00 committed by GitHub
commit 3c9dde54a2
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
15 changed files with 476 additions and 192 deletions

View File

@ -222,13 +222,6 @@ IF(BUILD_ENET)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
set(BulletRobotics_CLSOCKET_INCLUDES
../../examples/SharedMemory/PhysicsClientTCP.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.h
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.h
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.h
)
set(BulletRobotics_CLSOCKET_SRCS
../../examples/SharedMemory/PhysicsClientTCP.cpp
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
@ -237,13 +230,8 @@ IF(BUILD_CLSOCKET)
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
)
set(BulletRobotics_INCLUDES
${BulletRobotics_INCLUDES}
${BulletRobotics_CLSOCKET_INCLUDES}
)
set(BulletRobotics_SRCS
${BulletRobotics_SRCS}
${BulletRobotics_CLSOCKET_INCLUDES}
${BulletRobotics_CLSOCKET_SRCS}
)
ENDIF()
@ -260,25 +248,12 @@ IF (BUILD_SHARED_LIBS)
TARGET_LINK_LIBRARIES(BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics LinearMath Bullet3Common)
ENDIF (BUILD_SHARED_LIBS)
IF (INSTALL_EXTRA_LIBS)
INSTALL(FILES
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientSharedMemory2_C_API.h
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.h
../../examples/SharedMemory/SharedMemoryPublic.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
DESTINATION include/bullet
)
INSTALL(FILES
${BulletRobotics_INCLUDES}
DESTINATION include/bullet_robotics
)
INSTALL (
DIRECTORY ${CMAKE_SOURCE_DIR}/examples/
DESTINATION include/bullet
FILES_MATCHING PATTERN "*.h*")
INSTALL(TARGETS
BulletRobotics
@ -301,5 +276,4 @@ IF(NOT MSVC)
${PKGCONFIG_INSTALL_PREFIX}
)
ENDIF(NOT MSVC)
ENDIF (INSTALL_EXTRA_LIBS)

View File

@ -0,0 +1,208 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
${BULLET_PHYSICS_SOURCE_DIR}/examples/SharedMemory
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
)
SET(BulletRoboticsGUI_INCLUDES
../../examples/CommonInterfaces/Common2dCanvasInterface.h
../../examples/CommonInterfaces/CommonCallbacks.h
../../examples/CommonInterfaces/CommonCameraInterface.h
../../examples/CommonInterfaces/CommonExampleInterface.h
../../examples/CommonInterfaces/CommonFileIOInterface.h
../../examples/CommonInterfaces/CommonGraphicsAppInterface.h
../../examples/CommonInterfaces/CommonGUIHelperInterface.h
../../examples/CommonInterfaces/CommonMultiBodyBase.h
../../examples/CommonInterfaces/CommonParameterInterface.h
../../examples/CommonInterfaces/CommonRenderInterface.h
../../examples/CommonInterfaces/CommonRigidBodyBase.h
../../examples/CommonInterfaces/CommonWindowInterface.h
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.h
../../examples/TinyRenderer/model.h
../../examples/TinyRenderer/tgaimage.h
../../examples/TinyRenderer/our_gl.h
../../examples/TinyRenderer/TinyRenderer.h
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.h
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/InProcessMemory.h
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.h
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/SharedMemoryPublic.h
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/RobotLoggingUtil.h
../../examples/Utils/b3Clock.h
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/ChromeTraceUtil.h
../../examples/Utils/b3ERPCFMHelper.hpp
../../examples/Utils/b3ReferenceFrameHelper.hpp
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.h
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/ThirdPartyLibs/stb_image/stb_image.h
../../examples/ThirdPartyLibs/BussIK/Jacobian.h
../../examples/ThirdPartyLibs/BussIK/LinearR2.h
../../examples/ThirdPartyLibs/BussIK/LinearR3.h
../../examples/ThirdPartyLibs/BussIK/LinearR4.h
../../examples/ThirdPartyLibs/BussIK/MatrixRmn.h
../../examples/ThirdPartyLibs/BussIK/Node.h
../../examples/ThirdPartyLibs/BussIK/Tree.h
../../examples/ThirdPartyLibs/BussIK/VectorRn.h
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.h
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.h
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.h
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.h
../../examples/Importers/ImportURDFDemo/URDF2Bullet.h
../../examples/Importers/ImportURDFDemo/UrdfParser.h
../../examples/Importers/ImportURDFDemo/urdfStringSplit.h
../../examples/Importers/ImportURDFDemo/URDFImporterInterface.h
../../examples/Importers/ImportURDFDemo/URDFJointTypes.h
../../examples/Importers/ImportURDFDemo/SDFAudioTypes.h
../../examples/Importers/ImportURDFDemo/UrdfRenderingInterface.h
../../examples/Importers/ImportURDFDemo/MultiBodyCreationInterface.h
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h
../../examples/MultiThreading/b3PosixThreadSupport.h
../../examples/MultiThreading/b3Win32ThreadSupport.h
../../examples/MultiThreading/b3ThreadSupportInterface.h
)
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
../../examples/SharedMemory/RemoteGUIHelper.cpp
../../examples/SharedMemory/GraphicsServerExample.h
../../examples/SharedMemory/GraphicsClientExample.h
../../examples/SharedMemory/RemoteGUIHelper.h
../../examples/SharedMemory/GraphicsSharedMemoryCommands.h
../../examples/SharedMemory/GraphicsSharedMemoryPublic.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
ENDIF(BUILD_CLSOCKET)
IF(WIN32)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DWIN32)
ENDIF(BUILD_CLSOCKET)
ELSE(WIN32)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_CLSOCKET)
IF(NOT APPLE)
LINK_LIBRARIES( pthread ${DL} )
ENDIF(NOT APPLE)
ENDIF(WIN32)
IF(BUILD_ENET)
set(BulletRoboticsGUI_ENET_INCLUDES
../../examples/SharedMemory/PhysicsClientUDP.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/ThirdPartyLibs/enet/include/enet/win32.h
../../examples/ThirdPartyLibs/enet/include/enet/unix.h
../../examples/ThirdPartyLibs/enet/include/enet/callbacks.h
../../examples/ThirdPartyLibs/enet/include/enet/list.h
../../examples/ThirdPartyLibs/enet/include/enet/protocol.h
)
set(BulletRoboticsGUI_INCLUDES
${BulletRoboticsGUI_INCLUDES}
${BulletRoboticsGUI_ENET_INCLUDES}
)
ENDIF(BUILD_ENET)
ADD_DEFINITIONS(-DPHYSICS_SERVER_DIRECT)
ADD_LIBRARY(BulletRoboticsGUI ${BulletRoboticsGUI_SRCS})
SET_TARGET_PROPERTIES(BulletRoboticsGUI PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(BulletRoboticsGUI PROPERTIES SOVERSION ${BULLET_VERSION})
IF (BUILD_SHARED_LIBS)
TARGET_LINK_LIBRARIES(BulletRoboticsGUI BulletExampleBrowserLib BulletRobotics BulletInverseDynamicsUtils BulletWorldImporter BulletFileLoader BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamics LinearMath Bullet3Common)
ENDIF (BUILD_SHARED_LIBS)
INSTALL(TARGETS
BulletRoboticsGUI
LIBRARY DESTINATION lib${LIB_SUFFIX}
ARCHIVE DESTINATION lib${LIB_SUFFIX}
)
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES FRAMEWORK true)
SET_TARGET_PROPERTIES(BulletRobotics PROPERTIES PUBLIC_HEADER "PhysicsClientC_API.h" )
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
IF(NOT MSVC)
CONFIGURE_FILE(${CMAKE_CURRENT_SOURCE_DIR}/bullet_robotics_gui.pc.cmake
${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics_gui.pc @ONLY)
INSTALL(
FILES
${CMAKE_CURRENT_BINARY_DIR}/bullet_robotics_gui.pc
DESTINATION
${PKGCONFIG_INSTALL_PREFIX}
)
ENDIF(NOT MSVC)

View File

@ -0,0 +1,6 @@
Name: bullet_robotics_gui
Description: Bullet GUI extras for robotics
Requires: bullet
Version: @BULLET_VERSION@
Libs: -L@CMAKE_INSTALL_PREFIX@/@LIB_DESTINATION@ -lBulletRoboticsGUI
Cflags: @BULLET_DOUBLE_DEF@ -I@CMAKE_INSTALL_PREFIX@/@INCLUDE_INSTALL_DIR@ -I@CMAKE_INSTALL_PREFIX@/include/bullet_robotics_gui

View File

@ -1,4 +1,4 @@
SUBDIRS( InverseDynamics BulletRobotics obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils )
SUBDIRS( InverseDynamics BulletRoboticsGUI BulletRobotics obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils )

View File

@ -114,6 +114,8 @@ struct GUIHelperInterface
virtual void removeUserDebugItem(int debugItemUniqueId){};
virtual void removeAllUserDebugItems(){};
virtual void removeAllUserParameters() {};
virtual void setVisualizerFlagCallback(VisualizerFlagCallback callback) {}
//empty name stops dumping video

View File

@ -141,6 +141,7 @@ void CollisionShape2TriangleMesh(btCollisionShape* collisionShape, const btTrans
if (pol)
{
int baseIndex = vertexPositions.size();
for (int v = 0; v < pol->m_vertices.size(); v++)
{
vertexPositions.push_back(pol->m_vertices[v]);
@ -152,9 +153,9 @@ void CollisionShape2TriangleMesh(btCollisionShape* collisionShape, const btTrans
{
for (int ii = 2; ii < pol->m_faces[f].m_indices.size(); ii++)
{
indicesOut.push_back(pol->m_faces[f].m_indices[0]);
indicesOut.push_back(pol->m_faces[f].m_indices[ii - 1]);
indicesOut.push_back(pol->m_faces[f].m_indices[ii]);
indicesOut.push_back(baseIndex+pol->m_faces[f].m_indices[0]);
indicesOut.push_back(baseIndex + pol->m_faces[f].m_indices[ii - 1]);
indicesOut.push_back(baseIndex + pol->m_faces[f].m_indices[ii]);
}
}
}

View File

@ -1390,6 +1390,18 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClie
return 0;
}
B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_MESH_DATA);
if (command->m_type == CMD_REQUEST_MESH_DATA)
{
command->m_updateFlags = B3_MESH_DATA_COLLISIONSHAPEINDEX;
command->m_requestMeshDataArgs.m_collisionShapeIndex = shapeIndex;
}
}
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
@ -4059,6 +4071,20 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3Physics
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserRemoveAllParameters(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_USER_DEBUG_DRAW;
command->m_updateFlags = USER_DEBUG_REMOVE_ALL_PARAMETERS;
command->m_userDebugDrawArgs.m_parentObjectUniqueId = -1;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;

View File

@ -236,6 +236,7 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserRemoveAllParameters(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, const double objectColorRGB[/*3*/]);
@ -509,6 +510,8 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRemoveCollisionShapeCommand(b3PhysicsClientHandle physClient, int collisionShapeId);
B3_SHARED_API b3SharedMemoryCommandHandle b3GetMeshDataCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex);
B3_SHARED_API void b3GetMeshDataSetCollisionShapeIndex(b3SharedMemoryCommandHandle commandHandle, int shapeIndex);
B3_SHARED_API void b3GetMeshData(b3PhysicsClientHandle physClient, struct b3MeshData* meshData);

View File

@ -5029,8 +5029,13 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
convexHull->addPoint(pt * meshScale, false);
}
if (clientCmd.m_createUserShapeArgs.m_shapes[i].m_collisionFlags & GEOM_INITIALIZE_SAT_FEATURES)
{
convexHull->initializePolyhedralFeatures();
}
convexHull->recalcLocalAabb();
convexHull->optimizeConvexHull();
compound->addChildShape(childTransform, convexHull);
}
}
@ -5163,6 +5168,40 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
return hasStatus;
}
static void gatherVertices(const btTransform& trans, const btCollisionShape* colShape, btAlignedObjectArray<btVector3>& verticesOut, int collisionShapeIndex)
{
switch (colShape->getShapeType())
{
case COMPOUND_SHAPE_PROXYTYPE:
{
const btCompoundShape* compound = (const btCompoundShape*)colShape;
for (int i = 0; i < compound->getNumChildShapes(); i++)
{
btTransform childTr = trans * compound->getChildTransform(i);
if ((collisionShapeIndex < 0) || (collisionShapeIndex == i))
{
gatherVertices(childTr, compound->getChildShape(i), verticesOut, collisionShapeIndex);
}
}
break;
}
case CONVEX_HULL_SHAPE_PROXYTYPE:
{
const btConvexHullShape* convex = (const btConvexHullShape*)colShape;
btVector3 vtx;
for (int i = 0; i < convex->getNumVertices(); i++)
{
convex->getVertex(i, vtx);
btVector3 trVertex = trans * vtx;
verticesOut.push_back(trVertex);
}
break;
}
default:
{
}
}
}
bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
@ -5173,38 +5212,79 @@ bool PhysicsServerCommandProcessor::processRequestMeshDataCommand(const struct S
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_requestMeshDataArgs.m_bodyUniqueId);
if (bodyHandle)
{
int totalBytesPerVertex = sizeof(btVector3);
btVector3* verticesOut = (btVector3*)bufferServerToClient;
const btCollisionShape* colShape = 0;
if (bodyHandle->m_multiBody)
{
//todo
//collision shape
if (clientCmd.m_requestMeshDataArgs.m_linkIndex == -1)
{
colShape = bodyHandle->m_multiBody->getBaseCollider()->getCollisionShape();
}
else
{
colShape = bodyHandle->m_multiBody->getLinkCollider(clientCmd.m_requestMeshDataArgs.m_linkIndex)->getCollisionShape();
}
}
if (bodyHandle->m_rigidBody)
{
//todo
colShape = bodyHandle->m_rigidBody->getCollisionShape();
}
if (colShape)
{
btAlignedObjectArray<btVector3> vertices;
btTransform tr;
tr.setIdentity();
int collisionShapeIndex = -1;
if (clientCmd.m_updateFlags& B3_MESH_DATA_COLLISIONSHAPEINDEX)
{
collisionShapeIndex = clientCmd.m_requestMeshDataArgs.m_collisionShapeIndex;
}
gatherVertices(tr, colShape, vertices, collisionShapeIndex);
int numVertices = vertices.size();
int maxNumVertices = bufferSizeInBytes / totalBytesPerVertex - 1;
int numVerticesRemaining = numVertices - clientCmd.m_requestMeshDataArgs.m_startingVertex;
int verticesCopied = btMin(maxNumVertices, numVerticesRemaining);
for (int i = 0; i < verticesCopied; ++i)
{
verticesOut[i] = vertices[i];
}
serverStatusOut.m_type = CMD_REQUEST_MESH_DATA_COMPLETED;
serverStatusOut.m_sendMeshDataArgs.m_numVerticesCopied = verticesCopied;
serverStatusOut.m_sendMeshDataArgs.m_startingVertex = clientCmd.m_requestMeshDataArgs.m_startingVertex;
serverStatusOut.m_sendMeshDataArgs.m_numVerticesRemaining = numVerticesRemaining - verticesCopied;
}
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
if (bodyHandle->m_softBody)
{
btSoftBody* psb = bodyHandle->m_softBody;
int totalBytesPerVertex = sizeof(btVector3);
bool separateRenderMesh = (psb->m_renderNodes.size() != 0);
int numVertices = separateRenderMesh ? psb->m_renderNodes.size() : psb->m_nodes.size();
bool separateRenderMesh = (psb->m_renderNodes.size() != 0);
int numVertices = separateRenderMesh ? psb->m_renderNodes.size() : psb->m_nodes.size();
int maxNumVertices = bufferSizeInBytes / totalBytesPerVertex - 1;
int numVerticesRemaining = numVertices - clientCmd.m_requestMeshDataArgs.m_startingVertex;
int verticesCopied = btMin(maxNumVertices, numVerticesRemaining);
btVector3* verticesOut = (btVector3*)bufferServerToClient;
for (int i = 0; i < verticesCopied; ++i)
{
if (separateRenderMesh)
{
const btSoftBody::Node& n = psb->m_renderNodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
}
else
{
const btSoftBody::Node& n = psb->m_nodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
}
if (separateRenderMesh)
{
const btSoftBody::Node& n = psb->m_renderNodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
}
else
{
const btSoftBody::Node& n = psb->m_nodes[i + clientCmd.m_requestMeshDataArgs.m_startingVertex];
verticesOut[i] = n.m_x;
}
}
serverStatusOut.m_type = CMD_REQUEST_MESH_DATA_COMPLETED;
@ -5644,6 +5724,14 @@ bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct Sha
m_data->m_guiHelper->removeAllUserDebugItems();
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_ALL_PARAMETERS)
{
m_data->m_guiHelper->removeAllUserParameters();
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_ONE_ITEM)
{
m_data->m_guiHelper->removeUserDebugItem(clientCmd.m_userDebugDrawArgs.m_itemUniqueId);
@ -12209,6 +12297,8 @@ bool PhysicsServerCommandProcessor::processRequestCollisionShapeInfoCommand(cons
if (bodyHandle->m_multiBody)
{
b3CollisionShapeData* collisionShapeStoragePtr = (b3CollisionShapeData*)bufferServerToClient;
collisionShapeStoragePtr->m_objectUniqueId = bodyUniqueId;
collisionShapeStoragePtr->m_linkIndex = linkIndex;
int totalBytesPerObject = sizeof(b3CollisionShapeData);
int maxNumColObjects = bufferSizeInBytes / totalBytesPerObject - 1;
btTransform childTrans;

View File

@ -128,6 +128,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperRemoveTexture,
eGUIHelperSetVisualizerFlagCheckRenderedFrame,
eGUIHelperUpdateShape,
eGUIUserDebugRemoveAllParameters,
};
#include <stdio.h>
@ -494,6 +495,13 @@ struct UserDebugParameter
int m_itemUniqueId;
};
static void UserButtonToggle(int buttonId, bool buttonState, void* userPointer)
{
UserDebugParameter* param = (UserDebugParameter*)userPointer;
param->m_value += 1;
}
struct UserDebugText
{
char m_text[1024];
@ -1328,6 +1336,16 @@ public:
workerThreadWait();
}
virtual void removeAllUserParameters()
{
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugRemoveAllParameters);
workerThreadWait();
}
const char* m_mp4FileName;
virtual void dumpFramesToVideo(const char* mp4FileName)
{
@ -2359,6 +2377,7 @@ void PhysicsServerExample::updateGraphics()
UserDebugParameter* param = new UserDebugParameter(m_multiThreadedHelper->m_tmpParam);
m_multiThreadedHelper->m_userDebugParams.push_back(param);
if (param->m_rangeMin<= param->m_rangeMax)
{
SliderParams slider(param->m_text, &param->m_value);
slider.m_minVal = param->m_rangeMin;
@ -2367,6 +2386,19 @@ void PhysicsServerExample::updateGraphics()
if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
}
else
{
int buttonId = -1;
bool isTrigger = false;
ButtonParams button(param->m_text, buttonId, isTrigger);
button.m_callback = UserButtonToggle;
button.m_userPointer = param;
button.m_initialState = false;
//create a button
if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerButtonParameter(button);
}
m_multiThreadedHelper->m_userDebugParamUid = (*m_multiThreadedHelper->m_userDebugParams[m_multiThreadedHelper->m_userDebugParams.size() - 1]).m_itemUniqueId;
@ -2424,10 +2456,23 @@ void PhysicsServerExample::updateGraphics()
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIUserDebugRemoveAllParameters:
{
B3_PROFILE("eGUIUserDebugRemoveAllParameters");
if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->removeAllParameters();
for (int i = 0; i < m_multiThreadedHelper->m_userDebugParams.size(); i++)
{
delete m_multiThreadedHelper->m_userDebugParams[i];
}
m_multiThreadedHelper->m_userDebugParams.clear();
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIUserDebugRemoveAllItems:
{
B3_PROFILE("eGUIUserDebugRemoveAllItems");
m_multiThreadedHelper->m_userDebugLines.clear();
m_multiThreadedHelper->m_userDebugText.clear();
m_multiThreadedHelper->m_uidGenerator = 0;

View File

@ -811,6 +811,7 @@ enum EnumUserDebugDrawFlags
USER_DEBUG_HAS_TEXT_ORIENTATION = 512,
USER_DEBUG_HAS_PARENT_OBJECT = 1024,
USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID = 2048,
USER_DEBUG_REMOVE_ALL_PARAMETERS = 4096,
};
struct UserDebugDrawArgs
@ -1096,6 +1097,7 @@ struct b3RequestMeshDataArgs
int m_bodyUniqueId;
int m_linkIndex;
int m_startingVertex;
int m_collisionShapeIndex;
};
struct b3SendMeshDataArgs

View File

@ -449,6 +449,12 @@ struct b3MeshVertex
double x, y, z, w;
};
enum eMeshDataEnum
{
B3_MESH_DATA_COLLISIONSHAPEINDEX=1,
};
struct b3MeshData
{
int m_numVertices;
@ -940,6 +946,7 @@ enum eUrdfCollisionFlags
{
GEOM_FORCE_CONCAVE_TRIMESH = 1,
GEOM_CONCAVE_INTERNAL_EDGE = 2,
GEOM_INITIALIZE_SAT_FEATURES = URDF_INITIALIZE_SAT_FEATURES,
};
enum eUrdfVisualFlags

View File

@ -15,159 +15,41 @@ ENDIF()
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
SET(pybullet3_SRCS
pybullet.c
)
SET(pybullet_SRCS
pybullet.c
../../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/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../SharedMemory/GraphicsServerExample.cpp
../SharedMemory/GraphicsClientExample.cpp
../SharedMemory/RemoteGUIHelper.cpp
../SharedMemory/GraphicsServerExample.h
../SharedMemory/GraphicsClientExample.h
../SharedMemory/RemoteGUIHelper.h
../SharedMemory/GraphicsSharedMemoryCommands.h
../SharedMemory/GraphicsSharedMemoryPublic.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/b3PluginManager.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/RobotLoggingUtil.h
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image_write.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(BUILD_PYBULLET_CLSOCKET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
ENDIF(BUILD_PYBULLET_CLSOCKET)
ENDIF()
IF(WIN32)
LINK_LIBRARIES(
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
)
IF(BUILD_PYBULLET_ENET)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
ENDIF()
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DWIN32)
ENDIF(BUILD_PYBULLET_CLSOCKET)
ENDIF()
ELSE(WIN32)
IF(BUILD_PYBULLET_ENET)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
ENDIF(BUILD_PYBULLET_ENET)
ENDIF()
IF(BUILD_PYBULLET_CLSOCKET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_PYBULLET_CLSOCKET)
ENDIF()
ENDIF(WIN32)
IF(BUILD_PYBULLET_ENET)
set(pybullet_SRCS ${pybullet_SRCS}
../../examples/SharedMemory/PhysicsClientUDP.cpp
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
../../examples/SharedMemory/PhysicsClientUDP.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/ThirdPartyLibs/enet/win32.c
../../examples/ThirdPartyLibs/enet/unix.c
../../examples/ThirdPartyLibs/enet/callbacks.c
../../examples/ThirdPartyLibs/enet/compress.c
../../examples/ThirdPartyLibs/enet/host.c
../../examples/ThirdPartyLibs/enet/list.c
../../examples/ThirdPartyLibs/enet/packet.c
../../examples/ThirdPartyLibs/enet/peer.c
../../examples/ThirdPartyLibs/enet/protocol.c
)
ENDIF(BUILD_PYBULLET_ENET)
IF(BUILD_PYBULLET_CLSOCKET)
set(pybullet_SRCS ${pybullet_SRCS}
../../examples/SharedMemory/PhysicsClientTCP.cpp
../../examples/SharedMemory/PhysicsClientTCP.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
)
ENDIF()
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
@ -180,9 +62,9 @@ SET_TARGET_PROPERTIES(pybullet PROPERTIES DEBUG_POSTFIX "_d")
IF(WIN32)
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
IF(BUILD_ENET OR BUILD_CLSOCKET)
TARGET_LINK_LIBRARIES(pybullet ws2_32 )
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
ENDIF()
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd" )
ENDIF(WIN32)
@ -193,7 +75,7 @@ ENDIF()
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common)
TARGET_LINK_LIBRARIES(pybullet BulletRoboticsGUI BulletExampleBrowserLib BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common)
IF (WIN32)
TARGET_LINK_LIBRARIES(pybullet ${PYTHON_LIBRARIES})

View File

@ -6096,7 +6096,7 @@ static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args
int physicsClientId = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
{
return NULL;
}
@ -6117,6 +6117,36 @@ static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args
return Py_None;
}
static PyObject* pybullet_removeAllUserParameters(PyObject* self, PyObject* args, PyObject* keywds)
{
b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
int physicsClientId = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
commandHandle = b3InitUserRemoveAllParameters(sm);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
Py_INCREF(Py_None);
return Py_None;
}
static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyObject* keywds)
{
b3SharedMemoryStatusHandle statusHandle;
@ -8590,6 +8620,7 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject*
{
int bodyUniqueId = -1;
int linkIndex = -1;
int collisionShapeIndex = -1;
b3PhysicsClientHandle sm = 0;
b3SharedMemoryCommandHandle command;
b3SharedMemoryStatusHandle statusHandle;
@ -8597,8 +8628,8 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject*
int statusType;
int physicsClientId = 0;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|ii", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId))
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "collisionShapeIndex", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|iii", kwlist, &bodyUniqueId, &linkIndex,&collisionShapeIndex, &physicsClientId))
{
return NULL;
}
@ -8609,6 +8640,10 @@ static PyObject* pybullet_getMeshData(PyObject* self, PyObject* args, PyObject*
return NULL;
}
command = b3GetMeshDataCommandInit(sm, bodyUniqueId, linkIndex);
if (collisionShapeIndex >= 0)
{
b3GetMeshDataSetCollisionShapeIndex(command, collisionShapeIndex);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_REQUEST_MESH_DATA_COMPLETED)
@ -12270,6 +12305,9 @@ static PyMethodDef SpamMethods[] = {
{"removeAllUserDebugItems", (PyCFunction)pybullet_removeAllUserDebugItems, METH_VARARGS | METH_KEYWORDS,
"remove all user debug draw items"},
{ "removeAllUserParameters", (PyCFunction)pybullet_removeAllUserParameters, METH_VARARGS | METH_KEYWORDS,
"remove all user debug parameters (sliders, buttons)" },
{"setDebugObjectColor", (PyCFunction)pybullet_setDebugObjectColor, METH_VARARGS | METH_KEYWORDS,
"Override the wireframe debug drawing color for a particular object unique id / link index."
"If you ommit the color, the custom color will be removed."},

View File

@ -499,7 +499,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup(
name='pybullet',
version='2.6.7',
version='2.6.8',
description=
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description=