Merge remote-tracking branch 'upstream/master'

This commit is contained in:
yunfeibai
2017-05-22 22:23:55 -07:00
57 changed files with 1379 additions and 304 deletions

View File

@@ -277,9 +277,10 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"Gripper Grasp","Grasp experiment with a gripper to improve contact model", GripperGraspExampleCreateFunc,eGRIPPER_GRASP),
ExampleEntry(1,"Two Point Grasp","Grasp experiment with two point contact to test rolling friction", GripperGraspExampleCreateFunc, eTWO_POINT_GRASP),
ExampleEntry(1,"One Motor Gripper Grasp","Grasp experiment with a gripper with one motor to test slider constraint for closed loop structure", GripperGraspExampleCreateFunc, eONE_MOTOR_GRASP),
ExampleEntry(1,"Grasp Soft Body","Grasp soft body experiment", GripperGraspExampleCreateFunc, eGRASP_SOFT_BODY),
ExampleEntry(1,"Softbody Multibody Coupling","Two way coupling between soft body and multibody experiment", GripperGraspExampleCreateFunc, eSOFTBODY_MULTIBODY_COUPLING),
#ifdef USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
ExampleEntry(1,"Grasp Soft Body","Grasp soft body experiment", GripperGraspExampleCreateFunc, eGRASP_SOFT_BODY),
ExampleEntry(1,"Softbody Multibody Coupling","Two way coupling between soft body and multibody experiment", GripperGraspExampleCreateFunc, eSOFTBODY_MULTIBODY_COUPLING),
#endif //USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
#ifdef ENABLE_LUA
ExampleEntry(1,"Lua Script", "Create the dynamics world, collision shapes and rigid bodies using Lua scripting",

View File

@@ -51,6 +51,10 @@ public:
{
}
virtual ~MyDebugDrawer()
{
}
virtual DefaultColors getDefaultColors() const
{

View File

@@ -7,7 +7,7 @@
#include "../../Utils/b3ResourcePath.h"
#include "Bullet3Common/b3FileUtils.h"
#include "../../ThirdPartyLibs/stb_image/stb_image.h"
#include "../ImportObjDemo/LoadMeshFromObj.h"
bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData)
{
B3_PROFILE("loadAndRegisterMeshFromFileInternal");
@@ -28,7 +28,8 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
std::vector<tinyobj::shape_t> shapes;
{
B3_PROFILE("tinyobj::LoadObj");
std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, pathPrefix);
//std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
}
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);

View File

@@ -1,11 +1,56 @@
#include "LoadMeshFromObj.h"
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
#include "../../OpenGLWindow/GLInstanceGraphicsShape.h"
#include <stdio.h> //fopen
#include "Bullet3Common/b3AlignedObjectArray.h"
#include <string>
#include <vector>
#include "Wavefront2GLInstanceGraphicsShape.h"
#include "Bullet3Common/b3HashMap.h"
struct CachedObjResult
{
std::string m_msg;
std::vector<tinyobj::shape_t> m_shapes;
};
static b3HashMap<b3HashString, CachedObjResult> gCachedObjResults;
static int gEnableFileCaching = 1;
void b3EnableFileCaching(int enable)
{
gEnableFileCaching = enable;
if (enable==0)
{
gCachedObjResults.clear();
}
}
std::string LoadFromCachedOrFromObj(
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath)
{
CachedObjResult* resultPtr = gCachedObjResults[filename];
if (resultPtr)
{
const CachedObjResult& result = *resultPtr;
shapes = result.m_shapes;
return result.m_msg;
}
std::string err = tinyobj::LoadObj(shapes, filename, mtl_basepath);
CachedObjResult result;
result.m_msg = err;
result.m_shapes = shapes;
if (gEnableFileCaching)
{
gCachedObjResults.insert(filename,result);
}
return err;
}
GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const char* materialPrefixPath)
{
@@ -13,7 +58,7 @@ GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const cha
std::vector<tinyobj::shape_t> shapes;
{
B3_PROFILE("tinyobj::LoadObj2");
std::string err = tinyobj::LoadObj(shapes, relativeFileName, materialPrefixPath);
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, materialPrefixPath);
}
{

View File

@@ -4,6 +4,14 @@
struct GLInstanceGraphicsShape;
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
void b3EnableFileCaching(int enable);
std::string LoadFromCachedOrFromObj(
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath);
GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const char* materialPrefixPath);

View File

@@ -634,8 +634,15 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
case UrdfGeometry::FILE_OBJ:
if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH)
{
glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), 0);
char relativeFileName[1024];
char pathPrefix[1024];
pathPrefix[0] = 0;
if (b3ResourcePath::findResourcePath(collision->m_geometry.m_meshFileName.c_str(), relativeFileName, 1024))
{
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
}
glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), pathPrefix);
}
else
{

View File

@@ -588,6 +588,10 @@ public:
) :
btDiscreteDynamicsWorldMt( dispatcher, pairCache, constraintSolver, collisionConfiguration )
{
#if USE_PARALLEL_ISLAND_SOLVER
btSimulationIslandManagerMt* islandMgr = static_cast<btSimulationIslandManagerMt*>( m_islandManager );
islandMgr->setIslandDispatchFunction( parallelIslandDispatch );
#endif //#if USE_PARALLEL_ISLAND_SOLVER
}
};
@@ -762,14 +766,7 @@ void CommonRigidBodyMTBase::createEmptyDynamicsWorld()
#endif //#if USE_PARALLEL_ISLAND_SOLVER
btDiscreteDynamicsWorld* world = new MyDiscreteDynamicsWorld( m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration );
m_dynamicsWorld = world;
#if USE_PARALLEL_ISLAND_SOLVER
if ( btSimulationIslandManagerMt* islandMgr = dynamic_cast<btSimulationIslandManagerMt*>( world->getSimulationIslandManager() ) )
{
islandMgr->setIslandDispatchFunction( parallelIslandDispatch );
m_multithreadedWorld = true;
}
#endif //#if USE_PARALLEL_ISLAND_SOLVER
m_multithreadedWorld = true;
}
else
{

View File

@@ -1621,6 +1621,11 @@ static void b3CreateLookAt(const b3Vector3& eye, const b3Vector3& center,cons
void GLInstancingRenderer::renderSceneInternal(int renderMode)
{
if (!useShadowMap)
{
renderMode = B3_DEFAULT_RENDERMODE;
}
// glEnable(GL_DEPTH_TEST);
GLint dims[4];

View File

@@ -290,6 +290,7 @@ void b3RobotSimulatorClientAPI::setGravity(const b3Vector3& gravityAcceleration)
b3Warning("Not connected");
return;
}
b3Assert(b3CanSubmitCommand(m_data->m_physicsClientHandle));
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle);
b3SharedMemoryStatusHandle statusHandle;
@@ -1142,5 +1143,5 @@ void b3RobotSimulatorClientAPI::loadBunny(double scale, double mass, double coll
b3LoadBunnySetScale(command, scale);
b3LoadBunnySetMass(command, mass);
b3LoadBunnySetCollisionMargin(command, collisionMargin);
b3SubmitClientCommand(m_data->m_physicsClientHandle, command);
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
}

View File

@@ -92,7 +92,7 @@ public:
m_robotSim.loadSDF("kiva_shelf/model.sdf",results);
}
{
m_robotSim.loadURDF("results");
m_robotSim.loadURDF("plane.urdf");
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));

