This commit is contained in:
Erwin Coumans
2017-09-24 22:50:37 -07:00
43 changed files with 1925 additions and 725 deletions

View File

@@ -2,17 +2,21 @@ Bullet Physics is created by Erwin Coumans with contributions from the following
AMD
Apple
Yunfei Bai
Steve Baker
Gino van den Bergen
Jeff Bingham
Nicola Candussi
Erin Catto
Lawrence Chai
Erwin Coumans
Christer Ericson
Disney Animation
Benjamin Ellenberger
Christer Ericson
Google
Dirk Gregorius
Marcus Hennix
Jasmine Hsu
MBSim Development Team
Takahiro Harada
Simon Hobbs
@@ -20,6 +24,7 @@ John Hsu
Ole Kniemeyer
Jay Lee
Francisco Leon
lunkhound
Vsevolod Klementjev
Phil Knight
John McCutchan
@@ -32,9 +37,9 @@ Russel Smith
Sony
Jakub Stephien
Marten Svanfeldt
Jie Tan
Pierre Terdiman
Steven Thompson
Tamas Umenhoffer
Yunfei Bai
If your name is missing, please send an email to erwin.coumans@gmail.com or file an issue at http://github.com/bulletphysics/bullet3

View File

@@ -449,7 +449,11 @@ configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/BulletConfig.cmake.in
${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake
@ONLY ESCAPE_QUOTES
)
install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/UseBullet.cmake
OPTION(INSTALL_CMAKE_FILES "Install generated CMake files" ON)
IF (INSTALL_CMAKE_FILES)
install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/UseBullet.cmake
${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake
DESTINATION ${BULLET_CONFIG_CMAKE_PATH}
)
ENDIF (INSTALL_CMAKE_FILES)

View File

@@ -32,6 +32,9 @@ SET(BulletRobotics_SRCS
../../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

View File

@@ -171,6 +171,7 @@ SET(BulletExampleBrowser_SRCS
../SharedMemory/PhysicsServerCommandProcessor.h
../SharedMemory/SharedMemoryCommands.h
../SharedMemory/SharedMemoryPublic.h
../SharedMemory/b3PluginManager.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.h
../BasicDemo/BasicExample.cpp

View File

@@ -109,6 +109,7 @@ project "App_BulletExampleBrowser"
"../SharedMemory/PhysicsLoopBackC_API.h",
"../SharedMemory/PhysicsServerCommandProcessor.cpp",
"../SharedMemory/PhysicsServerCommandProcessor.h",
"../SharedMemory/b3PluginManager.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.h",
"../SharedMemory/SharedMemoryCommands.h",

View File

@@ -42,6 +42,8 @@ SET(RobotSimulator_SRCS
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp

View File

@@ -988,7 +988,8 @@ bool b3RobotSimulatorClientAPI::getBodyJacobian(int bodyUniqueId, int linkIndex,
if (b3GetStatusType(statusHandle) == CMD_CALCULATED_JACOBIAN_COMPLETED)
{
b3GetStatusJacobian(statusHandle, linearJacobian, angularJacobian);
int dofCount;
b3GetStatusJacobian(statusHandle, &dofCount, linearJacobian, angularJacobian);
return true;
}
return false;

View File

@@ -20,6 +20,8 @@ myfiles =
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp",

View File

@@ -1,5 +1,4 @@
SET(SharedMemory_SRCS
IKTrajectoryHelper.cpp
IKTrajectoryHelper.h
@@ -41,6 +40,7 @@ SET(SharedMemory_SRCS
TinyRendererVisualShapeConverter.h
SharedMemoryCommands.h
SharedMemoryPublic.h
b3PluginManager.cpp
../TinyRenderer/geometry.cpp
../TinyRenderer/model.cpp
../TinyRenderer/tgaimage.cpp

View File

@@ -1631,6 +1631,7 @@ B3_SHARED_API int b3SubmitClientCommand(b3PhysicsClientHandle physClient, const
#include "../Utils/b3Clock.h"
B3_SHARED_API b3SharedMemoryStatusHandle b3SubmitClientCommandAndWaitStatus(b3PhysicsClientHandle physClient, const b3SharedMemoryCommandHandle commandHandle)
{
B3_PROFILE("b3SubmitClientCommandAndWaitStatus");
@@ -1733,6 +1734,137 @@ B3_SHARED_API int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex
return cl->getJointInfo(bodyIndex, jointIndex, *info);
}
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_CUSTOM_COMMAND;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
if (command->m_type == CMD_CUSTOM_COMMAND)
{
command->m_updateFlags |= CMD_CUSTOM_COMMAND_LOAD_PLUGIN;
command->m_customCommandArgs.m_pluginPath[0] = 0;
int len = strlen(pluginPath);
if (len<MAX_FILENAME_LENGTH)
{
strcpy(command->m_customCommandArgs.m_pluginPath, pluginPath);
}
}
}
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle)
{
int statusUniqueId = -1;
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_CUSTOM_COMMAND_COMPLETED);
if (status->m_type == CMD_CUSTOM_COMMAND_COMPLETED)
{
statusUniqueId = status->m_customCommandResultArgs.m_executeCommandResult;
}
return statusUniqueId;
}
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
int statusUniqueId = -1;
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_CUSTOM_COMMAND_COMPLETED);
if (status->m_type == CMD_CUSTOM_COMMAND_COMPLETED)
{
statusUniqueId = status->m_customCommandResultArgs.m_pluginUniqueId;
}
return statusUniqueId;
}
B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
if (command->m_type == CMD_CUSTOM_COMMAND)
{
command->m_updateFlags |= CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN;
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
}
}
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, const char* textArguments)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
if (command->m_type == CMD_CUSTOM_COMMAND)
{
command->m_updateFlags |= CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND;
command->m_customCommandArgs.m_pluginUniqueId = pluginUniqueId;
command->m_customCommandArgs.m_arguments.m_numInts = 0;
command->m_customCommandArgs.m_arguments.m_numFloats = 0;
command->m_customCommandArgs.m_arguments.m_text[0] = 0;
int len = strlen(textArguments);
if (len<MAX_FILENAME_LENGTH)
{
strcpy(command->m_customCommandArgs.m_arguments.m_text, textArguments);
}
}
}
B3_SHARED_API void b3CustomCommandExecuteAddIntArgument(b3SharedMemoryCommandHandle commandHandle, int intVal)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
b3Assert(command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND);
if (command->m_type == CMD_CUSTOM_COMMAND && (command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND))
{
int numInts = command->m_customCommandArgs.m_arguments.m_numInts;
if (numInts<B3_MAX_PLUGIN_ARG_SIZE)
{
command->m_customCommandArgs.m_arguments.m_ints[numInts]=intVal;
command->m_customCommandArgs.m_arguments.m_numInts++;
}
}
}
B3_SHARED_API void b3CustomCommandExecuteAddFloatArgument(b3SharedMemoryCommandHandle commandHandle, float floatVal)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_CUSTOM_COMMAND);
b3Assert(command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND);
if (command->m_type == CMD_CUSTOM_COMMAND && (command->m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND))
{
int numFloats = command->m_customCommandArgs.m_arguments.m_numFloats;
if (numFloats<B3_MAX_PLUGIN_ARG_SIZE)
{
command->m_customCommandArgs.m_arguments.m_floats[numFloats]=floatVal;
command->m_customCommandArgs.m_arguments.m_numFloats++;
}
}
}
B3_SHARED_API b3SharedMemoryCommandHandle b3GetDynamicsInfoCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int linkIndex)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
@@ -3178,13 +3310,17 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3Physi
}
B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian)
B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, int* dofCount, double* linearJacobian, double* angularJacobian)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
btAssert(status->m_type == CMD_CALCULATED_JACOBIAN_COMPLETED);
if (status->m_type != CMD_CALCULATED_JACOBIAN_COMPLETED)
return false;
if (dofCount)
{
*dofCount = status->m_jacobianResultArgs.m_dofCount;
}
if (linearJacobian)
{
for (int i = 0; i < status->m_jacobianResultArgs.m_dofCount*3; i++)

View File

@@ -60,6 +60,18 @@ B3_SHARED_API b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHa
/// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes.
B3_SHARED_API int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle);
///Plugin system, load and unload a plugin, execute a command
B3_SHARED_API b3SharedMemoryCommandHandle b3CreateCustomCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API void b3CustomCommandLoadPlugin(b3SharedMemoryCommandHandle commandHandle, const char* pluginPath);
B3_SHARED_API int b3GetStatusPluginUniqueId(b3SharedMemoryStatusHandle statusHandle);
B3_SHARED_API int b3GetStatusPluginCommandResult(b3SharedMemoryStatusHandle statusHandle);
B3_SHARED_API void b3CustomCommandUnloadPlugin(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId);
B3_SHARED_API void b3CustomCommandExecutePluginCommand(b3SharedMemoryCommandHandle commandHandle, int pluginUniqueId, const char* textArguments);
B3_SHARED_API void b3CustomCommandExecuteAddIntArgument(b3SharedMemoryCommandHandle commandHandle, int intVal);
B3_SHARED_API void b3CustomCommandExecuteAddFloatArgument(b3SharedMemoryCommandHandle commandHandle, float floatVal);
B3_SHARED_API int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity);
B3_SHARED_API int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle);
@@ -304,7 +316,10 @@ B3_SHARED_API int b3GetStatusInverseDynamicsJointForces(b3SharedMemoryStatusHand
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, const double* localPosition, const double* jointPositionsQ, const double* jointVelocitiesQdot, const double* jointAccelerations);
B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian);
B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle,
int* dofCount,
double* linearJacobian,
double* angularJacobian);
///compute the joint positions to move the end effector to a desired target using inverse kinematics
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateInverseKinematicsCommandInit(b3PhysicsClientHandle physClient, int bodyIndex);

