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:
erwincoumans
2017-05-28 17:05:18 -07:00
parent c36792c950
commit 5436b8f048
10 changed files with 59 additions and 36 deletions

View File

@@ -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;