View File

@@ -62,7 +62,7 @@ SET(SharedMemory_SRCS
../Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../Importers/ImportMJCFDemo/BulletMJCFImporter.h
../Utils/b3ResourcePath.cpp
../Utils/b3Clock.cpp
../Utils/b3Clock.cpp
../Utils/RobotLoggingUtil.cpp
../Utils/RobotLoggingUtil.h
../Utils/ChromeTraceUtil.cpp
@@ -75,13 +75,13 @@ SET(SharedMemory_SRCS
../Importers/ImportSTLDemo/LoadMeshFromSTL.h
../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../Importers/ImportColladaDemo/ColladaGraphicsInstance.h
../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../ThirdPartyLibs/tinyxml/tinystr.cpp
../ThirdPartyLibs/tinyxml/tinyxml.cpp
../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../ThirdPartyLibs/stb_image/stb_image.cpp
../ThirdPartyLibs/stb_image/stb_image.cpp
../MultiThreading/b3ThreadSupportInterface.cpp
../MultiThreading/b3ThreadSupportInterface.h
)
@@ -95,6 +95,10 @@ LINK_LIBRARIES(
Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath BussIK
)
IF (USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD)
LINK_LIBRARIES(BulletSoftBody)
ENDIF()
IF (WIN32)
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory
${SharedMemory_SRCS}
@@ -112,7 +116,7 @@ ELSE(WIN32)
../MultiThreading/b3PosixThreadSupport.h
main.cpp
)
ELSE(APPLE)
LINK_LIBRARIES( pthread ${DL} )
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory
@@ -152,7 +156,7 @@ LINK_LIBRARIES(
IF (WIN32)
ADD_DEFINITIONS(-DGLEW_STATIC)
LINK_LIBRARIES( ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY} )
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory_GUI
${SharedMemory_SRCS}
../StandaloneMain/main_opengl_single_example.cpp
@@ -169,23 +173,23 @@ ELSE(WIN32)
FIND_LIBRARY(COCOA NAMES Cocoa)
MESSAGE(${COCOA})
LINK_LIBRARIES(${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY})
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory_GUI
${SharedMemory_SRCS}
../StandaloneMain/main_opengl_single_example.cpp
../ExampleBrowser/OpenGLGuiHelper.cpp
../ExampleBrowser/GL_ShapeDrawer.cpp
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
../MultiThreading/b3PosixThreadSupport.cpp
../MultiThreading/b3PosixThreadSupport.h
)
ELSE(APPLE)
LINK_LIBRARIES( pthread ${DL} )
ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1")
ADD_DEFINITIONS("-DGLEW_STATIC")
ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1")
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory_GUI
${SharedMemory_SRCS}
../StandaloneMain/main_opengl_single_example.cpp
@@ -215,7 +219,7 @@ INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/headers
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/samples/shared
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/samples/shared
)
@@ -233,7 +237,7 @@ LINK_LIBRARIES(
LINK_DIRECTORIES(${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/lib/win64)
ELSE(CMAKE_CL_64)
LINK_DIRECTORIES(${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/lib/win32)
ENDIF(CMAKE_CL_64)
ENDIF(CMAKE_CL_64)
ADD_EXECUTABLE(App_PhysicsServer_SharedMemory_VR
${SharedMemory_SRCS}
../StandaloneMain/hellovr_opengl_main.cpp
@@ -250,12 +254,12 @@ LINK_LIBRARIES(
../ThirdPartyLibs/openvr/samples/shared/pathtools.cpp
../ThirdPartyLibs/openvr/samples/shared/pathtools.h
../ThirdPartyLibs/openvr/samples/shared/strtools.cpp
../ThirdPartyLibs/openvr/samples/shared/strtools.h
../ThirdPartyLibs/openvr/samples/shared/strtools.h
../ThirdPartyLibs/openvr/samples/shared/Vectors.h
../MultiThreading/b3Win32ThreadSupport.cpp
../MultiThreading/b3Win32ThreadSupport.h
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
)
)
IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
@@ -272,7 +276,7 @@ IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
COMMAND ${CMAKE_COMMAND} ARGS -E copy_if_different ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll ${CMAKE_CURRENT_BINARY_DIR}/openvr_api.dll
)
ENDIF(CMAKE_CL_64)
ADD_CUSTOM_COMMAND(
TARGET App_PhysicsServer_SharedMemory_VR
POST_BUILD

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])
@@ -2712,6 +2726,8 @@ int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, doub
command->m_vrCameraStateArguments.m_rootOrientation[0] = rootOrn[0];
command->m_vrCameraStateArguments.m_rootOrientation[1] = rootOrn[1];
command->m_vrCameraStateArguments.m_rootOrientation[2] = rootOrn[2];
command->m_vrCameraStateArguments.m_rootOrientation[3] = rootOrn[3];
return 0;
}
@@ -2725,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