View File

@@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData {
m_hasLastServerStatus(false),
m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_verboseOutput(false),
m_timeOutInSeconds(5)
m_timeOutInSeconds(30)
{}
void processServerStatus();
@@ -1200,6 +1200,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
b3Warning("Request getCollisionInfo failed");
break;
}
case CMD_CUSTOM_COMMAND_COMPLETED:
{
break;
}
case CMD_CUSTOM_COMMAND_FAILED:
{
b3Warning("custom plugin command failed");
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);

View File

@@ -940,6 +940,16 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
break;
}
case CMD_CUSTOM_COMMAND_COMPLETED:
{
break;
}
case CMD_CUSTOM_COMMAND_FAILED:
{
b3Warning("custom plugin command failed");
break;
}
default:
{
//b3Warning("Unknown server status type");

View File

@@ -1,5 +1,6 @@
#include "PhysicsServerCommandProcessor.h"
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
@@ -37,6 +38,8 @@
#include "LinearMath/btRandom.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "../Utils/b3Clock.h"
#include "b3PluginManager.h"
#ifdef B3_ENABLE_TINY_AUDIO
#include "../TinyAudio/b3SoundEngine.h"
#endif
@@ -1053,13 +1056,13 @@ struct GenericRobotStateLogger : public InternalStateLogger
std::string m_fileName;
FILE* m_logFileHandle;
std::string m_structTypes;
btMultiBodyDynamicsWorld* m_dynamicsWorld;
const btMultiBodyDynamicsWorld* m_dynamicsWorld;
btAlignedObjectArray<int> m_bodyIdList;
bool m_filterObjectUniqueId;
int m_maxLogDof;
int m_logFlags;
GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, btMultiBodyDynamicsWorld* dynamicsWorld, int maxLogDof, int logFlags)
GenericRobotStateLogger(int loggingUniqueId, const std::string& fileName, const btMultiBodyDynamicsWorld* dynamicsWorld, int maxLogDof, int logFlags)
:m_loggingTimeStamp(0),
m_logFileHandle(0),
m_dynamicsWorld(dynamicsWorld),
@@ -1137,7 +1140,7 @@ struct GenericRobotStateLogger : public InternalStateLogger
{
for (int i=0;i<m_dynamicsWorld->getNumMultibodies();i++)
{
btMultiBody* mb = m_dynamicsWorld->getMultiBody(i);
const btMultiBody* mb = m_dynamicsWorld->getMultiBody(i);
int objectUniqueId = mb->getUserIndex2();
if (m_filterObjectUniqueId && m_bodyIdList.findLinearSearch2(objectUniqueId) < 0)
{
@@ -1430,6 +1433,8 @@ struct PhysicsServerCommandProcessorInternalData
b3ResizablePool< InternalBodyHandle > m_bodyHandles;
b3ResizablePool<InternalCollisionShapeHandle> m_userCollisionShapeHandles;
b3PluginManager m_pluginManager;
bool m_allowRealTimeSimulation;
@@ -1484,7 +1489,7 @@ struct PhysicsServerCommandProcessorInternalData
btAlignedObjectArray<int> m_sdfRecentLoadedBodies;
btAlignedObjectArray<InternalStateLogger*> m_stateLoggers;
int m_stateLoggersUniqueId;
int m_profileTimingLoggingUid;
@@ -1512,8 +1517,8 @@ struct PhysicsServerCommandProcessorInternalData
b3HashMap<b3HashString, char*> m_profileEvents;
PhysicsServerCommandProcessorInternalData()
:
PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc)
:m_pluginManager(proc),
m_allowRealTimeSimulation(false),
m_commandLogger(0),
m_logPlayback(0),
@@ -1537,6 +1542,16 @@ struct PhysicsServerCommandProcessorInternalData
m_pickedConstraint(0),
m_pickingMultiBodyPoint2Point(0)
{
{
//test to statically link a plugin
//#include "plugins/testPlugin/testplugin.h"
//register static plugins:
//m_pluginManager.registerStaticLinkedPlugin("path", initPlugin, exitPlugin, executePluginCommand);
}
m_vrControllerEvents.init();
m_bodyHandles.exitHandles();
@@ -1643,8 +1658,9 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH
PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
:m_data(0)
{
m_data = new PhysicsServerCommandProcessorInternalData();
m_data = new PhysicsServerCommandProcessorInternalData(this);
createEmptyDynamicsWorld();
@@ -1666,13 +1682,23 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
delete m_data;
}
void preTickCallback(btDynamicsWorld *world, btScalar timeStep)
{
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
bool isPreTick = true;
proc->tickPlugins(timeStep, isPreTick);
}
void logCallback(btDynamicsWorld *world, btScalar timeStep)
{
//handle the logging and playing sounds
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
proc->processCollisionForces(timeStep);
proc->logObjectStates(timeStep);
bool isPreTick = false;
proc->tickPlugins(timeStep, isPreTick);
}
@@ -1781,6 +1807,12 @@ void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep)
#endif//B3_ENABLE_TINY_AUDIO
}
void PhysicsServerCommandProcessor::tickPlugins(btScalar timeStep, bool isPreTick)
{
m_data->m_pluginManager.tickPlugins(timeStep, isPreTick);
}
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
{
for (int i=0;i<m_data->m_stateLoggers.size();i++)
@@ -2144,7 +2176,11 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
{
m_data->m_guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
}
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this);
bool isPreTick=false;
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this,isPreTick);
isPreTick = true;
m_data->m_dynamicsWorld->setInternalTickCallback(preTickCallback,this,isPreTick);
#ifdef B3_ENABLE_TINY_AUDIO
m_data->m_soundEngine.init(16,true);
@@ -2961,27 +2997,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
bool hasStatus = false;
{
///we ignore overflow of integer for now
{
//until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
//const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
#if 1
if (m_data->m_commandLogger)
{
m_data->m_commandLogger->logCommand(clientCmd);
}
#endif
//m_data->m_testBlock1->m_numProcessedClientCommands++;
//no timestamp yet
//int timeStamp = 0;
//catch uninitialized cases
serverStatusOut.m_type = CMD_INVALID_STATUS;
serverStatusOut.m_numDataStreamBytes = 0;
serverStatusOut.m_dataStream = 0;
@@ -2989,32 +3009,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
//consume the command
switch (clientCmd.m_type)
{
#if 0
case CMD_SEND_BULLET_DATA_STREAM:
{
if (m_data->m_verboseOutput)
{
b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
}
btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
m_data->m_worldImporters.push_back(worldImporter);
bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
if (completedOk)
{
SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
m_data->submitServerStatus(status);
} else
{
SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp);
m_data->submitServerStatus(status);
}
break;
}
#endif
case CMD_STATE_LOGGING:
{
BT_PROFILE("CMD_STATE_LOGGING");
@@ -6623,30 +6618,37 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
if (tree)
{
int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
const int num_dofs = bodyHandle->m_multiBody->getNumDofs();
btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs);
for (int i = 0; i < num_dofs; i++)
const int numDofs = bodyHandle->m_multiBody->getNumDofs();
btInverseDynamics::vecx q(numDofs + baseDofs);
btInverseDynamics::vecx qdot(numDofs + baseDofs);
btInverseDynamics::vecx nu(numDofs + baseDofs);
btInverseDynamics::vecx joint_force(numDofs + baseDofs);
for (int i = 0; i < numDofs; i++)
{
q[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointPositionsQ[i];
qdot[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointVelocitiesQdot[i];
nu[i+baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i];
nu[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i];
}
// Set the gravity to correspond to the world gravity
btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
if (-1 != tree->setGravityInWorldFrame(id_grav) &&
-1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
{
serverCmd.m_jacobianResultArgs.m_dofCount = num_dofs;
serverCmd.m_jacobianResultArgs.m_dofCount = numDofs + baseDofs;
// Set jacobian value
tree->calculateJacobians(q);
btInverseDynamics::mat3x jac_t(3, num_dofs);
tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex+1, &jac_t);
btInverseDynamics::mat3x jac_t(3, numDofs + baseDofs);
btInverseDynamics::mat3x jac_r(3, numDofs + baseDofs);
// Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link.
tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex + 1, &jac_t);
tree->getBodyJacobianRot(clientCmd.m_calculateJacobianArguments.m_linkIndex + 1, &jac_r);
for (int i = 0; i < 3; ++i)
{
for (int j = 0; j < num_dofs; ++j)
for (int j = 0; j < (numDofs + baseDofs); ++j)
{
serverCmd.m_jacobianResultArgs.m_linearJacobian[i*num_dofs+j] = jac_t(i,j);
int element = (numDofs + baseDofs) * i + j;
serverCmd.m_jacobianResultArgs.m_linearJacobian[element] = jac_t(i,j);
serverCmd.m_jacobianResultArgs.m_angularJacobian[element] = jac_r(i,j);
}
}
serverCmd.m_type = CMD_CALCULATED_JACOBIAN_COMPLETED;
@@ -7370,7 +7372,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
tree->calculateJacobians(q);
btInverseDynamics::mat3x jac_t(3, numDofs);
btInverseDynamics::mat3x jac_r(3,numDofs);
// Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link.
// Note that inverse dynamics uses zero-based indexing of bodies, not starting from -1 for the base link.
tree->getBodyJacobianTrans(endEffectorLinkIndex+1, &jac_t);
tree->getBodyJacobianRot(endEffectorLinkIndex+1, &jac_r);
for (int i = 0; i < 3; ++i)
@@ -7968,6 +7970,39 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_CUSTOM_COMMAND:
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_CUSTOM_COMMAND_FAILED;
serverCmd.m_customCommandResultArgs.m_pluginUniqueId = -1;
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_LOAD_PLUGIN)
{
//pluginPath could be registered or load from disk
int pluginUniqueId = m_data->m_pluginManager.loadPlugin(clientCmd.m_customCommandArgs.m_pluginPath);
if (pluginUniqueId>=0)
{
serverCmd.m_customCommandResultArgs.m_pluginUniqueId = pluginUniqueId;
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
}
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN)
{
m_data->m_pluginManager.unloadPlugin(clientCmd.m_customCommandArgs.m_pluginUniqueId);
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
if (clientCmd.m_updateFlags & CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND)
{
int result = m_data->m_pluginManager.executePluginCommand(clientCmd.m_customCommandArgs.m_pluginUniqueId, &clientCmd.m_customCommandArgs.m_arguments);
serverCmd.m_customCommandResultArgs.m_executeCommandResult = result;
serverCmd.m_type = CMD_CUSTOM_COMMAND_COMPLETED;
}
hasStatus = true;
break;
}
default:
{
BT_PROFILE("CMD_UNKNOWN");
@@ -8186,12 +8221,6 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
}
btVector3 gVRGripperPos(0.7, 0.3, 0.7);
btQuaternion gVRGripperOrn(0,0,0,1);
btVector3 gVRController2Pos(0,0,0.2);
btQuaternion gVRController2Orn(0,0,0,1);
btScalar gVRGripper2Analog = 0;
btScalar gVRGripperAnalog = 0;
@@ -8214,6 +8243,8 @@ bool PhysicsServerCommandProcessor::isRealTimeSimulationEnabled() const
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
{
m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
for (int i=0;i<m_data->m_stateLoggers.size();i++)
{
if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS)

View File

@@ -91,6 +91,7 @@ public:
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
//logging of object states (position etc)
void tickPlugins(btScalar timeStep, bool isPreTick);
void logObjectStates(btScalar timeStep);
void processCollisionForces(btScalar timeStep);

View File

@@ -109,6 +109,26 @@ struct b3SearchPathfArgs
char m_path[MAX_FILENAME_LENGTH];
};
enum CustomCommandEnum
{
CMD_CUSTOM_COMMAND_LOAD_PLUGIN=1,
CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN=2,
CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND=4,
};
struct b3CustomCommand
{
int m_pluginUniqueId;
b3PluginArguments m_arguments;
char m_pluginPath[MAX_FILENAME_LENGTH];
};
struct b3CustomCommandResultArgs
{
int m_pluginUniqueId;
int m_executeCommandResult;
};
struct BulletDataStreamArgs
{
@@ -968,6 +988,7 @@ struct SharedMemoryCommand
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
struct b3ChangeTextureArgs m_changeTextureArgs;
struct b3SearchPathfArgs m_searchPathArgs;
struct b3CustomCommand m_customCommandArgs;
};
};
@@ -1039,6 +1060,7 @@ struct SharedMemoryStatus
struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs;
struct SendMouseEvents m_sendMouseEvents;
struct b3LoadTextureResultArgs m_loadTextureResultArguments;
struct b3CustomCommandResultArgs m_customCommandResultArgs;
};
};

View File

@@ -72,6 +72,7 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_MOUSE_EVENTS_DATA,
CMD_CHANGE_TEXTURE,
CMD_SET_ADDITIONAL_SEARCH_PATH,
CMD_CUSTOM_COMMAND,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -167,6 +168,9 @@ enum EnumSharedMemoryServerStatus
CMD_REQUEST_COLLISION_INFO_FAILED,
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
CMD_CHANGE_TEXTURE_COMMAND_FAILED,
CMD_CUSTOM_COMMAND_COMPLETED,
CMD_CUSTOM_COMMAND_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -616,6 +620,19 @@ enum eStateLoggingFlags
STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES+STATE_LOG_JOINT_USER_TORQUES,
};
#define B3_MAX_PLUGIN_ARG_SIZE 128
#define B3_MAX_PLUGIN_ARG_TEXT_LEN 1024
struct b3PluginArguments
{
char m_text[B3_MAX_PLUGIN_ARG_TEXT_LEN];
int m_numInts;
int m_ints[B3_MAX_PLUGIN_ARG_SIZE];
int m_numFloats;
int m_floats[B3_MAX_PLUGIN_ARG_SIZE];
};
#endif//SHARED_MEMORY_PUBLIC_H

