turn test/SharedMemory/test.c into a gtest for CI unit testing in github

remove overly verbose printfs in importers
fix axis in r2d2.urdf
This commit is contained in:
Erwin Coumans
2016-03-15 22:47:53 -07:00
parent 005ef9d2f1
commit aa3daaa8c6
13 changed files with 189 additions and 76 deletions

View File

@@ -644,7 +644,7 @@ void bFile::preSwap()
swap(dataPtrHead, dataChunk,ignoreEndianFlag); swap(dataPtrHead, dataChunk,ignoreEndianFlag);
} else } else
{ {
printf("unknown chunk\n"); //printf("unknown chunk\n");
} }
} }

View File

@@ -224,7 +224,7 @@ void btBulletFile::parseData()
// } // }
} else } else
{ {
printf("unknown chunk\n"); //printf("unknown chunk\n");
mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)dataPtrHead); mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)dataPtrHead);
} }

View File

@@ -234,6 +234,7 @@
<joint_properties damping="0.0" friction="0.0"/> <joint_properties damping="0.0" friction="0.0"/>
</joint> </joint>
<joint name="gripper_extension" type="prismatic"> <joint name="gripper_extension" type="prismatic">
<axis xyz="0 0 1"/>
<parent link="base_link"/> <parent link="base_link"/>
<child link="gripper_pole"/> <child link="gripper_pole"/>
<limit effort="1000.0" lower="-0.38" upper="0" velocity="0.5"/> <limit effort="1000.0" lower="-0.38" upper="0" velocity="0.5"/>

View File