@@ -122,7 +122,8 @@ protected:
{
if (m_options == eCLIENTEXAMPLE_SERVER)
{
m_physicsServer.renderScene();
int renderFlags = 0;
m_physicsServer.renderScene(renderFlags);
}
b3DebugLines debugLines;

View File

@@ -226,7 +226,7 @@ bool TcpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv
}
void TcpNetworkedPhysicsProcessor::renderScene()
void TcpNetworkedPhysicsProcessor::renderScene(int renderFlags)
{
}

View File

@@ -24,7 +24,7 @@ public:
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene();
virtual void renderScene(int renderFlags);
virtual void physicsDebugDraw(int debugDrawFlags);

View File

@@ -540,7 +540,7 @@ bool UdpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv
}
void UdpNetworkedPhysicsProcessor::renderScene()
void UdpNetworkedPhysicsProcessor::renderScene(int renderFlags)
{
}

View File

@@ -24,7 +24,7 @@ public:
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene();
virtual void renderScene(int renderFlags);
virtual void physicsDebugDraw(int debugDrawFlags);

View File

@@ -1,6 +1,11 @@
#ifndef PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
#define PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
enum PhysicsCOmmandRenderFlags
{
COV_DISABLE_SYNC_RENDERING=1
};
class PhysicsCommandProcessorInterface
{
@@ -17,7 +22,7 @@ public:
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) = 0;
virtual void renderScene() = 0;
virtual void renderScene(int renderFlags) = 0;
virtual void physicsDebugDraw(int debugDrawFlags) = 0;
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper) = 0;
virtual void setTimeOut(double timeOutInSeconds) = 0;

View File

@@ -171,7 +171,8 @@ bool PhysicsDirect::connect(struct GUIHelperInterface* guiHelper)
void PhysicsDirect::renderScene()
{
m_data->m_commandProcessor->renderScene();
int renderFlags = 0;
m_data->m_commandProcessor->renderScene(renderFlags);
}
void PhysicsDirect::debugDraw(int debugDrawMode)

View File

@@ -33,7 +33,7 @@ public:
//and for physics visualization. The idea is that physicsDebugDraw can also send wireframe
//to a physics client, over shared memory
virtual void physicsDebugDraw(int debugDrawFlags)=0;
virtual void renderScene()=0;
virtual void renderScene(int renderFlags)=0;
virtual void enableCommandLogging(bool enable, const char* fileName)=0;
virtual void replayFromLogFile(const char* fileName)=0;

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
@@ -2181,7 +2184,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
//serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId);
btMultiBody* mb = bodyHandle->m_multiBody;
btMultiBody* mb = bodyHandle? bodyHandle->m_multiBody:0;
if (mb)
{
UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
@@ -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;
@@ -2837,10 +2846,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
int actualNumBodies = 0;
for (int i=0;i<usedHandles.size();i++)
{
InteralBodyData* body = m_data->m_bodyHandles.getHandle(usedHandles[i]);
int usedHandle = usedHandles[i];
InteralBodyData* body = m_data->m_bodyHandles.getHandle(usedHandle);
if (body && (body->m_multiBody || body->m_rigidBody))
{
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[actualNumBodies++] = i;
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[actualNumBodies++] = usedHandle;
}
}
serverStatusOut.m_sdfLoadedArgs.m_numBodies = actualNumBodies;
@@ -3237,6 +3247,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
case CMD_LOAD_BUNNY:
{
serverStatusOut.m_type = CMD_UNKNOWN_COMMAND_FLUSHED;
hasStatus = true;
#ifdef USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
double scale = 0.1;
double mass = 0.1;
@@ -3277,6 +3289,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
psb->getCollisionShape()->setMargin(collisionMargin);
m_data->m_dynamicsWorld->addSoftBody(psb);
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
#endif
break;
}
@@ -4058,6 +4071,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;
@@ -4216,10 +4235,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
case CMD_RESET_SIMULATION:
{
BT_PROFILE("CMD_RESET_SIMULATION");
m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,0);
resetSimulation();
m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,1);
SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
hasStatus = true;
@@ -5062,6 +5083,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
serverCmd.m_removeObjectArgs.m_numBodies = 0;
serverCmd.m_removeObjectArgs.m_numUserConstraints = 0;
m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,0);
for (int i=0;i<clientCmd.m_removeObjectArgs.m_numBodies;i++)
{
int bodyUniqueId = clientCmd.m_removeObjectArgs.m_bodyUniqueIds[i];
@@ -5142,7 +5165,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
m_data->m_bodyHandles.freeHandle(bodyUniqueId);
}
m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,1);
hasStatus = true;
break;
@@ -5929,11 +5953,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
//static int skip=1;
void PhysicsServerCommandProcessor::renderScene()
void PhysicsServerCommandProcessor::renderScene(int renderFlags)
{
if (m_data->m_guiHelper)
{
m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld);
if (0==(renderFlags&COV_DISABLE_SYNC_RENDERING))
{
m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld);
}
m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
}
#ifdef USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
@@ -6180,6 +6207,24 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
gResetSimulation = false;
}
if (gVRTrackingObjectUniqueId >= 0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(gVRTrackingObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
{
// 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());
}
}
}
if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
{
@@ -6199,14 +6244,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
gSubStep = m_data->m_physicsDeltaTime;
}
if (gVRTrackingObjectUniqueId >= 0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(gVRTrackingObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
{
gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform();
}
}
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);

View File

@@ -78,7 +78,7 @@ public:
return false;
};
virtual void renderScene();
virtual void renderScene(int renderFlags);
virtual void physicsDebugDraw(int debugDrawFlags);
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper);

View File