View File

@@ -0,0 +1,255 @@
#include "b3PluginManager.h"
#include "Bullet3Common/b3HashMap.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "SharedMemoryPublic.h"
#include "PhysicsDirect.h"
#include "plugins/b3PluginContext.h"
#ifdef _WIN32
#define WIN32_LEAN_AND_MEAN
#define VC_EXTRALEAN
#include <windows.h>
typedef HMODULE B3_DYNLIB_HANDLE;
#define B3_DYNLIB_OPEN LoadLibrary
#define B3_DYNLIB_CLOSE FreeLibrary
#define B3_DYNLIB_IMPORT GetProcAddress
#else
#include <dlfcn.h>
typedef void* B3_DYNLIB_HANDLE;
#define B3_DYNLIB_OPEN(path) dlopen(path, RTLD_NOW | RTLD_GLOBAL)
#define B3_DYNLIB_CLOSE dlclose
#define B3_DYNLIB_IMPORT dlsym
#endif
struct b3Plugin
{
B3_DYNLIB_HANDLE m_pluginHandle;
bool m_ownsPluginHandle;
std::string m_pluginPath;
int m_pluginUniqueId;
PFN_INIT m_initFunc;
PFN_EXIT m_exitFunc;
PFN_EXECUTE m_executeCommandFunc;
PFN_TICK m_preTickFunc;
PFN_TICK m_postTickFunc;
void* m_userPointer;
b3Plugin()
:m_pluginHandle(0),
m_ownsPluginHandle(false),
m_pluginUniqueId(-1),
m_initFunc(0),
m_exitFunc(0),
m_executeCommandFunc(0),
m_postTickFunc(0),
m_preTickFunc(0),
m_userPointer(0)
{
}
void clear()
{
if (m_ownsPluginHandle)
{
B3_DYNLIB_CLOSE(m_pluginHandle);
}
m_pluginHandle = 0;
m_initFunc = 0;
m_exitFunc = 0;
m_executeCommandFunc = 0;
m_preTickFunc = 0;
m_postTickFunc = 0;
m_userPointer = 0;
}
};
typedef b3PoolBodyHandle<b3Plugin> b3PluginHandle;
struct b3PluginManagerInternalData
{
b3ResizablePool<b3PluginHandle> m_plugins;
b3HashMap<b3HashString, b3PluginHandle> m_pluginMap;
PhysicsDirect* m_physicsDirect;
};
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
{
m_data = new b3PluginManagerInternalData;
m_data->m_physicsDirect = new PhysicsDirect(physSdk,false);
}
b3PluginManager::~b3PluginManager()
{
while (m_data->m_pluginMap.size())
{
b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(0);
unloadPlugin(plugin->m_pluginUniqueId);
}
delete m_data->m_physicsDirect;
m_data->m_pluginMap.clear();
m_data->m_plugins.exitHandles();
delete m_data;
}
int b3PluginManager::loadPlugin(const char* pluginPath)
{
int pluginUniqueId = -1;
b3Plugin* pluginOrg = m_data->m_pluginMap.find(pluginPath);
if (pluginOrg)
{
//already loaded
pluginUniqueId = pluginOrg->m_pluginUniqueId;
}
else
{
pluginUniqueId = m_data->m_plugins.allocHandle();
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
plugin->m_pluginUniqueId = pluginUniqueId;
B3_DYNLIB_HANDLE pluginHandle = B3_DYNLIB_OPEN(pluginPath);
bool ok = false;
if (pluginHandle)
{
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, "initPlugin");
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, "exitPlugin");
plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, "executePluginCommand");
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "preTickPluginCallback");
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, "postTickPluginCallback");
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
{
b3PluginContext context;
context.m_userPointer = plugin->m_userPointer;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
int version = plugin->m_initFunc(&context);
//keep the user pointer persistent
plugin->m_userPointer = context.m_userPointer;
if (version == SHARED_MEMORY_MAGIC_NUMBER)
{
ok = true;
plugin->m_ownsPluginHandle = true;
plugin->m_pluginHandle = pluginHandle;
plugin->m_pluginPath = pluginPath;
m_data->m_pluginMap.insert(pluginPath, *plugin);
}
else
{
int expect = SHARED_MEMORY_MAGIC_NUMBER;
b3Warning("Warning: plugin is wrong version: expected %d, got %d\n", expect, version);
}
}
else
{
b3Warning("Loaded plugin but couldn't bind functions");
}
if (!ok)
{
B3_DYNLIB_CLOSE(pluginHandle);
}
}
else
{
b3Warning("Warning: couldn't load plugin %s\n", pluginPath);
}
if (!ok)
{
m_data->m_plugins.freeHandle(pluginUniqueId);
pluginUniqueId = -1;
}
}
return pluginUniqueId;
}
void b3PluginManager::unloadPlugin(int pluginUniqueId)
{
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
if (plugin)
{
b3PluginContext context;
context.m_userPointer = plugin->m_userPointer;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
plugin->m_exitFunc(&context);
m_data->m_pluginMap.remove(plugin->m_pluginPath.c_str());
m_data->m_plugins.freeHandle(pluginUniqueId);
}
}
void b3PluginManager::tickPlugins(double timeStep, bool isPreTick)
{
for (int i=0;i<m_data->m_pluginMap.size();i++)
{
b3PluginHandle* plugin = m_data->m_pluginMap.getAtIndex(i);
PFN_TICK tick = isPreTick? plugin->m_preTickFunc : plugin->m_postTickFunc;
if (tick)
{
b3PluginContext context;
context.m_userPointer = plugin->m_userPointer;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
int result = tick(&context);
plugin->m_userPointer = context.m_userPointer;
}
}
}
int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArguments* arguments)
{
int result = -1;
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
if (plugin)
{
b3PluginContext context;
context.m_userPointer = plugin->m_userPointer;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
result = plugin->m_executeCommandFunc(&context, arguments);
plugin->m_userPointer = context.m_userPointer;
}
return result;
}
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc)
{
b3Plugin orgPlugin;
int pluginUniqueId = m_data->m_plugins.allocHandle();
b3PluginHandle* pluginHandle = m_data->m_plugins.getHandle(pluginUniqueId);
pluginHandle->m_pluginHandle = 0;
pluginHandle->m_ownsPluginHandle =false;
pluginHandle->m_pluginUniqueId = pluginUniqueId;
pluginHandle->m_executeCommandFunc = executeCommandFunc;
pluginHandle->m_exitFunc = exitFunc;
pluginHandle->m_initFunc = initFunc;
pluginHandle->m_preTickFunc = preTickFunc;
pluginHandle->m_postTickFunc = postTickFunc;
pluginHandle->m_pluginHandle = 0;
pluginHandle->m_pluginPath = pluginPath;
pluginHandle->m_userPointer = 0;
m_data->m_pluginMap.insert(pluginPath, *pluginHandle);
{
b3PluginContext context;
context.m_userPointer = 0;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
int result = pluginHandle->m_initFunc(&context);
pluginHandle->m_userPointer = context.m_userPointer;
}
return pluginUniqueId;
}

