This commit is contained in:
Erwin Coumans
2017-02-17 10:48:03 -08:00
43 changed files with 4021 additions and 71 deletions

View File

@@ -37,6 +37,7 @@ public:
virtual void initPhysics()=0;
virtual void exitPhysics()=0;
virtual void updateGraphics(){}
virtual void stepSimulation(float deltaTime)=0;
virtual void renderScene()=0;
virtual void physicsDebugDraw(int debugFlags)=0;//for now we reuse the flags in Bullet/src/LinearMath/btIDebugDraw.h

View File

@@ -266,6 +266,7 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
{
B3_PROFILE("clock.usleep");
clock.usleep(gMinUpdateTimeMicroSecs/10.);
exampleBrowser->updateGraphics();
} else
{
B3_PROFILE("exampleBrowser->update");

View File

@@ -257,7 +257,6 @@ void MyKeyboardCallback(int key, int state)
} else
{
b3ChromeUtilsStopTimingsAndWriteJsonFile();
}
#endif //BT_NO_PROFILE
@@ -309,8 +308,11 @@ static void MyMouseMoveCallback( float x, float y)
bool handled = false;
if (sCurrentDemo)
handled = sCurrentDemo->mouseMoveCallback(x,y);
if (!handled && gui2)
handled = gui2->mouseMoveCallback(x,y);
if (renderGui)
{
if (!handled && gui2)
handled = gui2->mouseMoveCallback(x,y);
}
if (!handled)
{
if (prevMouseMoveCallback)
@@ -327,9 +329,11 @@ static void MyMouseButtonCallback(int button, int state, float x, float y)
if (sCurrentDemo)
handled = sCurrentDemo->mouseButtonCallback(button,state,x,y);
if (!handled && gui2)
handled = gui2->mouseButtonCallback(button,state,x,y);
if (renderGui)
{
if (!handled && gui2)
handled = gui2->mouseButtonCallback(button,state,x,y);
}
if (!handled)
{
if (prevMouseButtonCallback )
@@ -1125,6 +1129,18 @@ bool OpenGLExampleBrowser::requestedExit()
return s_window->requestedExit();
}
void OpenGLExampleBrowser::updateGraphics()
{
if (sCurrentDemo)
{
if (!pauseSimulation || singleStepSimulation)
{
B3_PROFILE("sCurrentDemo->updateGraphics");
sCurrentDemo->updateGraphics();
}
}
}
void OpenGLExampleBrowser::update(float deltaTime)
{
b3ChromeUtilsEnableProfiling();

View File

@@ -19,6 +19,8 @@ public:
virtual void update(float deltaTime);
virtual void updateGraphics();
virtual bool requestedExit();
virtual void setSharedMemoryInterface(class SharedMemoryInterface* sharedMem);

View File

@@ -71,7 +71,7 @@ struct URDF2BulletCachedData
}
void registerMultiBody( int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
void registerMultiBody( int urdfLinkIndex, class btMultiBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame)
{
m_urdfLinkLocalInertialFrames[urdfLinkIndex] = localInertialFrame;
}
@@ -81,7 +81,7 @@ struct URDF2BulletCachedData
return m_urdfLink2rigidBodies[urdfLinkIndex];
}
void registerRigidBody( int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCompoundShape* compound, const btTransform& localInertialFrame)
void registerRigidBody( int urdfLinkIndex, class btRigidBody* body, const btTransform& worldTransform, btScalar mass, const btVector3& localInertiaDiagonal, const class btCollisionShape* compound, const btTransform& localInertialFrame)
{
btAssert(m_urdfLink2rigidBodies[urdfLinkIndex]==0);
@@ -250,7 +250,12 @@ void ConvertURDF2BulletInternal(
btCompoundShape* compoundShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
btCompoundShape* tmpShape = u2b.convertLinkCollisionShapes(urdfLinkIndex,pathPrefix,localInertialFrame);
btCollisionShape* compoundShape = tmpShape;
if (tmpShape->getNumChildShapes() == 1 && tmpShape->getChildTransform(0)==btTransform::getIdentity())
{
compoundShape = tmpShape->getChildShape(0);
}
int graphicsIndex = u2b.convertLinkVisualShapes(urdfLinkIndex,pathPrefix,localInertialFrame);

View File

@@ -787,7 +787,7 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName)
#ifdef _WIN32
sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
"-threads 0 -y -b 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName);
"-threads 0 -y -b:v 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName);
//sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
// "-y -crf 0 -b:v 1500000 -an -vcodec h264 -vf vflip %s", width, height, mp4FileName);

View File

@@ -839,7 +839,7 @@ void X11OpenGLWindow::pumpMessage()
if (m_data->m_keyboardCallback)
{
#if 0
#if 1
unsigned short is_retriggered = 0;
///filter out keyboard repeat
//see http://stackoverflow.com/questions/2100654/ignore-auto-repeat-in-x11-applications
@@ -851,8 +851,8 @@ void X11OpenGLWindow::pumpMessage()
if (nev.type == KeyPress && nev.xkey.time == m_data->m_xev.xkey.time &&
nev.xkey.keycode == m_data->m_xev.xkey.keycode)
{
fprintf (stdout, "key #%ld was retriggered.\n",
(long) MyXLookupKeysym(&nev.xkey, 0));
//fprintf (stdout, "key #%ld was retriggered.\n",
// (long) MyXLookupKeysym(&nev.xkey, 0));
// delete retriggered KeyPress event
MyXNextEvent(m_data->m_dpy, & m_data->m_xev);
@@ -861,6 +861,7 @@ void X11OpenGLWindow::pumpMessage()
}
#endif
int state = 0;
if (!is_retriggered)
(*m_data->m_keyboardCallback)(keycode,state);
}

View File

@@ -16,8 +16,8 @@
#include "b3RobotSimAPI.h"
#include "../Utils/b3Clock.h"
static btScalar sGripperVerticalVelocity = -0.2f;
static btScalar sGripperClosingTargetVelocity = 0.5f;
static btScalar sGripperVerticalVelocity = 0.f;
static btScalar sGripperClosingTargetVelocity = -0.7f;
class GripperGraspExample : public CommonExampleInterface
{
@@ -209,6 +209,7 @@ public:
if ((m_options & eONE_MOTOR_GRASP)!=0)
{
m_robotSim.setNumSolverIterations(150);
{
SliderParams slider("Vertical velocity",&sGripperVerticalVelocity);
slider.m_minVal=-2;
@@ -226,9 +227,9 @@ public:
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "sphere_small.urdf";
args.m_startPosition.setValue(0, 0, .107);
args.m_startOrientation.setEulerZYX(0, 0, 0);
args.m_fileName = "dinnerware/pan_tefal.urdf";
args.m_startPosition.setValue(0, -0.2, .47);
args.m_startOrientation.setEulerZYX(SIMD_HALF_PI, 0, 0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
}
@@ -492,7 +493,7 @@ public:
int fingerJointIndices[2]={0,1};
double fingerTargetVelocities[2]={sGripperVerticalVelocity,sGripperClosingTargetVelocity
};
double maxTorqueValues[2]={50.0,50.0};
double maxTorqueValues[2]={800.0,800.0};
for (int i=0;i<2;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
@@ -550,8 +551,8 @@ public:
virtual void resetCamera()
{
float dist = 1.5;
float pitch = 12;
float yaw = -10;
float pitch = 18;
float yaw = 10;
float targetPos[3]={-0.2,0.8,0.3};
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
{

View File

@@ -478,6 +478,16 @@ void b3RobotSimAPI::setGravity(const b3Vector3& gravityAcceleration)
}
void b3RobotSimAPI::setNumSolverIterations(int numIterations)
{
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClient);
b3SharedMemoryStatusHandle statusHandle;
b3PhysicsParamSetNumSolverIterations(command, numIterations);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClient, command);
b3Assert(b3GetStatusType(statusHandle)==CMD_CLIENT_COMMAND_COMPLETED);
}
void b3RobotSimAPI::setNumSimulationSubSteps(int numSubSteps)
{
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClient);

View File

@@ -157,6 +157,7 @@ public:
void setGravity(const b3Vector3& gravityAcceleration);
void setNumSimulationSubSteps(int numSubSteps);
void setNumSolverIterations(int numIterations);
bool calculateInverseKinematics(const struct b3RobotSimInverseKinematicArgs& args, struct b3RobotSimInverseKinematicsResults& results);

View File

@@ -338,6 +338,16 @@ int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandl
return 0;
}
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_contactBreakingThreshold = contactBreakingThreshold;
command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -191,7 +191,7 @@ int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHand
int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API

View File

@@ -12,6 +12,7 @@
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "LinearMath/btHashMap.h"
#include "BulletInverseDynamics/MultiBodyTree.hpp"
#include "IKTrajectoryHelper.h"
@@ -2817,7 +2818,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD)
{
gContactBreakingThreshold = clientCmd.m_physSimParamArgs.m_contactBreakingThreshold;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE)
{
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = clientCmd.m_physSimParamArgs.m_collisionFilterMode;

View File

@@ -553,7 +553,7 @@ public:
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
b3Clock::usleep(100);
b3Clock::usleep(0);
}
}
@@ -940,6 +940,8 @@ public:
virtual void stepSimulation(float deltaTime);
virtual void updateGraphics();
void enableCommandLogging()
{
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
@@ -1342,39 +1344,8 @@ bool PhysicsServerExample::wantsTermination()
return m_wantsShutdown;
}
void PhysicsServerExample::stepSimulation(float deltaTime)
void PhysicsServerExample::updateGraphics()
{
BT_PROFILE("PhysicsServerExample::stepSimulation");
//this->m_physicsServer.processClientCommands();
for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
}
}
}
for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
}
}
}
//check if any graphics related tasks are requested
switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
@@ -1543,6 +1514,40 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
}
}
void PhysicsServerExample::stepSimulation(float deltaTime)
{
BT_PROFILE("PhysicsServerExample::stepSimulation");
//this->m_physicsServer.processClientCommands();
for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
}
}
}
for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
}
}
}
updateGraphics();