@@ -25,6 +25,11 @@
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
extern btVector3 gLastPickPos;
bool gEnablePicking=true;
bool gEnableTeleporting=true;
bool gEnableRendering= true;
bool gEnableSyncPhysicsRendering= true;
bool gEnableUpdateDebugDrawLines = true;
btVector3 gVRTeleportPosLocal(0,0,0);
btQuaternion gVRTeleportOrnLocal(0,0,0,1);
@@ -181,6 +186,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIDumpFramesToVideo,
eGUIHelperRemoveGraphicsInstance,
eGUIHelperChangeGraphicsInstanceRGBAColor,
eGUIHelperSetVisualizerFlag,
};
@@ -232,7 +238,9 @@ struct MyMouseCommand
struct MotionArgs
{
MotionArgs()
:m_physicsServerPtr(0)
:
m_debugDrawFlags(0),
m_physicsServerPtr(0)
{
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
{
@@ -254,6 +262,7 @@ struct MotionArgs
b3CriticalSection* m_cs3;
b3CriticalSection* m_csGUI;
int m_debugDrawFlags;
btAlignedObjectArray<MyMouseCommand> m_mouseCommands;
@@ -452,6 +461,15 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
{
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers, keyEvents, args->m_sendKeyEvents.size());
}
{
if (gEnableUpdateDebugDrawLines)
{
args->m_csGUI->lock();
args->m_physicsServerPtr->physicsDebugDraw(args->m_debugDrawFlags);
gEnableUpdateDebugDrawLines=false;
args->m_csGUI->unlock();
}
}
deltaTimeInSeconds = 0;
}
@@ -546,6 +564,138 @@ struct UserDebugText
};
struct LineSegment
{
btVector3 m_from;
btVector3 m_to;
};
struct ColorWidth
{
btVector3FloatData m_color;
int width;
int getHash() const
{
unsigned char r = (unsigned char) m_color.m_floats[0]*255;
unsigned char g = (unsigned char) m_color.m_floats[1]*255;
unsigned char b = (unsigned char) m_color.m_floats[2]*255;
unsigned char w = width;
return r+(256*g)+(256*256*b)+(256*256*256*w);
}
bool equals(const ColorWidth& other) const
{
bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) &&
(m_color.m_floats[1] == other.m_color.m_floats[1]) &&
(m_color.m_floats[2] == other.m_color.m_floats[2]));
return same;
}
};
ATTRIBUTE_ALIGNED16( class )MultithreadedDebugDrawer : public btIDebugDraw
{
class GUIHelperInterface* m_guiHelper;
int m_debugMode;
btAlignedObjectArray< btAlignedObjectArray<unsigned int> > m_sortedIndices;
btAlignedObjectArray< btAlignedObjectArray<btVector3FloatData> > m_sortedLines;
btHashMap<ColorWidth,int> m_hashedLines;
public:
void drawDebugDrawerLines()
{
if (m_hashedLines.size())
{
for (int i=0;i<m_hashedLines.size();i++)
{
ColorWidth cw = m_hashedLines.getKeyAtIndex(i);
int index = *m_hashedLines.getAtIndex(i);
int stride = sizeof(btVector3FloatData);
const float* positions = &m_sortedLines[index][0].m_floats[0];
int numPoints = m_sortedLines[index].size();
const unsigned int* indices = &m_sortedIndices[index][0];
int numIndices = m_sortedIndices[index].size();
m_guiHelper->getRenderInterface()->drawLines(positions,cw.m_color.m_floats,numPoints, stride, indices,numIndices,cw.width);
}
}
}
MultithreadedDebugDrawer(GUIHelperInterface* guiHelper)
:m_guiHelper(guiHelper),
m_debugMode(0)
{
}
virtual ~MultithreadedDebugDrawer()
{
}
virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)
{
{
ColorWidth cw;
color.serializeFloat(cw.m_color);
cw.width = 1;
int index = -1;
int* indexPtr = m_hashedLines.find(cw);
if (indexPtr)
{
index = *indexPtr;
} else
{
index = m_sortedLines.size();
m_sortedLines.expand();
m_sortedIndices.expand();
m_hashedLines.insert(cw,index);
}
btAssert(index>=0);
if (index>=0)
{
btVector3FloatData from1,toX1;
m_sortedIndices[index].push_back(m_sortedLines[index].size());
from.serializeFloat(from1);
m_sortedLines[index].push_back(from1);
m_sortedIndices[index].push_back(m_sortedLines[index].size());
to.serializeFloat(toX1);
m_sortedLines[index].push_back(toX1);
}
}
}
virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)
{
drawLine(PointOnB,PointOnB+normalOnB*distance,color);
btVector3 ncolor(0, 0, 0);
drawLine(PointOnB, PointOnB + normalOnB*0.01, ncolor);
}
virtual void reportErrorWarning(const char* warningString)
{
}
virtual void draw3dText(const btVector3& location,const char* textString)
{
}
virtual void setDebugMode(int debugMode)
{
m_debugMode = debugMode;
}
virtual int getDebugMode() const
{
return m_debugMode;
}
virtual void clearLines()
{
m_hashedLines.clear();
m_sortedIndices.clear();
m_sortedLines.clear();
}
virtual void flushLines()
{
}
};
class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
{
@@ -555,17 +705,19 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
b3CriticalSection* m_cs2;
b3CriticalSection* m_cs3;
b3CriticalSection* m_csGUI;
public:
void setVisualizerFlag(int flag, int enable)
{
m_childGuiHelper->setVisualizerFlag(flag,enable);
}
MultithreadedDebugDrawer* m_debugDraw;
void drawDebugDrawerLines()
{
if (m_debugDraw)
{
m_debugDraw->drawDebugDrawerLines();
}
}
GUIHelperInterface* m_childGuiHelper;
int m_uidGenerator;
@@ -626,6 +778,7 @@ public:
m_cs2(0),
m_cs3(0),
m_csGUI(0),
m_debugDraw(0),
m_uidGenerator(0),
m_texels(0),
m_textureId(-1)
@@ -727,7 +880,18 @@ public:
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld)
{
m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
btAssert(rbWorld);
if (m_debugDraw)
{
delete m_debugDraw;
m_debugDraw = 0;
}
m_debugDraw = new MultithreadedDebugDrawer(this);
rbWorld->setDebugDrawer(m_debugDraw );
//m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
}
virtual int registerTexture(const unsigned char* texels, int width, int height)
@@ -759,6 +923,25 @@ public:
return m_shapeIndex;
}
int m_visualizerFlag;
int m_visualizerEnable;
void setVisualizerFlag(int flag, int enable)
{
m_visualizerFlag = flag;
m_visualizerEnable = enable;
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperSetVisualizerFlag);
workerThreadWait();
}
void setVisualizerFlagCallback(VisualizerFlagCallback callback)
{
m_childGuiHelper->setVisualizerFlagCallback(callback);
}
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
{
m_shapeIndex = shapeIndex;
@@ -998,6 +1181,10 @@ public:
}
const char* m_mp4FileName;
virtual void dumpFramesToVideo(const char* mp4FileName)
{
@@ -1558,6 +1745,38 @@ void PhysicsServerExample::updateGraphics()
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperSetVisualizerFlag:
{
int flag = m_multiThreadedHelper->m_visualizerFlag;
int enable = m_multiThreadedHelper->m_visualizerEnable;
if (flag==COV_ENABLE_VR_TELEPORTING)
{
gEnableTeleporting = enable;
}
if (flag == COV_ENABLE_VR_PICKING)
{
gEnablePicking = enable;
}
if (flag ==COV_ENABLE_SYNC_RENDERING_INTERNAL)
{
gEnableSyncPhysicsRendering = enable;
}
if (flag == COV_ENABLE_RENDERING)
{
gEnableRendering = enable;
}
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable);
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperRegisterGraphicsInstance:
{
m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
@@ -1761,32 +1980,6 @@ extern double gSubStep;
extern int gVRTrackingObjectUniqueId;
extern btTransform gVRTrackingObjectTr;
struct LineSegment
{
btVector3 m_from;
btVector3 m_to;
};
struct ColorWidth
{
btVector3FloatData m_color;
int width;
int getHash() const
{
unsigned char r = (unsigned char) m_color.m_floats[0]*255;
unsigned char g = (unsigned char) m_color.m_floats[1]*255;
unsigned char b = (unsigned char) m_color.m_floats[2]*255;
unsigned char w = width;
return r+(256*g)+(256*256*b)+(256*256*256*w);
}
bool equals(const ColorWidth& other) const
{
bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) &&
(m_color.m_floats[1] == other.m_color.m_floats[1]) &&
(m_color.m_floats[2] == other.m_color.m_floats[2]));
return same;
}
};
void PhysicsServerExample::drawUserDebugLines()
{
@@ -2013,30 +2206,41 @@ void PhysicsServerExample::renderScene()
m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->
getActiveCamera()->setVRCameraOffsetTransform(vrOffset);
}
m_physicsServer.renderScene();
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
if (gEnableRendering)
{
if (m_args[0].m_isVrControllerPicking[i] || m_args[0].m_isVrControllerDragging[i])
int renderFlags = 0;
if (!gEnableSyncPhysicsRendering)
{
btVector3 from = m_args[0].m_vrControllerPos[i];
btMatrix3x3 mat(m_args[0].m_vrControllerOrn[i]);
renderFlags|=1;//COV_DISABLE_SYNC_RENDERING;
}
m_physicsServer.renderScene(renderFlags);
}
btVector3 toX = from+mat.getColumn(0);
btVector3 toY = from+mat.getColumn(1);
btVector3 toZ = from+mat.getColumn(2);
if (gEnablePicking)
{
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
{
if (m_args[0].m_isVrControllerPicking[i] || m_args[0].m_isVrControllerDragging[i])
{
btVector3 from = m_args[0].m_vrControllerPos[i];
btMatrix3x3 mat(m_args[0].m_vrControllerOrn[i]);
int width = 2;
btVector3 toX = from+mat.getColumn(0);
btVector3 toY = from+mat.getColumn(1);
btVector3 toZ = from+mat.getColumn(2);
int width = 2;
btVector4 color;
color=btVector4(1,0,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width);
color=btVector4(0,1,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width);
color=btVector4(0,0,1,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width);
btVector4 color;
color=btVector4(1,0,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width);
color=btVector4(0,1,0,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width);
color=btVector4(0,0,1,1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width);
}
}
}
@@ -2058,9 +2262,18 @@ void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
{
drawUserDebugLines();
///debug rendering
m_physicsServer.physicsDebugDraw(debugDrawFlags);
if (gEnableRendering)
{
///debug rendering
//m_physicsServer.physicsDebugDraw(debugDrawFlags);
m_args[0].m_csGUI->lock();
//draw stuff and flush?
this->m_multiThreadedHelper->m_debugDraw->drawDebugDrawerLines();
m_args[0].m_debugDrawFlags = debugDrawFlags;
gEnableUpdateDebugDrawLines = true;
m_args[0].m_csGUI->unlock();
}
}
@@ -2132,10 +2345,12 @@ btVector3 PhysicsServerExample::getRayTo(int x,int y)
extern int gSharedMemoryKey;
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
{
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper);
PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
options.m_sharedMem,
@@ -2250,7 +2465,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
}
if (button==1)
if (button==1 && gEnableTeleporting)
{
m_args[0].m_isVrControllerTeleporting[controllerId] = true;
}
@@ -2262,7 +2477,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
else
{
if (button == 33)
if (button == 33 && gEnablePicking)
{
m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);

View File

@@ -274,9 +274,9 @@ void PhysicsServerSharedMemory::processClientCommands()
}
}
void PhysicsServerSharedMemory::renderScene()
void PhysicsServerSharedMemory::renderScene(int renderFlags)
{
m_data->m_commandProcessor->renderScene();
m_data->m_commandProcessor->renderScene(renderFlags);

View File

@@ -42,7 +42,7 @@ public:
//and for physics visualization. The idea is that physicsDebugDraw can also send wireframe
//to a physics client, over shared memory
void physicsDebugDraw(int debugDrawFlags);
void renderScene();
void renderScene(int renderFlags);
void enableCommandLogging(bool enable, const char* fileName);
void replayFromLogFile(const char* fileName);

View File

@@ -183,7 +183,7 @@ bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serv
return false;
}
void SharedMemoryCommandProcessor::renderScene()
void SharedMemoryCommandProcessor::renderScene(int renderFlags)
{
}