View File

@@ -0,0 +1,23 @@
#ifndef B3_PLUGIN_MANAGER_H
#define B3_PLUGIN_MANAGER_H
#include "plugins/b3PluginAPI.h"
class b3PluginManager
{
struct b3PluginManagerInternalData* m_data;
public:
b3PluginManager(class PhysicsCommandProcessorInterface* physSdk);
virtual ~b3PluginManager();
int loadPlugin(const char* pluginPath);
void unloadPlugin(int pluginUniqueId);
int executePluginCommand(int pluginUniqueId, const struct b3PluginArguments* arguments);
void tickPlugins(double timeStep, bool isPreTick);
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE m_executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc);
};
#endif //B3_PLUGIN_MANAGER_H

View File

@@ -0,0 +1,37 @@
#ifndef B3_PLUGIN_API_H
#define B3_PLUGIN_API_H
#ifdef _WIN32
#define B3_SHARED_API __declspec(dllexport)
#elif defined (__GNUC__)
#define B3_SHARED_API __attribute__((visibility("default")))
#else
#define B3_SHARED_API
#endif
#if defined(_WIN32)
#define B3_API_ENTRY
#define B3_API_CALL __cdecl
#define B3_CALLBACK __cdecl
#else
#define B3_API_ENTRY
#define B3_API_CALL
#define B3_CALLBACK
#endif
#ifdef __cplusplus
extern "C" {
#endif
/* Plugin API */
typedef B3_API_ENTRY int (B3_API_CALL * PFN_INIT)(struct b3PluginContext* context);
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)(struct b3PluginContext* context);
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
typedef B3_API_ENTRY int (B3_API_CALL * PFN_TICK)(struct b3PluginContext* context);
#ifdef __cplusplus
}
#endif
#endif //B3_PLUGIN_API_H

View File

@@ -0,0 +1,21 @@
#ifndef B3_PLUGIN_CONTEXT_H
#define B3_PLUGIN_CONTEXT_H
#include "../PhysicsClientC_API.h"
struct b3PluginContext
{
b3PhysicsClientHandle m_physClient;
//plugin can modify the m_userPointer to store persistent object pointer (class or struct instance etc)
void* m_userPointer;
};
#endif //B3_PLUGIN_CONTEXT_H

View File

@@ -0,0 +1,42 @@
project ("pybullet_testplugin")
language "C++"
kind "SharedLib"
includedirs {".","../../../../src", "../../../../examples",
"../../../ThirdPartyLibs"}
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
hasCL = findOpenCL("clew")
links{"BulletFileLoader", "Bullet3Common", "LinearMath"}
if os.is("MacOSX") then
-- targetextension {"so"}
links{"Cocoa.framework","Python"}
end
files {
"testplugin.cpp",
"../../PhysicsClient.cpp",
"../../PhysicsClient.h",
"../../PhysicsClientSharedMemory.cpp",
"../../PhysicsClientSharedMemory.h",
"../../PhysicsClientSharedMemory_C_API.cpp",
"../../PhysicsClientSharedMemory_C_API.h",
"../../PhysicsClientC_API.cpp",
"../../PhysicsClientC_API.h",
"../../Win32SharedMemory.cpp",
"../../Win32SharedMemory.h",
"../../PosixSharedMemory.cpp",
"../../PosixSharedMemory.h",
"../../../Utils/b3Clock.cpp",
"../../../Utils/b3Clock.h",
"../../../Utils/b3ResourcePath.cpp",
"../../../Utils/b3ResourcePath.h",
}

View File

@@ -0,0 +1,150 @@
//test plugin, can load a URDF file, example usage on a Windows machine:
/*
import pybullet as p
p.connect(p.GUI)
pluginUid = p.loadPlugin("E:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll")
commandUid = 0
argument = "plane.urdf"
p.executePluginCommand(pluginUid,commandUid,argument)
p.unloadPlugin(pluginUid)
*/
#include "testplugin.h"
#include "../../SharedMemoryPublic.h"
#include "../b3PluginContext.h"
#include <stdio.h>
struct MyClass
{
int m_testData;
MyClass()
:m_testData(42)
{
}
virtual ~MyClass()
{
}
};
B3_SHARED_API int initPlugin(struct b3PluginContext* context)
{
MyClass* obj = new MyClass();
context->m_userPointer = obj;
printf("hi!\n");
return SHARED_MEMORY_MAGIC_NUMBER;
}
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context)
{
MyClass* obj = (MyClass* )context->m_userPointer;
{
b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(context->m_physClient);
int deviceTypeFilter = VR_DEVICE_CONTROLLER;
b3VREventsSetDeviceTypeFilter(commandHandle, deviceTypeFilter);
b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
int statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_REQUEST_VR_EVENTS_DATA_COMPLETED)
{
struct b3VREventsData vrEvents;
int i = 0;
b3GetVREventsData(context->m_physClient, &vrEvents);
if (vrEvents.m_numControllerEvents)
{
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
printf("got %d VR controller events!\n", vrEvents.m_numControllerEvents);
}
}
}
{
b3KeyboardEventsData keyboardEventsData;
b3SharedMemoryCommandHandle commandHandle = b3RequestKeyboardEventsCommandInit(context->m_physClient);
b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
b3GetKeyboardEventsData(context->m_physClient, &keyboardEventsData);
if (keyboardEventsData.m_numKeyboardEvents)
{
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
printf("got %d keyboard events\n", keyboardEventsData.m_numKeyboardEvents);
}
}
{
b3MouseEventsData mouseEventsData;
b3SharedMemoryCommandHandle commandHandle = b3RequestMouseEventsCommandInit(context->m_physClient);
b3SubmitClientCommandAndWaitStatus(context->m_physClient, commandHandle);
b3GetMouseEventsData(context->m_physClient, &mouseEventsData);
if (mouseEventsData.m_numMouseEvents)
{
//this is only for a test, normally you wouldn't print to the console at each simulation substep!
printf("got %d mouse events\n", mouseEventsData.m_numMouseEvents);
}
}
return 0;
}
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context)
{
MyClass* obj = (MyClass* )context->m_userPointer;
obj->m_testData++;
return 0;
}
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
{
printf("text argument:%s\n",arguments->m_text);
printf("int args: [");
for (int i=0;i<arguments->m_numInts;i++)
{
printf("%d", arguments->m_ints[i]);
if ((i+1)<arguments->m_numInts)
{
printf(",");
}
}
printf("]\nfloat args: [");
for (int i=0;i<arguments->m_numFloats;i++)
{
printf("%f", arguments->m_floats[i]);
if ((i+1)<arguments->m_numFloats)
{
printf(",");
}
}
printf("]\n");
MyClass* obj = (MyClass*) context->m_userPointer;
b3SharedMemoryStatusHandle statusHandle;
int statusType = -1;
int bodyUniqueId = -1;
b3SharedMemoryCommandHandle command =
b3LoadUrdfCommandInit(context->m_physClient, arguments->m_text);
statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_URDF_LOADING_COMPLETED)
{
bodyUniqueId = b3GetStatusBodyIndex(statusHandle);
}
return bodyUniqueId;
}
B3_SHARED_API void exitPlugin(struct b3PluginContext* context)
{
MyClass* obj = (MyClass*) context->m_userPointer;
delete obj;
context->m_userPointer = 0;
printf("bye!\n");
}