View File

@@ -313,7 +313,8 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64,
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE=128,
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256,
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
};
enum EnumLoadBunnyUpdateFlags
@@ -340,6 +341,7 @@ struct SendPhysicsSimulationParameters
bool m_allowRealTimeSimulation;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
double m_contactBreakingThreshold;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;

View File

@@ -44,16 +44,13 @@ public:
PhysicsClientSharedMemory::disconnectSharedMemory();
}
unsigned long int ms = m_clock.getTimeMilliseconds();
if (ms>20)
{
m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
} else
{
//b3Clock::usleep(100);
}
return PhysicsClientSharedMemory::processServerStatus();
if (ms>20)
{
m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
}
b3Clock::usleep(0);
return PhysicsClientSharedMemory::processServerStatus();
}

View File

@@ -135,6 +135,8 @@ public:
void SetupRenderModelForTrackedDevice( vr::TrackedDeviceIndex_t unTrackedDeviceIndex );
CGLRenderModel *FindOrLoadRenderModel( const char *pchRenderModelName );
SimpleOpenGL3App* getApp() { return m_app;}
private:
bool m_bDebugOpenGL;
bool m_bVerbose;
@@ -2260,7 +2262,7 @@ int main(int argc, char *argv[])
b3ChromeUtilsEnableProfiling();
}
#ifdef BT_USE_CUSTOM_PROFILER
b3SetCustomEnterProfileZoneFunc(dcEnter);
b3SetCustomLeaveProfileZoneFunc(dcLeave);
@@ -2287,6 +2289,11 @@ int main(int argc, char *argv[])
}
char* gVideoFileName = 0;
args.GetCmdLineArgument("mp4",gVideoFileName);
if (gVideoFileName)
pMainApplication->getApp()->dumpFramesToVideo(gVideoFileName);
//request disable VSYNC
typedef bool (APIENTRY *PFNWGLSWAPINTERVALFARPROC)(int);
PFNWGLSWAPINTERVALFARPROC wglSwapIntervalEXT = 0;

