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

@@ -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>
#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 sensorJointIndexLeft=-1;
@@ -34,21 +40,6 @@ int main(int argc, char* argv[])
double startPosX, startPosY,startPosZ;
int imuLinkIndex = -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))
{
@@ -72,10 +63,7 @@ int main(int argc, char* argv[])
ret = b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_URDF_LOADING_COMPLETED)
{
printf("Loading URDF failed, status type = %d\n",statusType);
}
ASSERT_EQ(statusType, CMD_URDF_LOADING_COMPLETED);
bodyIndex = b3GetStatusBodyIndex(statusHandle);
}
@@ -87,7 +75,7 @@ int main(int argc, char* argv[])
struct b3JointInfo 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
if (strstr(jointInfo.m_linkName,"base_link"))
{
@@ -144,15 +132,16 @@ int main(int argc, char* argv[])
b3SharedMemoryStatusHandle statusHandle;
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
statusType = b3GetStatusType(statusHandle);
ASSERT_EQ(statusType, CMD_ACTUAL_STATE_UPDATE_COMPLETED);
if (statusType == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
{
b3GetStatusActualState(statusHandle,
0, &posVarCount, &dofCount,
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));
statusType = b3GetStatusType(statusHandle);
if (statusType != CMD_STEP_FORWARD_SIMULATION_COMPLETED)
{
printf("Step Simulation failed, Unexpected status type = %d\n",statusType);
break;
}
ASSERT_EQ(statusType, CMD_STEP_FORWARD_SIMULATION_COMPLETED);
}
{
@@ -222,3 +207,43 @@ int main(int argc, char* argv[])
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