View File

@@ -23,7 +23,7 @@ public:
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene();
virtual void renderScene(int renderFlags);
virtual void physicsDebugDraw(int debugDrawFlags);
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper);

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
@@ -495,6 +500,11 @@ enum b3ConfigureDebugVisualizerEnum
COV_ENABLE_GUI=1,
COV_ENABLE_SHADOWS,
COV_ENABLE_WIREFRAME,
COV_ENABLE_VR_TELEPORTING,
COV_ENABLE_VR_PICKING,
COV_ENABLE_VR_RENDER_CONTROLLERS,
COV_ENABLE_RENDERING,
COV_ENABLE_SYNC_RENDERING_INTERNAL,
};
enum eCONNECT_METHOD {

View File

@@ -516,7 +516,6 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines)
if (linkPtr)
{
const btArray<UrdfVisual>* shapeArray;
bool useVisual;
int cnt = 0;
if (linkPtr->m_visualArray.size() > 0)

View File

@@ -367,6 +367,49 @@ void MyKeyboardCallback(int key, int state)
prevKeyboardCallback(key,state);
}
#include "../SharedMemory/SharedMemoryPublic.h"
extern bool useShadowMap;
bool gEnableVRRenderControllers=true;
void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable)
{
if (flag == COV_ENABLE_SHADOWS)
{
useShadowMap = enable;
}
if (flag == COV_ENABLE_GUI)
{
//there is no regular GUI here, but disable the
}
if (flag == COV_ENABLE_VR_RENDER_CONTROLLERS)
{
gEnableVRRenderControllers = enable;
}
if (flag == COV_ENABLE_WIREFRAME)
{
if (enable)
{
glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
//gDebugDrawFlags |= btIDebugDraw::DBG_DrawWireframe;
} else
{
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL);
//gDebugDrawFlags &= ~btIDebugDraw::DBG_DrawWireframe;
}
}
}
//-----------------------------------------------------------------------------
// Purpose:
//-----------------------------------------------------------------------------
@@ -418,6 +461,7 @@ bool CMainApplication::BInit()
sGuiPtr = new OpenGLGuiHelper(m_app,false);
sGuiPtr->setVisualizerFlagCallback(VRPhysicsServerVisualizerFlagCallback);
sGuiPtr->setVRMode(true);
//sGuiPtr = new DummyGUIHelper;
@@ -773,6 +817,7 @@ bool CMainApplication::HandleInput()
if (button==2)
{
//glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync
///so it can (and likely will) cause crashes
///add a special debug drawer that deals with this
@@ -810,7 +855,6 @@ bool CMainApplication::HandleInput()
if (button==2)
{
gDebugDrawFlags = 0;
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL);
}
sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn);
@@ -1379,6 +1423,8 @@ extern int gGraspingController;
void CMainApplication::DrawControllers()
{
// don't draw controllers if somebody else has input focus
if( m_pHMD->IsInputFocusCapturedByAnotherProcess() )
return;
@@ -1866,39 +1912,42 @@ void CMainApplication::RenderScene( vr::Hmd_Eye nEye )
bool bIsInputCapturedByAnotherProcess = m_pHMD->IsInputFocusCapturedByAnotherProcess();
if( !bIsInputCapturedByAnotherProcess )
if (gEnableVRRenderControllers)
{
// draw the controller axis lines
glUseProgram( m_unControllerTransformProgramID );
glUniformMatrix4fv( m_nControllerMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() );
glBindVertexArray( m_unControllerVAO );
glDrawArrays( GL_LINES, 0, m_uiControllerVertcount );
glBindVertexArray( 0 );
if( !bIsInputCapturedByAnotherProcess )
{
// draw the controller axis lines
glUseProgram( m_unControllerTransformProgramID );
glUniformMatrix4fv( m_nControllerMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() );
glBindVertexArray( m_unControllerVAO );
glDrawArrays( GL_LINES, 0, m_uiControllerVertcount );
glBindVertexArray( 0 );
}
// ----- Render Model rendering -----
glUseProgram( m_unRenderModelProgramID );
for( uint32_t unTrackedDevice = 0; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ )
{
if( !m_rTrackedDeviceToRenderModel[ unTrackedDevice ] || !m_rbShowTrackedDevice[ unTrackedDevice ] )
continue;
const vr::TrackedDevicePose_t & pose = m_rTrackedDevicePose[ unTrackedDevice ];
if( !pose.bPoseIsValid )
continue;
if( bIsInputCapturedByAnotherProcess && m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) == vr::TrackedDeviceClass_Controller )
continue;
const Matrix4 & matDeviceToTracking = m_rmat4DevicePose[ unTrackedDevice ];
Matrix4 matMVP = GetCurrentViewProjectionMatrix( nEye ) * matDeviceToTracking;
glUniformMatrix4fv( m_nRenderModelMatrixLocation, 1, GL_FALSE, matMVP.get() );
m_rTrackedDeviceToRenderModel[ unTrackedDevice ]->Draw();
}
}
// ----- Render Model rendering -----
glUseProgram( m_unRenderModelProgramID );
for( uint32_t unTrackedDevice = 0; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ )
{
if( !m_rTrackedDeviceToRenderModel[ unTrackedDevice ] || !m_rbShowTrackedDevice[ unTrackedDevice ] )
continue;
const vr::TrackedDevicePose_t & pose = m_rTrackedDevicePose[ unTrackedDevice ];
if( !pose.bPoseIsValid )
continue;
if( bIsInputCapturedByAnotherProcess && m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) == vr::TrackedDeviceClass_Controller )
continue;
const Matrix4 & matDeviceToTracking = m_rmat4DevicePose[ unTrackedDevice ];
Matrix4 matMVP = GetCurrentViewProjectionMatrix( nEye ) * matDeviceToTracking;
glUniformMatrix4fv( m_nRenderModelMatrixLocation, 1, GL_FALSE, matMVP.get() );
m_rTrackedDeviceToRenderModel[ unTrackedDevice ]->Draw();
}
glUseProgram( 0 );
glUseProgram( 0 );
}