View File

@@ -0,0 +1,25 @@
import pybullet as p
import time
p.connect(p.GUI)
p.loadURDF("plane.urdf",useMaximalCoordinates=True)
p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
gravXid = p.addUserDebugParameter("gravityX",-10,10,0)
gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
gravZid = p.addUserDebugParameter("gravityZ",-10,10,-10)
p.setPhysicsEngineParameter(numSolverIterations=10)
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
for i in range (10):
for j in range (10):
for k in range (5):
ob = p.loadURDF("sphere_1cm.urdf",[0.02*i,0.02*j,0.2+0.02*k],useMaximalCoordinates=True)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(1)
while True:
gravX = p.readUserDebugParameter(gravXid)
gravY = p.readUserDebugParameter(gravYid)
gravZ = p.readUserDebugParameter(gravZid)
p.setGravity(gravX,gravY,gravZ)
time.sleep(0.01)

View File

@@ -583,14 +583,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
double splitImpulsePenetrationThreshold = -1;
int numSubSteps = -1;
int collisionFilterMode = -1;
double contactBreakingThreshold = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "physicsClientId", NULL };
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
&collisionFilterMode, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &physicsClientId))
{
return NULL;
}
@@ -610,6 +611,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{
b3PhysicsParamSetNumSolverIterations(command, numSolverIterations);
}
if (collisionFilterMode>=0)
{
b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode);
@@ -630,6 +632,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
{
b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold);
}
if (contactBreakingThreshold>=0)
{
b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold);
}
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);