@@ -316,12 +316,12 @@ void readLibraryGeometries(TiXmlDocument& doc, btAlignedObjectArray<GLInstanceGr
} }
printf(" index_count =%dand vertexPositions.size=%d\n",indices.size(), vertexPositions.size()); //b3Printf(" index_count =%dand vertexPositions.size=%d\n",indices.size(), vertexPositions.size());
indexBase=visualShape.m_vertices->size(); indexBase=visualShape.m_vertices->size();
visualShape.m_numIndices = visualShape.m_indices->size(); visualShape.m_numIndices = visualShape.m_indices->size();
visualShape.m_numvertices = visualShape.m_vertices->size(); visualShape.m_numvertices = visualShape.m_vertices->size();
} }
printf("geometry name=%s\n",geometryName); //b3Printf("geometry name=%s\n",geometryName);
name2Shape.insert(geometryName,shapeIndex); name2Shape.insert(geometryName,shapeIndex);
@@ -331,7 +331,7 @@ void readLibraryGeometries(TiXmlDocument& doc, btAlignedObjectArray<GLInstanceGr
void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shape, btAlignedObjectArray<ColladaGraphicsInstance>& visualShapeInstances, const btMatrix4x4& parentTransMat) void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shape, btAlignedObjectArray<ColladaGraphicsInstance>& visualShapeInstances, const btMatrix4x4& parentTransMat)
{ {
const char* nodeName = node->Attribute("id"); const char* nodeName = node->Attribute("id");
printf("processing node %s\n", nodeName); //printf("processing node %s\n", nodeName);
btMatrix4x4 nodeTrans; btMatrix4x4 nodeTrans;
@@ -356,7 +356,7 @@ void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shap
nodeTrans = nodeTrans*t; nodeTrans = nodeTrans*t;
} else } else
{ {
printf("Error: expected 16 elements in a <matrix> element, skipping\n"); b3Warning("Error: expected 16 elements in a <matrix> element, skipping\n");
} }
} }
} }
@@ -412,19 +412,19 @@ void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shap
instanceGeom=instanceGeom->NextSiblingElement("instance_geometry")) instanceGeom=instanceGeom->NextSiblingElement("instance_geometry"))
{ {
const char* geomUrl = instanceGeom->Attribute("url"); const char* geomUrl = instanceGeom->Attribute("url");
printf("node referring to geom %s\n", geomUrl); //printf("node referring to geom %s\n", geomUrl);
geomUrl++; geomUrl++;
int* shapeIndexPtr = name2Shape[geomUrl]; int* shapeIndexPtr = name2Shape[geomUrl];
if (shapeIndexPtr) if (shapeIndexPtr)
{ {
// int index = *shapeIndexPtr; // int index = *shapeIndexPtr;
printf("found geom with index %d\n", *shapeIndexPtr); //printf("found geom with index %d\n", *shapeIndexPtr);
ColladaGraphicsInstance& instance = visualShapeInstances.expand(); ColladaGraphicsInstance& instance = visualShapeInstances.expand();
instance.m_shapeIndex = *shapeIndexPtr; instance.m_shapeIndex = *shapeIndexPtr;
instance.m_worldTransform = nodeTrans; instance.m_worldTransform = nodeTrans;
} else } else
{ {
printf("geom not found\n"); b3Warning("geom not found\n");
} }
} }
@@ -492,7 +492,7 @@ void getUnitMeterScalingAndUpAxisTransform(TiXmlDocument& doc, btTransform& tr,
if (unitMeter) if (unitMeter)
{ {
const char* meterText = unitMeter->Attribute("meter"); const char* meterText = unitMeter->Attribute("meter");
printf("meterText=%s\n", meterText); //printf("meterText=%s\n", meterText);
unitMeterScaling = atof(meterText); unitMeterScaling = atof(meterText);
} }
@@ -565,7 +565,7 @@ void LoadMeshFromCollada(const char* relativeFileName, btAlignedObjectArray<GLIn
char filename[1024]; char filename[1024];
if (!f.findFile(relativeFileName,filename,1024)) if (!f.findFile(relativeFileName,filename,1024))
{ {
printf("File not found: %s\n", filename); b3Warning("File not found: %s\n", filename);
return; return;
} }
@@ -703,12 +703,12 @@ void LoadMeshFromColladaAssimp(const char* relativeFileName, btAlignedObjectArra
int size=0; int size=0;
if (fseek(file, 0, SEEK_END) || (size = ftell(file)) == EOF || fseek(file, 0, SEEK_SET)) if (fseek(file, 0, SEEK_END) || (size = ftell(file)) == EOF || fseek(file, 0, SEEK_SET))
{ {
printf("Error: Cannot access file to determine size of %s\n", relativeFileName); b3Warning("Error: Cannot access file to determine size of %s\n", relativeFileName);
} else } else
{ {
if (size) if (size)
{ {
printf("Open DAE file of %d bytes\n",size); //printf("Open DAE file of %d bytes\n",size);
Assimp::Importer importer; Assimp::Importer importer;
//importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS, aiComponent_NORMALS | aiComponent_COLORS); //importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS, aiComponent_NORMALS | aiComponent_COLORS);

View File

@@ -24,17 +24,17 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName)
int size=0; int size=0;
if (fseek(file, 0, SEEK_END) || (size = ftell(file)) == EOF || fseek(file, 0, SEEK_SET)) if (fseek(file, 0, SEEK_END) || (size = ftell(file)) == EOF || fseek(file, 0, SEEK_SET))
{ {
printf("Error: Cannot access file to determine size of %s\n", relativeFileName); b3Warning("Error: Cannot access file to determine size of %s\n", relativeFileName);
} else } else
{ {
if (size) if (size)
{ {
printf("Open STL file of %d bytes\n",size); //b3Warning("Open STL file of %d bytes\n",size);
char* memoryBuffer = new char[size+1]; char* memoryBuffer = new char[size+1];
int actualBytesRead = fread(memoryBuffer,1,size,file); int actualBytesRead = fread(memoryBuffer,1,size,file);
if (actualBytesRead!=size) if (actualBytesRead!=size)
{ {
printf("Error reading from file %s",relativeFileName); b3Warning("Error reading from file %s",relativeFileName);
} else } else
{ {
int numTriangles = *(int*)&memoryBuffer[80]; int numTriangles = *(int*)&memoryBuffer[80];
@@ -69,10 +69,6 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName)
MySTLTriangle* tri = (MySTLTriangle*) curPtr; MySTLTriangle* tri = (MySTLTriangle*) curPtr;
GLInstanceVertex v0,v1,v2; GLInstanceVertex v0,v1,v2;
if (i==numTriangles-2)
{
printf("!\n");
}
v0.uv[0] = v1.uv[0] = v2.uv[0] = 0.5; v0.uv[0] = v1.uv[0] = v2.uv[0] = 0.5;
v0.uv[1] = v1.uv[1] = v2.uv[1] = 0.5; v0.uv[1] = v1.uv[1] = v2.uv[1] = 0.5;
for (int v=0;v<3;v++) for (int v=0;v<3;v++)

View File

@@ -282,7 +282,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
{ {
case URDF_GEOM_CYLINDER: case URDF_GEOM_CYLINDER:
{ {
printf("processing a cylinder\n");
btAlignedObjectArray<btVector3> vertices; btAlignedObjectArray<btVector3> vertices;
//int numVerts = sizeof(barrel_vertices)/(9*sizeof(float)); //int numVerts = sizeof(barrel_vertices)/(9*sizeof(float));
@@ -306,7 +305,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
} }
case URDF_GEOM_BOX: case URDF_GEOM_BOX:
{ {
printf("processing a box\n");
btVector3 extents = visual->m_geometry.m_boxSize; btVector3 extents = visual->m_geometry.m_boxSize;
@@ -318,7 +316,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
} }
case URDF_GEOM_SPHERE: case URDF_GEOM_SPHERE:
{ {
printf("processing a sphere\n");
btScalar radius = visual->m_geometry.m_sphereRadius; btScalar radius = visual->m_geometry.m_sphereRadius;
btSphereShape* sphereShape = new btSphereShape(radius); btSphereShape* sphereShape = new btSphereShape(radius);
convexColShape = sphereShape; convexColShape = sphereShape;
@@ -331,14 +328,14 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
{ {
if (visual->m_name.length()) if (visual->m_name.length())
{ {
printf("visual->name=%s\n", visual->m_name.c_str()); //b3Printf("visual->name=%s\n", visual->m_name.c_str());
} }
if (1)//visual->m_geometry) if (1)//visual->m_geometry)
{ {
if (visual->m_geometry.m_meshFileName.length()) if (visual->m_geometry.m_meshFileName.length())
{ {
const char* filename = visual->m_geometry.m_meshFileName.c_str(); const char* filename = visual->m_geometry.m_meshFileName.c_str();
printf("mesh->filename=%s\n", filename); //b3Printf("mesh->filename=%s\n", filename);
char fullPath[1024]; char fullPath[1024];
int fileType = 0; int fileType = 0;
@@ -471,7 +468,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
} }
default: default:
{ {
printf("Error: unsupported file type for Visual mesh: %s\n", fullPath); b3Warning("Error: unsupported file type for Visual mesh: %s\n", fullPath);
btAssert(0); btAssert(0);
} }
} }
@@ -482,13 +479,13 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
} }
else else
{ {
printf("issue extracting mesh from COLLADA/STL file %s\n", fullPath); b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath);
} }
} }
else else
{ {
printf("mesh geometry not found %s\n", fullPath); b3Warning("mesh geometry not found %s\n", fullPath);
} }
@@ -500,7 +497,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
} }
default: default:
{ {
printf("Error: unknown visual geometry type\n"); b3Warning("Error: unknown visual geometry type\n");
} }
} }
@@ -593,7 +590,6 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
{ {
case URDF_GEOM_CYLINDER: case URDF_GEOM_CYLINDER:
{ {
printf("processing a cylinder\n");
btScalar cylRadius = collision->m_geometry.m_cylinderRadius; btScalar cylRadius = collision->m_geometry.m_cylinderRadius;
btScalar cylLength = collision->m_geometry.m_cylinderLength; btScalar cylLength = collision->m_geometry.m_cylinderLength;
@@ -623,7 +619,6 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
} }
case URDF_GEOM_BOX: case URDF_GEOM_BOX:
{ {
printf("processing a box\n");
btVector3 extents = collision->m_geometry.m_boxSize; btVector3 extents = collision->m_geometry.m_boxSize;
btBoxShape* boxShape = new btBoxShape(extents*0.5f); btBoxShape* boxShape = new btBoxShape(extents*0.5f);
//btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5); //btConvexShape* boxShape = new btConeShapeX(extents[2]*0.5,extents[0]*0.5);
@@ -633,7 +628,6 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
} }
case URDF_GEOM_SPHERE: case URDF_GEOM_SPHERE:
{ {
printf("processing a sphere\n");
btScalar radius = collision->m_geometry.m_sphereRadius; btScalar radius = collision->m_geometry.m_sphereRadius;
btSphereShape* sphereShape = new btSphereShape(radius); btSphereShape* sphereShape = new btSphereShape(radius);
@@ -647,14 +641,14 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
{ {
if (collision->m_name.length()) if (collision->m_name.length())
{ {
printf("collision->name=%s\n",collision->m_name.c_str()); //b3Printf("collision->name=%s\n",collision->m_name.c_str());
} }
if (1) if (1)
{ {
if (collision->m_geometry.m_meshFileName.length()) if (collision->m_geometry.m_meshFileName.length())
{ {
const char* filename = collision->m_geometry.m_meshFileName.c_str(); const char* filename = collision->m_geometry.m_meshFileName.c_str();
printf("mesh->filename=%s\n",filename); //b3Printf("mesh->filename=%s\n",filename);
char fullPath[1024]; char fullPath[1024];
int fileType = 0; int fileType = 0;
sprintf(fullPath,"%s%s",urdfPathPrefix,filename); sprintf(fullPath,"%s%s",urdfPathPrefix,filename);
@@ -783,7 +777,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
} }
default: default:
{ {
printf("Unsupported file type in Collision: %s\n",fullPath); b3Warning("Unsupported file type in Collision: %s\n",fullPath);
btAssert(0); btAssert(0);
} }
} }
@@ -791,7 +785,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
if (glmesh && (glmesh->m_numvertices>0)) if (glmesh && (glmesh->m_numvertices>0))
{ {
printf("extracted %d verticed from STL file %s\n", glmesh->m_numvertices,fullPath); //b3Printf("extracted %d verticed from STL file %s\n", glmesh->m_numvertices,fullPath);
//int shapeId = m_glApp->m_instancingRenderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size()); //int shapeId = m_glApp->m_instancingRenderer->registerShape(&gvertices[0].pos[0],gvertices.size(),&indices[0],indices.size());
//convex->setUserIndex(shapeId); //convex->setUserIndex(shapeId);
btAlignedObjectArray<btVector3> convertedVerts; btAlignedObjectArray<btVector3> convertedVerts;
@@ -809,12 +803,12 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
shape = cylZShape; shape = cylZShape;
} else } else
{ {
printf("issue extracting mesh from STL file %s\n", fullPath); b3Warning("issue extracting mesh from STL file %s\n", fullPath);
} }
} else } else
{ {
printf("mesh geometry not found %s\n",fullPath); b3Warning("mesh geometry not found %s\n",fullPath);
} }
@@ -826,7 +820,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
} }
default: default:
{ {
printf("Error: unknown visual geometry type\n"); b3Warning("Error: unknown visual geometry type\n");
} }
} }
return shape; return shape;

View File

@@ -766,9 +766,10 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
} }
} }
char msg[1024];
sprintf(msg,"Num materials=%d", m_model.m_materials.size()); // char msg[1024];
logger->printMessage(msg); // sprintf(msg,"Num materials=%d", m_model.m_materials.size());
// logger->printMessage(msg);
for (TiXmlElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link")) for (TiXmlElement* link_xml = robot_xml->FirstChildElement("link"); link_xml; link_xml = link_xml->NextSiblingElement("link"))

View File

@@ -215,7 +215,7 @@ void b3BulletFile::parseData()
// } // }
} else } else
{ {
printf("unknown chunk\n"); //printf("unknown chunk\n");
mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)dataPtrHead); mLibPointers.insert(dataChunk.oldPtr, (bStructHandle*)dataPtrHead);
} }

View File

@@ -612,7 +612,7 @@ void bFile::preSwap()
swap(dataPtrHead, dataChunk,ignoreEndianFlag); swap(dataPtrHead, dataChunk,ignoreEndianFlag);
} else } else
{ {
printf("unknown chunk\n"); //printf("unknown chunk\n");
} }
} }

