enable file caching, currently only for Wavefront .obj files. You can disable file caching using

pybullet.setPhysicsEngineParameter(enableFileCaching=0)
Allow VR camera tracking only using position tracking, no orientation tracking (use
pybullet.setVRCamera([posX,posY,posZ],trackObjectFlag=0 or pybullet.VR_CAMERA_TRACK_OBJECT_ORIENTATION)
This commit is contained in:
Erwin Coumans
2017-05-17 19:29:12 -07:00
parent 972660f825
commit 19295f2859
11 changed files with 153 additions and 15 deletions

View File

@@ -381,6 +381,17 @@ int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHan
}
int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_enableFileCaching= enableFileCaching;
command->m_updateFlags |= SIM_PARAM_ENABLE_FILE_CACHING ;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
@@ -1785,7 +1796,10 @@ void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandl
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
b3Assert(renderer>(1<<15));
command->m_updateFlags |= renderer;
if (renderer>(1<<15))
{
command->m_updateFlags |= renderer;
}
}
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
@@ -2727,6 +2741,15 @@ int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int o
return 0;
}
int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_SET_VR_CAMERA_STATE);
command->m_updateFlags |= VR_CAMERA_FLAG;
command->m_vrCameraStateArguments.m_trackingObjectFlag = flag;
return 0;
}
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient)

View File

@@ -215,6 +215,7 @@ int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle,
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms);
int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching);
//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
@@ -376,6 +377,7 @@ b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle
int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]);
int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]);
int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag);
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);

View File

@@ -22,6 +22,7 @@
#include "../Utils/RobotLoggingUtil.h"
#include "LinearMath/btTransform.h"
#include "../Importers/ImportMJCFDemo/BulletMJCFImporter.h"
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
#include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
#include "LinearMath/btSerializer.h"
@@ -54,6 +55,8 @@ bool gCreateDefaultRobotAssets = false;
int gInternalSimFlags = 0;
bool gResetSimulation = 0;
int gVRTrackingObjectUniqueId = -1;
int gVRTrackingObjectFlag = VR_CAMERA_TRACK_OBJECT_ORIENTATION;
btTransform gVRTrackingObjectTr = btTransform::getIdentity();
int gMaxNumCmdPer1ms = -1;//experiment: add some delay to avoid threads starving other threads
@@ -2440,6 +2443,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_profileTimingLoggingUid)
{
serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED;
b3ChromeUtilsStopTimingsAndWriteJsonFile(m_data->m_profileTimingFileName.c_str());
m_data->m_profileTimingLoggingUid = -1;
}
@@ -2482,6 +2486,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
gVRTrackingObjectUniqueId = clientCmd.m_vrCameraStateArguments.m_trackingObjectUniqueId;
}
if (clientCmd.m_updateFlags & VR_CAMERA_FLAG)
{
gVRTrackingObjectFlag = clientCmd.m_vrCameraStateArguments.m_trackingObjectFlag;
}
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true;
break;
@@ -4059,6 +4068,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = clientCmd.m_physSimParamArgs.m_defaultContactERP;
}
if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_FILE_CACHING)
{
b3EnableFileCaching(clientCmd.m_physSimParamArgs.m_enableFileCaching);
}
SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true;
@@ -6194,7 +6209,16 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(gVRTrackingObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
{
gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform();
// gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform();
if (gVRTrackingObjectUniqueId>=0)
{
gVRTrackingObjectTr.setOrigin(bodyHandle->m_multiBody->getBaseWorldTransform().getOrigin());
}
if (gVRTrackingObjectFlag&VR_CAMERA_TRACK_OBJECT_ORIENTATION)
{
gVRTrackingObjectTr.setBasis(bodyHandle->m_multiBody->getBaseWorldTransform().getBasis());
}
}
}

View File

@@ -353,6 +353,8 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
SIM_PARAM_MAX_CMD_PER_1MS = 2048,
SIM_PARAM_ENABLE_FILE_CACHING = 4096,
};
enum EnumLoadBunnyUpdateFlags
@@ -384,6 +386,7 @@ struct SendPhysicsSimulationParameters
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;
int m_enableFileCaching;
};
struct LoadBunnyArgs
@@ -675,7 +678,8 @@ enum eVRCameraEnums
{
VR_CAMERA_ROOT_POSITION=1,
VR_CAMERA_ROOT_ORIENTATION=2,
VR_CAMERA_ROOT_TRACKING_OBJECT=4
VR_CAMERA_ROOT_TRACKING_OBJECT=4,
VR_CAMERA_FLAG = 8,
};
enum eStateLoggingEnums
@@ -696,6 +700,7 @@ struct VRCameraState
double m_rootPosition[3];
double m_rootOrientation[4];
int m_trackingObjectUniqueId;
int m_trackingObjectFlag;
};

View File

@@ -320,6 +320,11 @@ enum eVRDeviceTypeEnums
VR_DEVICE_GENERIC_TRACKER=4,
};
enum EVRCameraFlags
{
VR_CAMERA_TRACK_OBJECT_ORIENTATION=1,
};
struct b3VRControllerEvent
{
int m_controllerId;//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT