print better error warning, in case the physics client/server version mismatch.
fix in b3HashString remove many unused dependencies from kuka_grasp_block_playback.py (time,math, datetime ,numpy,pylab ,sys, os, fnmatch,argparse were not used!) move block_grasp_log.bin from Bullet3/data to Bullet3/examples/pybullet/examples/data folder. PhysicsServerCommandProcessor, derive from CommandProcessorInterface to prepare for different back-end implementation
This commit is contained in:
@@ -1,7 +1,7 @@
|
||||
#ifndef PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
|
||||
#define PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
|
||||
|
||||
enum PhysicsCOmmandRenderFlags
|
||||
enum PhysicsCommandRenderFlags
|
||||
{
|
||||
COV_DISABLE_SYNC_RENDERING=1
|
||||
};
|
||||
@@ -29,4 +29,27 @@ public:
|
||||
|
||||
};
|
||||
|
||||
|
||||
class btVector3;
|
||||
|
||||
class CommandProcessorInterface : public PhysicsCommandProcessorInterface
|
||||
{
|
||||
|
||||
public:
|
||||
virtual ~CommandProcessorInterface(){}
|
||||
|
||||
virtual void syncPhysicsToGraphics()=0;
|
||||
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents)=0;
|
||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0;
|
||||
|
||||
virtual void enableCommandLogging(bool enable, const char* fileName)=0;
|
||||
virtual void replayFromLogFile(const char* fileName)=0;
|
||||
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes )=0;
|
||||
|
||||
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
|
||||
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
|
||||
virtual void removePickingConstraint()=0;
|
||||
|
||||
};
|
||||
|
||||
#endif //PHYSICS_COMMAND_PROCESSOR_INTERFACE_H
|
||||
|
||||
@@ -25,18 +25,18 @@ public:
|
||||
|
||||
//@todo(erwincoumans) Should we have shared memory commands for picking objects?
|
||||
///The pickBody method will try to pick the first body along a ray, return true if succeeds, false otherwise
|
||||
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
|
||||
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;
|
||||
virtual void removePickingConstraint()=0;
|
||||
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld){return false;}
|
||||
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld){return false;}
|
||||
virtual void removePickingConstraint(){}
|
||||
|
||||
//for physicsDebugDraw and renderScene are mainly for debugging purposes
|
||||
//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(int renderFlags)=0;
|
||||
virtual void physicsDebugDraw(int debugDrawFlags){}
|
||||
virtual void renderScene(int renderFlags){}
|
||||
|
||||
virtual void enableCommandLogging(bool enable, const char* fileName)=0;
|
||||
virtual void replayFromLogFile(const char* fileName)=0;
|
||||
virtual void enableCommandLogging(bool enable, const char* fileName){}
|
||||
virtual void replayFromLogFile(const char* fileName){}
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -15,7 +15,7 @@ struct SharedMemLines
|
||||
|
||||
|
||||
///todo: naming. Perhaps PhysicsSdkCommandprocessor?
|
||||
class PhysicsServerCommandProcessor : public PhysicsCommandProcessorInterface
|
||||
class PhysicsServerCommandProcessor : public CommandProcessorInterface
|
||||
{
|
||||
|
||||
struct PhysicsServerCommandProcessorInternalData* m_data;
|
||||
@@ -91,16 +91,16 @@ public:
|
||||
virtual void removePickingConstraint();
|
||||
|
||||
//logging /playback the shared memory commands
|
||||
void enableCommandLogging(bool enable, const char* fileName);
|
||||
void replayFromLogFile(const char* fileName);
|
||||
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||
virtual void enableCommandLogging(bool enable, const char* fileName);
|
||||
virtual void replayFromLogFile(const char* fileName);
|
||||
virtual void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||
|
||||
//logging of object states (position etc)
|
||||
void logObjectStates(btScalar timeStep);
|
||||
void processCollisionForces(btScalar timeStep);
|
||||
|
||||
void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
||||
void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
virtual void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
void applyJointDamping(int bodyUniqueId);
|
||||
|
||||
virtual void setTimeOut(double timeOutInSeconds);
|
||||
|
||||
@@ -600,7 +600,7 @@ struct ColorWidth
|
||||
|
||||
ATTRIBUTE_ALIGNED16( class )MultithreadedDebugDrawer : public btIDebugDraw
|
||||
{
|
||||
class GUIHelperInterface* m_guiHelper;
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
int m_debugMode;
|
||||
|
||||
btAlignedObjectArray< btAlignedObjectArray<unsigned int> > m_sortedIndices;
|
||||
@@ -1776,22 +1776,22 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
if (flag==COV_ENABLE_VR_TELEPORTING)
|
||||
{
|
||||
gEnableTeleporting = enable;
|
||||
gEnableTeleporting = (enable!=0);
|
||||
}
|
||||
|
||||
if (flag == COV_ENABLE_VR_PICKING)
|
||||
{
|
||||
gEnablePicking = enable;
|
||||
gEnablePicking = (enable!=0);
|
||||
}
|
||||
|
||||
if (flag ==COV_ENABLE_SYNC_RENDERING_INTERNAL)
|
||||
{
|
||||
gEnableSyncPhysicsRendering = enable;
|
||||
gEnableSyncPhysicsRendering = (enable!=0);
|
||||
}
|
||||
|
||||
if (flag == COV_ENABLE_RENDERING)
|
||||
{
|
||||
gEnableRendering = enable;
|
||||
gEnableRendering = (enable!=0);
|
||||
}
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable);
|
||||
|
||||
@@ -30,7 +30,7 @@ struct PhysicsServerSharedMemoryInternalData
|
||||
int m_sharedMemoryKey;
|
||||
bool m_areConnected[MAX_SHARED_MEMORY_BLOCKS];
|
||||
bool m_verboseOutput;
|
||||
PhysicsServerCommandProcessor* m_commandProcessor;
|
||||
CommandProcessorInterface* m_commandProcessor;
|
||||
|
||||
PhysicsServerSharedMemoryInternalData()
|
||||
:m_sharedMemory(0),
|
||||
@@ -89,7 +89,7 @@ PhysicsServerSharedMemory::PhysicsServerSharedMemory(SharedMemoryInterface* shar
|
||||
PhysicsServerSharedMemory::~PhysicsServerSharedMemory()
|
||||
{
|
||||
|
||||
m_data->m_commandProcessor->deleteDynamicsWorld();
|
||||
//m_data->m_commandProcessor->deleteDynamicsWorld();
|
||||
delete m_data->m_commandProcessor;
|
||||
|
||||
if (m_data->m_sharedMemory)
|
||||
@@ -109,11 +109,12 @@ PhysicsServerSharedMemory::~PhysicsServerSharedMemory()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void PhysicsServerSharedMemory::resetDynamicsWorld()
|
||||
/*void PhysicsServerSharedMemory::resetDynamicsWorld()
|
||||
{
|
||||
m_data->m_commandProcessor->deleteDynamicsWorld();
|
||||
m_data->m_commandProcessor ->createEmptyDynamicsWorld();
|
||||
}
|
||||
*/
|
||||
void PhysicsServerSharedMemory::setSharedMemoryKey(int key)
|
||||
{
|
||||
m_data->m_sharedMemoryKey = key;
|
||||
@@ -188,7 +189,7 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
|
||||
|
||||
void PhysicsServerSharedMemory::disconnectSharedMemory(bool deInitializeSharedMemory)
|
||||
{
|
||||
m_data->m_commandProcessor->deleteDynamicsWorld();
|
||||
//m_data->m_commandProcessor->deleteDynamicsWorld();
|
||||
|
||||
m_data->m_commandProcessor->setGuiHelper(0);
|
||||
|
||||
|
||||
@@ -48,7 +48,6 @@ public:
|
||||
void enableCommandLogging(bool enable, const char* fileName);
|
||||
void replayFromLogFile(const char* fileName);
|
||||
|
||||
void resetDynamicsWorld();
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -73,7 +73,15 @@ bool SharedMemoryCommandProcessor::connect()
|
||||
|
||||
if (m_data->m_testBlock1) {
|
||||
if (m_data->m_testBlock1->m_magicId != SHARED_MEMORY_MAGIC_NUMBER) {
|
||||
b3Error("Error: please start server before client\n");
|
||||
|
||||
if ((m_data->m_testBlock1->m_magicId < 211705023) &&
|
||||
(m_data->m_testBlock1->m_magicId >=201705023))
|
||||
{
|
||||
b3Error("Error: physics server version mismatch (expected %d got %d)\n",SHARED_MEMORY_MAGIC_NUMBER, m_data->m_testBlock1->m_magicId);
|
||||
} else
|
||||
{
|
||||
b3Error("Error connecting to shared memory: please start server before client\n");
|
||||
}
|
||||
m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey,
|
||||
SHARED_MEMORY_SIZE);
|
||||
m_data->m_testBlock1 = 0;
|
||||
|
||||
@@ -1,14 +1,6 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
from datetime import datetime
|
||||
from numpy import *
|
||||
from pylab import *
|
||||
import struct
|
||||
import sys
|
||||
import os, fnmatch
|
||||
import argparse
|
||||
from time import sleep
|
||||
|
||||
|
||||
def readLogFile(filename, verbose = True):
|
||||
f = open(filename, 'rb')
|
||||
|
||||
@@ -44,8 +44,8 @@ struct b3HashString
|
||||
|
||||
/* Fowler / Noll / Vo (FNV) Hash */
|
||||
unsigned int hash = InitialFNV;
|
||||
|
||||
for(int i = 0; m_string[i]; i++)
|
||||
int len = m_string.length();
|
||||
for(int i = 0; i<len; i++)
|
||||
{
|
||||
hash = hash ^ (m_string[i]); /* xor the low 8 bits */
|
||||
hash = hash * FNVMultiple; /* multiply by the magic number */
|
||||
|
||||
Reference in New Issue
Block a user