View File

@@ -1,6 +1,6 @@
IF(BUILD_BULLET3) IF(BUILD_BULLET3)
#SUBDIRS( TestBullet3OpenCL ) #SUBDIRS( TestBullet3OpenCL )
SUBDIRS( InverseDynamics ) SUBDIRS( InverseDynamics SharedMemory )
ENDIF(BUILD_BULLET3) ENDIF(BUILD_BULLET3)
SUBDIRS( gtest-1.7.0 collision BulletDynamics/pendulum ) SUBDIRS( gtest-1.7.0 collision BulletDynamics/pendulum )

View File

@@ -0,0 +1,73 @@
INCLUDE_DIRECTORIES(
.
../../src
../gtest-1.7.0/include
../../examples
../../examples/ThirdPartyLibs
)
#ADD_DEFINITIONS(-DGTEST_HAS_PTHREAD=1)
ADD_DEFINITIONS(-DPHYSICS_LOOP_BACK -DPHYSICS_SERVER_DIRECT -DENABLE_GTEST -D_VARIADIC_MAX=10)
LINK_LIBRARIES(
BulletFileLoader BulletWorldImporter Bullet3Common BulletDynamics BulletCollision LinearMath gtest
)
IF (NOT WIN32)
LINK_LIBRARIES( pthread )
ENDIF()
ADD_EXECUTABLE(Test_PhysicsClientServer
gtestwrap.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/PhysicsLoopBack.cpp
../../examples/SharedMemory/PhysicsLoopBack.h
../../examples/SharedMemory/PhysicsLoopBackC_API.cpp
../../examples/SharedMemory/PhysicsLoopBackC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
)
ADD_TEST(Test_PhysicsClientServer_PASS Test_PhysicsClientServer)
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
SET_TARGET_PROPERTIES(Test_PhysicsClientServer PROPERTIES DEBUG_POSTFIX "_Debug")
SET_TARGET_PROPERTIES(Test_PhysicsClientServer PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
SET_TARGET_PROPERTIES(Test_PhysicsClientServer PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)

View File

@@ -0,0 +1,23 @@
#include <gtest/gtest.h>
#include "test.c"
#include "Bullet3Common/b3Logging.h"
void myprintf(const char* bla)
{
}
int main(int argc, char **argv) {
b3SetCustomPrintfFunc(myprintf);
b3SetCustomWarningMessageFunc(myprintf);
#if _MSC_VER
_CrtSetDbgFlag ( _CRTDBG_ALLOC_MEM_DF | _CRTDBG_LEAK_CHECK_DF );
//void *testWhetherMemoryLeakDetectionWorks = malloc(1);
#endif
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

View File

@@ -22,8 +22,14 @@
#include <stdio.h> #include <stdio.h>
#ifndef ENABLE_GTEST
#include <assert.h>
#define ASSERT_EQ(a,b) assert((a)==(b));
#else
#define printf
#endif
int main(int argc, char* argv[]) void testSharedMemory(b3PhysicsClientHandle sm)
{ {
int i, dofCount , posVarCount, ret ,numJoints ; int i, dofCount , posVarCount, ret ,numJoints ;
int sensorJointIndexLeft=-1; int sensorJointIndexLeft=-1;
@@ -34,21 +40,6 @@ int main(int argc, char* argv[])
double startPosX, startPosY,startPosZ; double startPosX, startPosY,startPosZ;
int imuLinkIndex = -1; int imuLinkIndex = -1;
int bodyIndex = -1; int bodyIndex = -1;
#ifdef PHYSICS_LOOP_BACK
b3PhysicsClientHandle sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
#endif
#ifdef PHYSICS_SERVER_DIRECT
b3PhysicsClientHandle sm = b3ConnectPhysicsDirect();
#endif
#ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
b3PhysicsClientHandle sm = b3CreateInProcessPhysicsServerAndConnect(argc,argv);
#endif
#ifdef PHYSICS_SHARED_MEMORY
b3PhysicsClientHandle sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
#endif //PHYSICS_SHARED_MEMORY
if (b3CanSubmitCommand(sm)) if (b3CanSubmitCommand(sm))
{ {
@@ -72,10 +63,7 @@ int main(int argc, char* argv[])
ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_URDF_LOADING_COMPLETED) ASSERT_EQ(statusType, CMD_URDF_LOADING_COMPLETED);
{
printf("Loading URDF failed, status type = %d\n",statusType);
}
bodyIndex = b3GetStatusBodyIndex(statusHandle); bodyIndex = b3GetStatusBodyIndex(statusHandle);
} }
@@ -87,7 +75,7 @@ int main(int argc, char* argv[])
struct b3JointInfo jointInfo; struct b3JointInfo jointInfo;
b3GetJointInfo(sm,bodyIndex, i,&jointInfo); b3GetJointInfo(sm,bodyIndex, i,&jointInfo);
printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName); // printf("jointInfo[%d].m_jointName=%s\n",i,jointInfo.m_jointName);
//pick the IMU link index based on torso name //pick the IMU link index based on torso name
if (strstr(jointInfo.m_linkName,"base_link")) if (strstr(jointInfo.m_linkName,"base_link"))
{ {
@@ -144,15 +132,16 @@ int main(int argc, char* argv[])
b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryStatusHandle statusHandle;
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
ASSERT_EQ(statusType, CMD_ACTUAL_STATE_UPDATE_COMPLETED);
if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED) if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
{ {
b3GetStatusActualState(statusHandle, b3GetStatusActualState(statusHandle,
0, &posVarCount, &dofCount, 0, &posVarCount, &dofCount,
0, 0, 0, 0); 0, 0, 0, 0);
ASSERT_EQ(posVarCount,15);
ASSERT_EQ(dofCount,14);
b3Printf("posVarCount = %d\n",posVarCount);
printf("dofCount = %d\n",dofCount);
} }
} }
@@ -176,11 +165,7 @@ int main(int argc, char* argv[])
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm)); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm));
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_STEP_FORWARD_SIMULATION_COMPLETED) ASSERT_EQ(statusType, CMD_STEP_FORWARD_SIMULATION_COMPLETED);
{
printf("Step Simulation failed, Unexpected status type = %d\n",statusType);
break;
}
} }
{ {
@@ -222,3 +207,43 @@ int main(int argc, char* argv[])
b3DisconnectSharedMemory(sm); b3DisconnectSharedMemory(sm);
} }
#ifdef ENABLE_GTEST
TEST(BulletPhysicsClientServerTest, DirectConnection) {
b3PhysicsClientHandle sm = b3ConnectPhysicsDirect();
testSharedMemory(sm);
}
TEST(BulletPhysicsClientServerTest, LoopBackSharedMemory) {
b3PhysicsClientHandle sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
testSharedMemory(sm);
}
#else
int main(int argc, char* argv[])
{
#ifdef PHYSICS_LOOP_BACK
b3PhysicsClientHandle sm = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY);
#endif
#ifdef PHYSICS_SERVER_DIRECT
b3PhysicsClientHandle sm = b3ConnectPhysicsDirect();
#endif
#ifdef PHYSICS_IN_PROCESS_EXAMPLE_BROWSER
b3PhysicsClientHandle sm = b3CreateInProcessPhysicsServerAndConnect(argc,argv);
#endif
#ifdef PHYSICS_SHARED_MEMORY
b3PhysicsClientHandle sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
#endif //PHYSICS_SHARED_MEMORY
testSharedMemory(sm);
}
#endif