Merge pull request #1337 from erwincoumans/master

tweak pybullet examples, fix a few warnings
This commit is contained in:
erwincoumans
2017-09-25 09:33:28 -07:00
committed by GitHub
8 changed files with 38 additions and 28 deletions

View File

@@ -1680,20 +1680,20 @@ B3_SHARED_API int b3GetNumUserConstraints(b3PhysicsClientHandle physClient)
return cl->getNumUserConstraints();
}
B3_SHARED_API int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* infoPtr)
B3_SHARED_API int b3GetUserConstraintInfo(b3PhysicsClientHandle physClient, int constraintUniqueId, struct b3UserConstraint* info)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3UserConstraint constraintInfo1;
b3Assert(physClient);
b3Assert(infoPtr);
b3Assert(info);
b3Assert(constraintUniqueId>=0);
if (infoPtr==0)
if (info==0)
return 0;
if (cl->getUserConstraintInfo(constraintUniqueId, constraintInfo1))
{
*infoPtr = constraintInfo1;
*info = constraintInfo1;
return 1;
}
return 0;
@@ -2049,7 +2049,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3P
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double pivotInB[3])
B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double jointChildPivot[])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
@@ -2059,12 +2059,12 @@ B3_SHARED_API int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHan
command->m_updateFlags |= USER_CONSTRAINT_CHANGE_PIVOT_IN_B;
command->m_userConstraintArguments.m_childFrame[0] = pivotInB[0];
command->m_userConstraintArguments.m_childFrame[1] = pivotInB[1];
command->m_userConstraintArguments.m_childFrame[2] = pivotInB[2];
command->m_userConstraintArguments.m_childFrame[0] = jointChildPivot[0];
command->m_userConstraintArguments.m_childFrame[1] = jointChildPivot[1];
command->m_userConstraintArguments.m_childFrame[2] = jointChildPivot[2];
return 0;
}
B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double frameOrnInB[4])
B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double jointChildFrameOrn[])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
@@ -2073,10 +2073,10 @@ B3_SHARED_API int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHan
command->m_updateFlags |= USER_CONSTRAINT_CHANGE_FRAME_ORN_IN_B;
command->m_userConstraintArguments.m_childFrame[3] = frameOrnInB[0];
command->m_userConstraintArguments.m_childFrame[4] = frameOrnInB[1];
command->m_userConstraintArguments.m_childFrame[5] = frameOrnInB[2];
command->m_userConstraintArguments.m_childFrame[6] = frameOrnInB[3];
command->m_userConstraintArguments.m_childFrame[3] = jointChildFrameOrn[0];
command->m_userConstraintArguments.m_childFrame[4] = jointChildFrameOrn[1];
command->m_userConstraintArguments.m_childFrame[5] = jointChildFrameOrn[2];
command->m_userConstraintArguments.m_childFrame[6] = jointChildFrameOrn[3];
return 0;
}

View File

@@ -104,7 +104,7 @@ B3_SHARED_API int b3GetBodyUniqueId(b3PhysicsClientHandle physClient, int serial
B3_SHARED_API int b3GetBodyInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, struct b3BodyInfo* info);
///give a unique body index (after loading the body) return the number of joints.
B3_SHARED_API int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex);
B3_SHARED_API int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId);
///given a body and joint index, return the joint information. See b3JointInfo in SharedMemoryPublic.h
B3_SHARED_API int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info);
@@ -187,8 +187,8 @@ B3_SHARED_API int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle
///request an image from a simulated camera, using a software renderer.
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]);
B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[/*16*/], float projectionMatrix[/*16*/]);
B3_SHARED_API void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height );
B3_SHARED_API void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[/*3*/]);
B3_SHARED_API void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[/*3*/]);
B3_SHARED_API void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance);
@@ -210,13 +210,13 @@ B3_SHARED_API void b3ComputeProjectionMatrixFOV(float fov, float aspect, float n
/* obsolete, please use b3ComputeViewProjectionMatrices */
B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/]);
B3_SHARED_API void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[/*3*/], const float cameraTargetPosition[/*3*/], const float cameraUp[/*3*/]);
/* obsolete, please use b3ComputeViewProjectionMatrices */
B3_SHARED_API void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[/*3*/], float distance, float yaw, float pitch, float roll, int upAxis);
/* obsolete, please use b3ComputeViewProjectionMatrices */
B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal);
B3_SHARED_API void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal);
/* obsolete, please use b3ComputeViewProjectionMatrices */
B3_SHARED_API void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal);
B3_SHARED_API void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float fov, float aspect, float nearVal, float farVal);
///request an contact point information
@@ -225,7 +225,7 @@ B3_SHARED_API void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHa
B3_SHARED_API void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
B3_SHARED_API void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA);
B3_SHARED_API void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB);
B3_SHARED_API void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo);
B3_SHARED_API void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointData);
///compute the closest points between two bodies
B3_SHARED_API b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient);
@@ -465,8 +465,8 @@ B3_SHARED_API void b3GetRaycastInformation(b3PhysicsClientHandle physClient, str
/// Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates.
B3_SHARED_API b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient);
B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[/*3*/], const double position[/*3*/], int flags);
B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flags);
B3_SHARED_API void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[/*3*/], const double position[/*3*/], int flag);
B3_SHARED_API void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[/*3*/], int flag);
///experiments of robots interacting with non-rigid objects (such as btSoftBody)
B3_SHARED_API b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient);
@@ -505,7 +505,7 @@ B3_SHARED_API int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle
B3_SHARED_API int b3StateLoggingSetLogFlags(b3SharedMemoryCommandHandle commandHandle, int logFlags);
B3_SHARED_API int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle);
B3_SHARED_API int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId);
B3_SHARED_API int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid);
B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name);

View File

@@ -2,7 +2,7 @@
#include "b3PluginManager.h"
#include "Bullet3Common/b3HashMap.h"
#include "Bullet3Common/b3ResizablePool.h"
#include "SharedMemoryPublic.h"
#include "PhysicsClientC_API.h"
#include "PhysicsDirect.h"
#include "plugins/b3PluginContext.h"

View File

@@ -16,7 +16,7 @@ class b3PluginManager
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);
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc);
};

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

@@ -441,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',