View File

@@ -0,0 +1,26 @@
#ifndef TEST_PLUGIN_H
#define TEST_PLUGIN_H
#include "../b3PluginAPI.h"
#ifdef __cplusplus
extern "C"
{
#endif
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
B3_SHARED_API int initPlugin(struct b3PluginContext* context);
B3_SHARED_API void exitPlugin(struct b3PluginContext* context);
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
//preTickPluginCallback and postTickPluginCallback are optional.
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context);
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context);
#ifdef __cplusplus
};
#endif
#endif//#define TEST_PLUGIN_H

View File

@@ -7,7 +7,7 @@ else
kind "ConsoleApp"
end
includedirs {".","../../src", "../ThirdPartyLibs",}
includedirs {".","../../src", "../ThirdPartyLibs"}
links {
"Bullet3Common","BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision", "LinearMath", "BussIK"
@@ -53,6 +53,8 @@ myfiles =
"SharedMemoryCommandProcessor.h",
"PhysicsServerCommandProcessor.cpp",
"PhysicsServerCommandProcessor.h",
"b3PluginManager.cpp",
"b3PluginManager.h",
"TinyRendererVisualShapeConverter.cpp",
"TinyRendererVisualShapeConverter.h",
"../TinyRenderer/geometry.cpp",
@@ -99,6 +101,7 @@ myfiles =
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
}
files {
@@ -405,4 +408,4 @@ end
include "udp"
include "tcp"
include "plugins/testPlugin"

View File

@@ -88,6 +88,9 @@ myfiles =
"../SharedMemoryPublic.h",
"../PhysicsServerCommandProcessor.cpp",
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../PhysicsDirect.cpp",
"../PhysicsClient.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../../TinyRenderer/geometry.cpp",

View File

@@ -79,6 +79,9 @@ myfiles =
"../SharedMemoryPublic.h",
"../PhysicsServerCommandProcessor.cpp",
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../PhysicsDirect.cpp",
"../PhysicsClient.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../../TinyRenderer/geometry.cpp",

View File

@@ -43,6 +43,9 @@ SET(pybullet_SRCS
../../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

View File

@@ -23,6 +23,7 @@ p.changeConstraint(c,gearRatio=-1, maxForce=10000)
p.setRealTimeSimulation(1)
while(1):
p.setGravity(0,0,-10)
time.sleep(0.01)
#p.removeConstraint(c)

View File

@@ -187,6 +187,7 @@ t = 0.0
t_end = t + 15
ref_time = time.time()
while (t<t_end):
p.setGravity(0,0,-10)
if (useRealTime):
t = time.time()-ref_time
else:

View File

@@ -1,6 +1,8 @@
import pybullet as p
import time
#p.connect(p.UDP,"192.168.86.100")
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI)
@@ -80,6 +82,12 @@ p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0.000000,0.000000,0.000000)
p.setGravity(0,0,-10)
p.stepSimulation()
##show this for 10 seconds
#now = time.time()
#while (time.time() < now+10):
# p.stepSimulation()
p.setRealTimeSimulation(1)
while (1):
p.setGravity(0,0,-10)
p.disconnect()

View File

@@ -116,6 +116,8 @@ if not _OPTIONS["no-enet"] then
"../../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",

View File