View File

@@ -560,9 +560,12 @@ LoadObj(
int maxchars = 8192; // Alloc enough size.
std::vector<char> buf(maxchars); // Alloc enough size.
std::string linebuf;
linebuf.reserve(maxchars);
while (ifs.peek() != -1) {
std::string linebuf;
linebuf.resize(0);
safeGetline(ifs,linebuf);
// Trim newline '\r\n' or '\r'

View File

@@ -0,0 +1,37 @@
import pybullet as p
import time
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
cid = p.connect(p.GUI)
p.resetSimulation()
useRealTime = 0
p.setRealTimeSimulation(useRealTime)
p.setGravity(0,0,0)
p.loadURDF("plane.urdf")
obUids = p.loadMJCF("mjcf/humanoid_fixed.xml")
human = obUids[0]
for i in range (p.getNumJoints(human)):
p.setJointMotorControl2(human,i,p.POSITION_CONTROL,targetPosition=0,force=50)
kneeAngleTargetId = p.addUserDebugParameter("kneeAngle",-4,4,-1)
maxForceId = p.addUserDebugParameter("maxForce",0,100,10)
kneeJointIndex=11
while (1):
time.sleep(0.01)
kneeAngleTarget = p.readUserDebugParameter(kneeAngleTargetId)
maxForce = p.readUserDebugParameter(maxForceId)
p.setJointMotorControl2(human,kneeJointIndex,p.POSITION_CONTROL,targetPosition=kneeAngleTarget,force=maxForce)
if (useRealTime==0):
p.stepSimulation()

View File

@@ -1,21 +0,0 @@
"""An actor network."""
import tensorflow as tf
import sonnet as snt
class ActorNetwork(snt.AbstractModule):
"""An actor network as a sonnet Module."""
def __init__(self, layer_sizes, action_size, name='target_actor'):
super(ActorNetwork, self).__init__(name=name)
self._layer_sizes = layer_sizes
self._action_size = action_size
def _build(self, inputs):
state = inputs
for output_size in self._layer_sizes:
state = snt.Linear(output_size)(state)
state = tf.nn.relu(state)
action = tf.tanh(
snt.Linear(self._action_size, name='action')(state))
return action

View File

@@ -1,46 +0,0 @@
"""Loads a DDPG agent without too much external dependencies
"""
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
import os
import collections
import numpy as np
import tensorflow as tf
import sonnet as snt
from agents import actor_net
class SimpleAgent():
def __init__(
self,
session,
ckpt_path,
actor_layer_size,
observation_size=(31,),
action_size=8,
):
self._ckpt_path = ckpt_path
self._actor_layer_size = actor_layer_size
self._observation_size = observation_size
self._action_size = action_size
self._session = session
self._build()
def _build(self):
self._agent_net = actor_net.ActorNetwork(self._actor_layer_size, self._action_size)
self._obs = tf.placeholder(tf.float32, (31,))
with tf.name_scope('Act'):
batch_obs = snt.nest.pack_iterable_as(self._obs,
snt.nest.map(lambda x: tf.expand_dims(x, 0),
snt.nest.flatten_iterable(self._obs)))
self._action = self._agent_net(batch_obs)
saver = tf.train.Saver()
saver.restore(
sess=self._session,
save_path=self._ckpt_path)
def __call__(self, observation):
out_action = self._session.run(self._action, feed_dict={self._obs: observation})
return out_action[0]

View File

@@ -0,0 +1,36 @@
"""Loads a DDPG agent without too much external dependencies
"""
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
import os
import collections
import numpy as np
import tensorflow as tf
import pdb
class SimplerAgent():
def __init__(
self,
session,
ckpt_path,
observation_dim=31
):
self._ckpt_path = ckpt_path
self._session = session
self._observation_dim = observation_dim
self._build()
def _build(self):
saver = tf.train.import_meta_graph(self._ckpt_path + '.meta')
saver.restore(
sess=self._session,
save_path=self._ckpt_path)
self._action = tf.get_collection('action_op')[0]
self._obs = tf.get_collection('observation_placeholder')[0]
def __call__(self, observation):
feed_dict={self._obs: observation}
out_action = self._session.run(self._action, feed_dict=feed_dict)
return out_action[0]

View File

@@ -1,2 +1,2 @@
model_checkpoint_path: "/cns/ij-d/home/jietan/persistent/minitaur/minitaur_vizier_3_153645653/Bullet/MinitaurSimEnv/28158/0003600000/agent/tf_graph_data/tf_graph_data.ckpt"
all_model_checkpoint_paths: "/cns/ij-d/home/jietan/persistent/minitaur/minitaur_vizier_3_153645653/Bullet/MinitaurSimEnv/28158/0003600000/agent/tf_graph_data/tf_graph_data.ckpt"
model_checkpoint_path: "tf_graph_data_converted.ckpt-0"
all_model_checkpoint_paths: "tf_graph_data_converted.ckpt-0"

View File

@@ -10,7 +10,7 @@ import numpy as np
import tensorflow as tf
from envs.bullet.minitaurGymEnv import MinitaurGymEnv
from agents import simpleAgent
from agents import simplerAgent
def testSinePolicy():
"""Tests sine policy
@@ -53,17 +53,14 @@ def testDDPGPolicy():
environment = MinitaurGymEnv(render=True)
sum_reward = 0
steps = 1000
ckpt_path = 'data/agent/tf_graph_data/tf_graph_data.ckpt'
ckpt_path = 'data/agent/tf_graph_data/tf_graph_data_converted.ckpt-0'
observation_shape = (31,)
action_size = 8
actor_layer_sizes = (100, 181)
n_steps = 0
tf.reset_default_graph()
with tf.Session() as session:
agent = simpleAgent.SimpleAgent(session, ckpt_path,
actor_layer_sizes,
observation_size=observation_shape,
action_size=action_size)
agent = simplerAgent.SimplerAgent(session, ckpt_path)
state = environment.reset()
action = agent(state)
for _ in range(steps):

View File

@@ -95,6 +95,9 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16])
int i, len;
PyObject* seq;
if (objMat==NULL)
return 0;
seq = PySequence_Fast(objMat, "expected a sequence");
if (seq)
{
@@ -123,6 +126,7 @@ static int pybullet_internalSetVector(PyObject* objVec, float vector[3])
{
int i, len;
PyObject* seq = 0;
if (objVec == NULL)
return 0;
@@ -720,13 +724,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
int collisionFilterMode = -1;
double contactBreakingThreshold = -1;
int maxNumCmdPer1ms = -2;
int enableFileCaching = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "physicsClientId", NULL};
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &physicsClientId))
{
return NULL;
}
@@ -777,6 +783,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
b3PhysicsParamSetMaxNumCommandsPer1ms(command, maxNumCmdPer1ms);
}
if (enableFileCaching>=0)
{
b3PhysicsParamSetEnableFileCaching(command, enableFileCaching);
}
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
@@ -3699,11 +3710,12 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
PyObject* rootPosObj = 0;
PyObject* rootOrnObj = 0;
int trackObjectUid = -2;
int trackObjectFlag = -1;
double rootPos[3];
double rootOrn[4];
static char* kwlist[] = {"rootPosition", "rootOrientation", "trackObject", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|OOii", kwlist, &rootPosObj, &rootOrnObj, &trackObjectUid, &physicsClientId))
static char* kwlist[] = {"rootPosition", "rootOrientation", "trackObject", "trackObjectFlag","physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|OOiii", kwlist, &rootPosObj, &rootOrnObj, &trackObjectUid,&trackObjectFlag, &physicsClientId))
{
return NULL;
}
@@ -3730,6 +3742,11 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
b3SetVRCameraTrackingObject(commandHandle, trackObjectUid);
}
if (trackObjectFlag>=-1)
{
b3SetVRCameraTrackingObjectFlag(commandHandle, trackObjectFlag);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
@@ -4543,7 +4560,7 @@ static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject*
b3PhysicsClientHandle sm = 0;
int numJoints = -1;
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "enableSensor", "physicsClientId"};
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "enableSensor", "physicsClientId",NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &jointIndex, &enableSensor, &physicsClientId))
{
@@ -4755,12 +4772,13 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
float projectionMatrix[16];
float lightDir[3];
float lightColor[3];
float lightDist = 10.0;
int hasShadow = 0;
float lightAmbientCoeff = 0.6;
float lightDiffuseCoeff = 0.35;
float lightSpecularCoeff = 0.05;
int renderer = 0;
float lightDist = -1;
int hasShadow = -1;
float lightAmbientCoeff = -1;
float lightDiffuseCoeff = -1;
float lightSpecularCoeff = -1;
int renderer = -1;
// inialize cmd
b3SharedMemoryCommandHandle command;
int physicsClientId = 0;
@@ -4783,12 +4801,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
b3RequestCameraImageSetPixelResolution(command, width, height);
// set camera matrices only if set matrix function succeeds
if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && (pybullet_internalSetMatrix(objProjMat, projectionMatrix)))
if (objViewMat && objProjMat && pybullet_internalSetMatrix(objViewMat, viewMatrix) && (pybullet_internalSetMatrix(objProjMat, projectionMatrix)))
{
b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix);
}
//set light direction only if function succeeds
if (pybullet_internalSetVector(lightDirObj, lightDir))
if (lightDirObj && pybullet_internalSetVector(lightDirObj, lightDir))
{
b3RequestCameraImageSetLightDirection(command, lightDir);
}
@@ -4797,16 +4815,34 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
{
b3RequestCameraImageSetLightColor(command, lightColor);
}
if (lightDist>=0)
{
b3RequestCameraImageSetLightDistance(command, lightDist);
}
b3RequestCameraImageSetLightDistance(command, lightDist);
if (hasShadow>=0)
{
b3RequestCameraImageSetShadow(command, hasShadow);
}
if (lightAmbientCoeff>=0)
{
b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff);
}
if (lightDiffuseCoeff>=0)
{
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
}
b3RequestCameraImageSetShadow(command, hasShadow);
if (lightSpecularCoeff>=0)
{
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
}
b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff);
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
if (renderer>=0)
{
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
}
//PyErr_Clear();
if (b3CanSubmitCommand(sm))
{
@@ -6332,6 +6368,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "VR_DEVICE_HMD", VR_DEVICE_HMD);
PyModule_AddIntConstant(m, "VR_DEVICE_GENERIC_TRACKER", VR_DEVICE_GENERIC_TRACKER);
PyModule_AddIntConstant(m, "VR_CAMERA_TRACK_OBJECT_ORIENTATION", VR_CAMERA_TRACK_OBJECT_ORIENTATION);
PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown);
PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered);
PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased);
@@ -6346,6 +6384,11 @@ initpybullet(void)
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);
PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME);
PyModule_AddIntConstant(m, "COV_ENABLE_VR_PICKING", COV_ENABLE_VR_PICKING);
PyModule_AddIntConstant(m, "COV_ENABLE_VR_TELEPORTING", COV_ENABLE_VR_TELEPORTING);
PyModule_AddIntConstant(m, "COV_ENABLE_RENDERING", COV_ENABLE_RENDERING);
PyModule_AddIntConstant(m, "COV_ENABLE_VR_RENDER_CONTROLLERS", COV_ENABLE_VR_RENDER_CONTROLLERS);
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);