@@ -445,10 +445,10 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
{
printf("Connection terminated, couldn't get body info\n");
b3DisconnectSharedMemory(sm);
sm = 0;
sm = 0;
sPhysicsClients1[freeIndex] = 0;
sPhysicsClientsGUI[freeIndex] = 0;
sNumPhysicsClients++;
sPhysicsClientsGUI[freeIndex] = 0;
sNumPhysicsClients++;
return PyInt_FromLong(-1);
}
}
@@ -2835,7 +2835,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject*
if (info.m_jointName)
{
PyTuple_SetItem(pyListJointInfo, 1,
PyString_FromString(info.m_jointName));
PyString_FromString(info.m_jointName));
} else
{
PyTuple_SetItem(pyListJointInfo, 1,
@@ -4754,21 +4754,21 @@ static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject*
static PyObject* MyConvertContactPoint(struct b3ContactInformation* contactPointPtr)
{
/*
0 int m_contactFlags;
1 int m_bodyUniqueIdA;
2 int m_bodyUniqueIdB;
3 int m_linkIndexA;
4 int m_linkIndexB;
5 double m_positionOnAInWS[3];//contact point location on object A,
in world space coordinates
6 double m_positionOnBInWS[3];//contact point location on object
A, in world space coordinates
7 double m_contactNormalOnBInWS[3];//the separating contact
normal, pointing from object B towards object A
8 double m_contactDistance;//negative number is penetration, positive
is distance.
9 double m_normalForce;
*/
0 int m_contactFlags;
1 int m_bodyUniqueIdA;
2 int m_bodyUniqueIdB;
3 int m_linkIndexA;
4 int m_linkIndexB;
5 double m_positionOnAInWS[3];//contact point location on object A,
in world space coordinates
6 double m_positionOnBInWS[3];//contact point location on object
A, in world space coordinates
7 double m_contactNormalOnBInWS[3];//the separating contact
normal, pointing from object B towards object A
8 double m_contactDistance;//negative number is penetration, positive
is distance.
9 double m_normalForce;
*/
int i;
@@ -5559,9 +5559,9 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
{
int bodyUniqueIdA = -1;
int bodyUniqueIdB = -1;
int linkIndexA = -2;
int linkIndexB = -2;
int linkIndexA = -2;
int linkIndexB = -2;
b3SharedMemoryCommandHandle commandHandle;
struct b3ContactInformation contactPointData;
b3SharedMemoryStatusHandle statusHandle;
@@ -5583,24 +5583,24 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
}
commandHandle = b3InitRequestContactPointInformation(sm);
if (bodyUniqueIdA>=0)
{
b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA);
}
if (bodyUniqueIdB>=0)
{
b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB);
}
if (bodyUniqueIdA>=0)
{
b3SetContactFilterBodyA(commandHandle, bodyUniqueIdA);
}
if (bodyUniqueIdB>=0)
{
b3SetContactFilterBodyB(commandHandle, bodyUniqueIdB);
}
if (linkIndexA>=-1)
{
b3SetContactFilterLinkA( commandHandle, linkIndexA);
}
if (linkIndexB >=-1)
{
b3SetContactFilterLinkB( commandHandle, linkIndexB);
}
if (linkIndexA>=-1)
{
b3SetContactFilterLinkA( commandHandle, linkIndexA);
}
if (linkIndexB >=-1)
{
b3SetContactFilterLinkB( commandHandle, linkIndexB);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED)
@@ -6574,7 +6574,7 @@ static PyObject* pybullet_invertTransform(PyObject* self,
PyErr_SetString(SpamError, "Invalid input: expected position [x,y,z] and orientation [x,y,z,w].");
return NULL;
}
/// quaternion <-> euler yaw/pitch/roll convention from URDF/SDF, see Gazebo
/// https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc
@@ -6653,6 +6653,131 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self,
return Py_None;
}
static PyObject* pybullet_loadPlugin(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
char* pluginPath = 0;
b3SharedMemoryCommandHandle command = 0;
b3SharedMemoryStatusHandle statusHandle = 0;
int statusType = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginPath", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist, &pluginPath, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3CreateCustomCommand(sm);
b3CustomCommandLoadPlugin(command, pluginPath);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusPluginUniqueId(statusHandle);
return PyInt_FromLong(statusType);
}
static PyObject* pybullet_unloadPlugin(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
int pluginUniqueId = -1;
b3SharedMemoryCommandHandle command = 0;
b3SharedMemoryStatusHandle statusHandle = 0;
int statusType = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginUniqueId", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &pluginUniqueId,&physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3CreateCustomCommand(sm);
b3CustomCommandUnloadPlugin(command, pluginUniqueId);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
Py_INCREF(Py_None);
return Py_None;;
}
//createCustomCommand for executing commands implemented in a plugin system
static PyObject* pybullet_executePluginCommand(PyObject* self,
PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
int pluginUniqueId = -1;
char* textArgument = 0;
b3SharedMemoryCommandHandle command=0;
b3SharedMemoryStatusHandle statusHandle=0;
int statusType = -1;
PyObject* intArgs=0;
PyObject* floatArgs=0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = { "pluginUniqueId", "textArgument", "intArgs", "floatArgs", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sOOi", kwlist, &pluginUniqueId, &textArgument, &intArgs, &floatArgs, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
command = b3CreateCustomCommand(sm);
b3CustomCommandExecutePluginCommand(command, pluginUniqueId, textArgument);
{
PyObject* seqIntArgs = intArgs?PySequence_Fast(intArgs, "expected a sequence"):0;
PyObject* seqFloatArgs = floatArgs?PySequence_Fast(floatArgs, "expected a sequence"):0;
int numIntArgs = seqIntArgs?PySequence_Size(intArgs):0;
int numFloatArgs = seqIntArgs?PySequence_Size(floatArgs):0;
int i;
for (i=0;i<numIntArgs;i++)
{
int val = pybullet_internalGetIntFromSequence(seqIntArgs,i);
b3CustomCommandExecuteAddIntArgument(command, val);
}
for (i=0;i<numFloatArgs;i++)
{
float val = pybullet_internalGetFloatFromSequence(seqFloatArgs,i);
b3CustomCommandExecuteAddFloatArgument(command, val);
}
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusPluginCommandResult(statusHandle);
return PyInt_FromLong(statusType);
}
///Inverse Kinematics binding
static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
PyObject* args, PyObject* keywds)
@@ -6831,8 +6956,7 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
/// Given an object id, joint positions, joint velocities and joint
/// accelerations,
/// compute the joint forces using Inverse Dynamics
static PyObject* pybullet_calculateInverseDynamics(PyObject* self,
PyObject* args, PyObject* keywds)
static PyObject* pybullet_calculateInverseDynamics(PyObject* self, PyObject* args, PyObject* keywds)
{
{
int bodyUniqueId;
@@ -6841,14 +6965,21 @@ static PyObject* pybullet_calculateInverseDynamics(PyObject* self,
PyObject* objAccelerations;
int physicsClientId = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"bodyUniqueId", "objPositions", "objVelocities", "objAccelerations", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist, &bodyUniqueId, &objPositionsQ,
&objVelocitiesQdot, &objAccelerations, &physicsClientId))
static char* kwlist[] = {"bodyUniqueId", "objPositions",
"objVelocities", "objAccelerations",
"physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist,
&bodyUniqueId, &objPositionsQ,
&objVelocitiesQdot, &objAccelerations,
&physicsClientId))
{
static char* kwlist2[] = {"bodyIndex", "objPositions", "objVelocities", "objAccelerations", "physicsClientId", NULL};
static char* kwlist2[] = {"bodyIndex", "objPositions",
"objVelocities", "objAccelerations",
"physicsClientId", NULL};
PyErr_Clear();
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist2, &bodyUniqueId, &objPositionsQ,
&objVelocitiesQdot, &objAccelerations, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iOOO|i", kwlist2,
&bodyUniqueId, &objPositionsQ, &objVelocitiesQdot,
&objAccelerations, &physicsClientId))
{
return NULL;
}
@@ -6947,6 +7078,150 @@ static PyObject* pybullet_calculateInverseDynamics(PyObject* self,
return Py_None;
}
/// Given an object id, joint positions, joint velocities and joint
/// accelerations, compute the Jacobian
static PyObject* pybullet_calculateJacobian(PyObject* self, PyObject* args, PyObject* keywds)
{
{
int bodyUniqueId;
int linkIndex;
PyObject* localPosition;
PyObject* objPositions;
PyObject* objVelocities;
PyObject* objAccelerations;
int physicsClientId = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "localPosition",
"objPositions", "objVelocities",
"objAccelerations", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiOOOO|i", kwlist,
&bodyUniqueId, &linkIndex, &localPosition, &objPositions,
&objVelocities, &objAccelerations, &physicsClientId))
{
return NULL;
}
sm = getPhysicsClient(physicsClientId);
if (sm == 0)
{
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
int szLoPos = PySequence_Size(localPosition);
int szObPos = PySequence_Size(objPositions);
int szObVel = PySequence_Size(objVelocities);
int szObAcc = PySequence_Size(objAccelerations);
int numJoints = b3GetNumJoints(sm, bodyUniqueId);
if (numJoints && (szLoPos == 3) && (szObPos == numJoints) &&
(szObVel == numJoints) && (szObAcc == numJoints))
{
int byteSizeJoints = sizeof(double) * numJoints;
int byteSizeVec3 = sizeof(double) * 3;
int i;
PyObject* pyResultList = PyTuple_New(2);
double* localPoint = (double*)malloc(byteSizeVec3);
double* jointPositions = (double*)malloc(byteSizeJoints);
double* jointVelocities = (double*)malloc(byteSizeJoints);
double* jointAccelerations = (double*)malloc(byteSizeJoints);
double* linearJacobian = (double*)malloc(3 * byteSizeJoints);
double* angularJacobian = (double*)malloc(3 * byteSizeJoints);
pybullet_internalSetVectord(localPosition, localPoint);
for (i = 0; i < numJoints; i++)
{
jointPositions[i] =
pybullet_internalGetFloatFromSequence(objPositions, i);
jointVelocities[i] =
pybullet_internalGetFloatFromSequence(objVelocities, i);
jointAccelerations[i] =
pybullet_internalGetFloatFromSequence(objAccelerations, i);
}
{
b3SharedMemoryStatusHandle statusHandle;
b3SharedMemoryCommandHandle commandHandle =
b3CalculateJacobianCommandInit(sm, bodyUniqueId,
linkIndex, localPoint, jointPositions,
jointVelocities, jointAccelerations);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
int statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_CALCULATED_JACOBIAN_COMPLETED)
{
int dofCount;
b3GetStatusJacobian(statusHandle, &dofCount, NULL, NULL);
if (dofCount)
{
int byteSizeDofCount = sizeof(double) * dofCount;
double* linearJacobian = (double*)malloc(3 * byteSizeDofCount);
double* angularJacobian = (double*)malloc(3 * byteSizeDofCount);
b3GetStatusJacobian(statusHandle,
NULL,
linearJacobian,
angularJacobian);
if (linearJacobian)
{
int r;
PyObject* pymat = PyTuple_New(3);
for (r = 0; r < 3; ++r) {
int c;
PyObject* pyrow = PyTuple_New(dofCount);
for (c = 0; c < dofCount; ++c) {
int element = r * dofCount + c;
PyTuple_SetItem(pyrow, c,
PyFloat_FromDouble(linearJacobian[element]));
}
PyTuple_SetItem(pymat, r, pyrow);
}
PyTuple_SetItem(pyResultList, 0, pymat);
}
if (angularJacobian)
{
int r;
PyObject* pymat = PyTuple_New(3);
for (r = 0; r < 3; ++r) {
int c;
PyObject* pyrow = PyTuple_New(dofCount);
for (c = 0; c < dofCount; ++c) {
int element = r * dofCount + c;
PyTuple_SetItem(pyrow, c,
PyFloat_FromDouble(linearJacobian[element]));
}
PyTuple_SetItem(pymat, r, pyrow);
}
PyTuple_SetItem(pyResultList, 1, pymat);
}
}
}
else
{
PyErr_SetString(SpamError,
"Internal error in calculateJacobian");
}
}
free(localPoint);
free(jointPositions);
free(jointVelocities);
free(jointAccelerations);
free(linearJacobian);
free(angularJacobian);
if (pyResultList) return pyResultList;
}
else
{
PyErr_SetString(SpamError,
"calculateJacobian [numJoints] needs to be "
"positive, [local position] needs to be of "
"size 3 and [joint positions], "
"[joint velocities], [joint accelerations] "
"need to match the number of joints.");
return NULL;
}
}
}
Py_INCREF(Py_None);
return Py_None;
}
static PyMethodDef SpamMethods[] = {
{"connect", (PyCFunction)pybullet_connectPhysicsServer, METH_VARARGS | METH_KEYWORDS,
@@ -6985,6 +7260,8 @@ static PyMethodDef SpamMethods[] = {
"This is for experimental purposes, use at own risk, magic may or not happen"},
{"loadURDF", (PyCFunction)pybullet_loadURDF, METH_VARARGS | METH_KEYWORDS,
"bodyUniqueId = loadURDF(fileName, basePosition=[0.,0.,0.], baseOrientation=[0.,0.,0.,1.], "
"useMaximalCoordinates=0, useFixedBase=0, flags=0, globalScaling=1.0, physicsClientId=0)\n"
"Create a multibody by loading a URDF file."},
{"loadSDF", (PyCFunction)pybullet_loadSDF, METH_VARARGS | METH_KEYWORDS,
@@ -7233,6 +7510,19 @@ static PyMethodDef SpamMethods[] = {
"Given an object id, joint positions, joint velocities and joint "
"accelerations, compute the joint forces using Inverse Dynamics"},
{"calculateJacobian", (PyCFunction)pybullet_calculateJacobian, METH_VARARGS | METH_KEYWORDS,
"Compute the jacobian for a specified local position on a body and its kinematics.\n"
"Args:\n"
" bodyIndex - a scalar defining the unique object id.\n"
" linkIndex - a scalar identifying the link containing the local point.\n"
" localPosition - a list of [x, y, z] of the coordinates of the local point.\n"
" objPositions - a list of the joint positions.\n"
" objVelocities - a list of the joint velocities.\n"
" objAccelerations - a list of the joint accelerations.\n"
"Returns:\n"
" linearJacobian - a list of the partial linear velocities of the jacobian.\n"
" angularJacobian - a list of the partial angular velocities of the jacobian.\n"},
{"calculateInverseKinematics", (PyCFunction)pybullet_calculateInverseKinematics,
METH_VARARGS | METH_KEYWORDS,
"Inverse Kinematics bindings: Given an object id, "
@@ -7265,6 +7555,16 @@ static PyMethodDef SpamMethods[] = {
"Cast a batch of rays and return the result for each of the rays (first object hit, if any. or -1) "
"Takes two arguments (list of from_positions [x,y,z] and a list of to_positions [x,y,z] in Cartesian world coordinates"},
{ "loadPlugin", (PyCFunction)pybullet_loadPlugin, METH_VARARGS | METH_KEYWORDS,
"Load a plugin, could implement custom commands etc." },
{ "unloadPlugin", (PyCFunction)pybullet_unloadPlugin, METH_VARARGS | METH_KEYWORDS,
"Unload a plugin, given the pluginUniqueId." },
{ "executePluginCommand", (PyCFunction)pybullet_executePluginCommand, METH_VARARGS | METH_KEYWORDS,
"Execute a command, implemented in a plugin." },
{"submitProfileTiming", (PyCFunction)pybullet_submitProfileTiming, METH_VARARGS | METH_KEYWORDS,
"Add a custom profile timing that will be visible in performance profile recordings on the physics server."
"On the physics server (in GUI and VR mode) you can press 'p' to start and/or stop profile recordings" },

File diff suppressed because it is too large Load Diff

View File

@@ -70,6 +70,7 @@ sources = ["examples/pybullet/pybullet.c"]\
+["examples/SharedMemory/PhysicsClientUDP_C_API.cpp"]\
+["examples/SharedMemory/PhysicsClientTCP.cpp"]\
+["examples/SharedMemory/PhysicsClientTCP_C_API.cpp"]\
+["examples/SharedMemory/b3PluginManager.cpp"]\
+["examples/Utils/b3ResourcePath.cpp"]\
+["examples/Utils/RobotLoggingUtil.cpp"]\
+["examples/Utils/ChromeTraceUtil.cpp"]\
@@ -440,7 +441,7 @@ print("-----")
setup(
name = 'pybullet',
version='1.4.5',
version='1.4.6',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',

View File

@@ -227,26 +227,59 @@ static void b3FetchLeaves(b3DynamicBvh* pdbvt,
}
}
//
static void b3Split( const b3NodeArray& leaves,
b3NodeArray& left,
b3NodeArray& right,
static bool b3LeftOfAxis( const b3DbvtNode* node,
const b3Vector3& org,
const b3Vector3& axis)
{
return b3Dot(axis,node->volume.Center()-org) <= 0;
}
// Partitions leaves such that leaves[0, n) are on the
// left of axis, and leaves[n, count) are on the right
// of axis. returns N.
static int b3Split( b3DbvtNode** leaves,
int count,
const b3Vector3& org,
const b3Vector3& axis)
{
left.resize(0);
right.resize(0);
for(int i=0,ni=leaves.size();i<ni;++i)
int begin=0;
int end=count;
for(;;)
{
if(b3Dot(axis,leaves[i]->volume.Center()-org)<0)
left.push_back(leaves[i]);
else
right.push_back(leaves[i]);
while(begin!=end && b3LeftOfAxis(leaves[begin],org,axis))
{
++begin;
}
if(begin==end)
{
break;
}
while(begin!=end && !b3LeftOfAxis(leaves[end-1],org,axis))
{
--end;
}
if(begin==end)
{
break;
}
// swap out of place nodes
--end;
b3DbvtNode* temp=leaves[begin];
leaves[begin]=leaves[end];
leaves[end]=temp;
++begin;
}
return begin;
}
//
static b3DbvtVolume b3Bounds( const b3NodeArray& leaves)
static b3DbvtVolume b3Bounds( b3DbvtNode** leaves,
int count)
{
#if B3_DBVT_MERGE_IMPL==B3_DBVT_IMPL_SSE
B3_ATTRIBUTE_ALIGNED16(char locals[sizeof(b3DbvtVolume)]);
@@ -255,7 +288,7 @@ static b3DbvtVolume b3Bounds( const b3NodeArray& leaves)
#else
b3DbvtVolume volume=leaves[0]->volume;
#endif
for(int i=1,ni=leaves.size();i<ni;++i)
for(int i=1,ni=count;i<ni;++i)
{
b3Merge(volume,leaves[i]->volume,volume);
}
@@ -264,15 +297,16 @@ static b3DbvtVolume b3Bounds( const b3NodeArray& leaves)
//
static void b3BottomUp( b3DynamicBvh* pdbvt,
b3NodeArray& leaves)
b3DbvtNode** leaves,
int count)
{
while(leaves.size()>1)
while(count>1)
{
b3Scalar minsize=B3_INFINITY;
int minidx[2]={-1,-1};
for(int i=0;i<leaves.size();++i)
for(int i=0;i<count;++i)
{
for(int j=i+1;j<leaves.size();++j)
for(int j=i+1;j<count;++j)
{
const b3Scalar sz=b3Size(b3Merge(leaves[i]->volume,leaves[j]->volume));
if(sz<minsize)
@@ -290,31 +324,33 @@ static void b3BottomUp( b3DynamicBvh* pdbvt,
n[0]->parent = p;
n[1]->parent = p;
leaves[minidx[0]] = p;
leaves.swap(minidx[1],leaves.size()-1);
leaves.pop_back();
leaves[minidx[1]] = leaves[count-1];
--count;
}
}
//
static b3DbvtNode* b3TopDown(b3DynamicBvh* pdbvt,
b3NodeArray& leaves,
b3DbvtNode** leaves,
int count,
int bu_treshold)
{
static const b3Vector3 axis[]={b3MakeVector3(1,0,0),
b3MakeVector3(0,1,0),
b3MakeVector3(0,0,1)};
if(leaves.size()>1)
b3Assert(bu_treshold>1);
if(count>1)
{
if(leaves.size()>bu_treshold)
if(count>bu_treshold)
{
const b3DbvtVolume vol=b3Bounds(leaves);
const b3DbvtVolume vol=b3Bounds(leaves,count);
const b3Vector3 org=vol.Center();
b3NodeArray sets[2];
int partition;
int bestaxis=-1;
int bestmidp=leaves.size();
int bestmidp=count;
int splitcount[3][2]={{0,0},{0,0},{0,0}};
int i;
for( i=0;i<leaves.size();++i)
for( i=0;i<count;++i)
{
const b3Vector3 x=leaves[i]->volume.Center()-org;
for(int j=0;j<3;++j)
@@ -336,29 +372,23 @@ static b3DbvtNode* b3TopDown(b3DynamicBvh* pdbvt,
}
if(bestaxis>=0)
{
sets[0].reserve(splitcount[bestaxis][0]);
sets[1].reserve(splitcount[bestaxis][1]);
b3Split(leaves,sets[0],sets[1],org,axis[bestaxis]);
partition=b3Split(leaves,count,org,axis[bestaxis]);
b3Assert(partition!=0 && partition!=count);
}
else
{
sets[0].reserve(leaves.size()/2+1);
sets[1].reserve(leaves.size()/2);
for(int i=0,ni=leaves.size();i<ni;++i)
{
sets[i&1].push_back(leaves[i]);
}
partition=count/2+1;
}
b3DbvtNode* node=b3CreateNode(pdbvt,0,vol,0);
node->childs[0]=b3TopDown(pdbvt,sets[0],bu_treshold);
node->childs[1]=b3TopDown(pdbvt,sets[1],bu_treshold);
node->childs[0]=b3TopDown(pdbvt,&leaves[0],partition,bu_treshold);
node->childs[1]=b3TopDown(pdbvt,&leaves[partition],count-partition,bu_treshold);
node->childs[0]->parent=node;
node->childs[1]->parent=node;
return(node);
}
else
{
b3BottomUp(pdbvt,leaves);
b3BottomUp(pdbvt,leaves,count);
return(leaves[0]);
}
}
@@ -442,7 +472,7 @@ void b3DynamicBvh::optimizeBottomUp()
b3NodeArray leaves;
leaves.reserve(m_leaves);
b3FetchLeaves(this,m_root,leaves);
b3BottomUp(this,leaves);
b3BottomUp(this,&leaves[0],leaves.size());
m_root=leaves[0];
}
}
@@ -455,7 +485,7 @@ void b3DynamicBvh::optimizeTopDown(int bu_treshold)
b3NodeArray leaves;
leaves.reserve(m_leaves);
b3FetchLeaves(this,m_root,leaves);
m_root=b3TopDown(this,leaves,bu_treshold);
m_root=b3TopDown(this,&leaves[0],leaves.size(),bu_treshold);
}
}

View File

@@ -229,25 +229,60 @@ static void fetchleaves(btDbvt* pdbvt,
}
//
static void split( const tNodeArray& leaves,
tNodeArray& left,
tNodeArray& right,
static bool leftOfAxis( const btDbvtNode* node,
const btVector3& org,
const btVector3& axis)
{
return btDot(axis, node->volume.Center() - org) <= 0;
}
// Partitions leaves such that leaves[0, n) are on the
// left of axis, and leaves[n, count) are on the right
// of axis. returns N.
static int split( btDbvtNode** leaves,
int count,
const btVector3& org,
const btVector3& axis)
{
left.resize(0);
right.resize(0);
for(int i=0,ni=leaves.size();i<ni;++i)
int begin=0;
int end=count;
for(;;)
{
if(btDot(axis,leaves[i]->volume.Center()-org)<0)
left.push_back(leaves[i]);
else
right.push_back(leaves[i]);
while(begin!=end && leftOfAxis(leaves[begin],org,axis))
{
++begin;
}
if(begin==end)
{
break;
}
while(begin!=end && !leftOfAxis(leaves[end-1],org,axis))
{
--end;
}
if(begin==end)
{
break;
}
// swap out of place nodes
--end;
btDbvtNode* temp=leaves[begin];
leaves[begin]=leaves[end];
leaves[end]=temp;
++begin;
}
return begin;
}
//
static btDbvtVolume bounds( const tNodeArray& leaves)
static btDbvtVolume bounds( btDbvtNode** leaves,
int count)
{
#if DBVT_MERGE_IMPL==DBVT_IMPL_SSE
ATTRIBUTE_ALIGNED16(char locals[sizeof(btDbvtVolume)]);
@@ -257,7 +292,7 @@ static btDbvtVolume bounds( const tNodeArray& leaves)
#else
btDbvtVolume volume=leaves[0]->volume;
#endif
for(int i=1,ni=leaves.size();i<ni;++i)
for(int i=1,ni=count;i<ni;++i)
{
Merge(volume,leaves[i]->volume,volume);
}
@@ -266,15 +301,16 @@ static btDbvtVolume bounds( const tNodeArray& leaves)
//
static void bottomup( btDbvt* pdbvt,
tNodeArray& leaves)
btDbvtNode** leaves,
int count)
{
while(leaves.size()>1)
while(count>1)
{
btScalar minsize=SIMD_INFINITY;
int minidx[2]={-1,-1};
for(int i=0;i<leaves.size();++i)
for(int i=0;i<count;++i)
{
for(int j=i+1;j<leaves.size();++j)
for(int j=i+1;j<count;++j)
{
const btScalar sz=size(merge(leaves[i]->volume,leaves[j]->volume));
if(sz<minsize)
@@ -292,31 +328,33 @@ static void bottomup( btDbvt* pdbvt,
n[0]->parent = p;
n[1]->parent = p;
leaves[minidx[0]] = p;
leaves.swap(minidx[1],leaves.size()-1);
leaves.pop_back();
leaves[minidx[1]] = leaves[count-1];
--count;
}
}
//
static btDbvtNode* topdown(btDbvt* pdbvt,
tNodeArray& leaves,
btDbvtNode** leaves,
int count,
int bu_treshold)
{
static const btVector3 axis[]={btVector3(1,0,0),
btVector3(0,1,0),
btVector3(0,0,1)};
if(leaves.size()>1)
btAssert(bu_treshold>2);
if(count>1)
{
if(leaves.size()>bu_treshold)
if(count>bu_treshold)
{
const btDbvtVolume vol=bounds(leaves);
const btDbvtVolume vol=bounds(leaves,count);
const btVector3 org=vol.Center();
tNodeArray sets[2];
int partition;
int bestaxis=-1;
int bestmidp=leaves.size();
int bestmidp=count;
int splitcount[3][2]={{0,0},{0,0},{0,0}};
int i;
for( i=0;i<leaves.size();++i)
for( i=0;i<count;++i)
{
const btVector3 x=leaves[i]->volume.Center()-org;
for(int j=0;j<3;++j)
@@ -338,29 +376,23 @@ static btDbvtNode* topdown(btDbvt* pdbvt,
}
if(bestaxis>=0)
{
sets[0].reserve(splitcount[bestaxis][0]);
sets[1].reserve(splitcount[bestaxis][1]);
split(leaves,sets[0],sets[1],org,axis[bestaxis]);
partition=split(leaves,count,org,axis[bestaxis]);
btAssert(partition!=0 && partition!=count);
}
else
{
sets[0].reserve(leaves.size()/2+1);
sets[1].reserve(leaves.size()/2);
for(int i=0,ni=leaves.size();i<ni;++i)
{
sets[i&1].push_back(leaves[i]);
}
partition=count/2+1;
}
btDbvtNode* node=createnode(pdbvt,0,vol,0);
node->childs[0]=topdown(pdbvt,sets[0],bu_treshold);
node->childs[1]=topdown(pdbvt,sets[1],bu_treshold);
node->childs[0]=topdown(pdbvt,&leaves[0],partition,bu_treshold);
node->childs[1]=topdown(pdbvt,&leaves[partition],count-partition,bu_treshold);
node->childs[0]->parent=node;
node->childs[1]->parent=node;
return(node);
}
else
{
bottomup(pdbvt,leaves);
bottomup(pdbvt,leaves,count);
return(leaves[0]);
}
}
@@ -444,7 +476,7 @@ void btDbvt::optimizeBottomUp()
tNodeArray leaves;
leaves.reserve(m_leaves);
fetchleaves(this,m_root,leaves);
bottomup(this,leaves);
bottomup(this,&leaves[0],leaves.size());
m_root=leaves[0];
}
}
@@ -457,7 +489,7 @@ void btDbvt::optimizeTopDown(int bu_treshold)
tNodeArray leaves;
leaves.reserve(m_leaves);
fetchleaves(this,m_root,leaves);
m_root=topdown(this,leaves,bu_treshold);
m_root=topdown(this,&leaves[0],leaves.size(),bu_treshold);
}
}

View File

@@ -135,6 +135,11 @@ public:
return m_solverInfo;
}
const btContactSolverInfo& getSolverInfo() const
{
return m_solverInfo;
}
///obsolete, use addAction instead.
virtual void addVehicle(btActionInterface* vehicle) {(void)vehicle;}

View File

@@ -72,6 +72,11 @@ public:
return m_multiBodies[mbIndex];
}
const btMultiBody* getMultiBody(int mbIndex) const
{
return m_multiBodies[mbIndex];
}
virtual void addMultiBodyConstraint( btMultiBodyConstraint* constraint);
virtual int getNumMultiBodyConstraints() const

View File

@@ -69,7 +69,7 @@ idScalar maxAbsMat3x(const mat3x &m) {
void mul(const mat33 &a, const mat3x &b, mat3x *result) {
if (b.cols() != result->cols()) {
error_message("size missmatch. a.cols()= %d, b.cols()= %d\n",
error_message("size missmatch. b.cols()= %d, result->cols()= %d\n",
static_cast<int>(b.cols()), static_cast<int>(result->cols()));
abort();
}

View File

@@ -1013,7 +1013,7 @@ int MultiBodyTree::MultiBodyImpl::getBodyDotJacobianRotU(const int body_index,
int MultiBodyTree::MultiBodyImpl::getBodyJacobianTrans(const int body_index, mat3x* world_jac_trans) const{
CHECK_IF_BODY_INDEX_IS_VALID(body_index);
const RigidBody &body = m_body_list[body_index];
mul(body.m_body_T_world.transpose(), body.m_body_Jac_T,world_jac_trans);
mul(body.m_body_T_world.transpose(), body.m_body_Jac_T, world_jac_trans);
return 0;
}

View File

@@ -21,6 +21,9 @@ ENDIF()
IF (NOT WIN32)
LINK_LIBRARIES( pthread )
IF (NOT APPLE)
LINK_LIBRARIES(${DL})
ENDIF()
ENDIF()
ADD_EXECUTABLE(Test_PhysicsClientServer
@@ -39,6 +42,7 @@ ENDIF()
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp

View File

@@ -177,6 +177,8 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/SharedMemory/PhysicsServerSharedMemory.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/PhysicsDirect.cpp",
"../../examples/SharedMemory/PhysicsLoopBack.cpp",
"../../examples/SharedMemory/PhysicsLoopBack.h",
"../../examples/SharedMemory/PhysicsLoopBackC_API.cpp",
@@ -261,6 +263,7 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp",
@@ -370,6 +373,7 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/b3PluginManager.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp",