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:
@@ -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();
|
||||
visualShape.m_numIndices = visualShape.m_indices->size();
|
||||
visualShape.m_numvertices = visualShape.m_vertices->size();
|
||||
}
|
||||
printf("geometry name=%s\n",geometryName);
|
||||
//b3Printf("geometry name=%s\n",geometryName);
|
||||
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)
|
||||
{
|
||||
const char* nodeName = node->Attribute("id");
|
||||
printf("processing node %s\n", nodeName);
|
||||
//printf("processing node %s\n", nodeName);
|
||||
|
||||
|
||||
btMatrix4x4 nodeTrans;
|
||||
@@ -356,7 +356,7 @@ void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shap
|
||||
nodeTrans = nodeTrans*t;
|
||||
} 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"))
|
||||
{
|
||||
const char* geomUrl = instanceGeom->Attribute("url");
|
||||
printf("node referring to geom %s\n", geomUrl);
|
||||
//printf("node referring to geom %s\n", geomUrl);
|
||||
geomUrl++;
|
||||
int* shapeIndexPtr = name2Shape[geomUrl];
|
||||
if (shapeIndexPtr)
|
||||
{
|
||||
// int index = *shapeIndexPtr;
|
||||
printf("found geom with index %d\n", *shapeIndexPtr);
|
||||
//printf("found geom with index %d\n", *shapeIndexPtr);
|
||||
ColladaGraphicsInstance& instance = visualShapeInstances.expand();
|
||||
instance.m_shapeIndex = *shapeIndexPtr;
|
||||
instance.m_worldTransform = nodeTrans;
|
||||
} else
|
||||
{
|
||||
printf("geom not found\n");
|
||||
b3Warning("geom not found\n");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -492,7 +492,7 @@ void getUnitMeterScalingAndUpAxisTransform(TiXmlDocument& doc, btTransform& tr,
|
||||
if (unitMeter)
|
||||
{
|
||||
const char* meterText = unitMeter->Attribute("meter");
|
||||
printf("meterText=%s\n", meterText);
|
||||
//printf("meterText=%s\n", meterText);
|
||||
unitMeterScaling = atof(meterText);
|
||||
}
|
||||
|
||||
@@ -565,7 +565,7 @@ void LoadMeshFromCollada(const char* relativeFileName, btAlignedObjectArray<GLIn
|
||||
char filename[1024];
|
||||
if (!f.findFile(relativeFileName,filename,1024))
|
||||
{
|
||||
printf("File not found: %s\n", filename);
|
||||
b3Warning("File not found: %s\n", filename);
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -703,12 +703,12 @@ void LoadMeshFromColladaAssimp(const char* relativeFileName, btAlignedObjectArra
|
||||
int size=0;
|
||||
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
|
||||
{
|
||||
if (size)
|
||||
{
|
||||
printf("Open DAE file of %d bytes\n",size);
|
||||
//printf("Open DAE file of %d bytes\n",size);
|
||||
|
||||
Assimp::Importer importer;
|
||||
//importer.SetPropertyInteger(AI_CONFIG_PP_RVC_FLAGS, aiComponent_NORMALS | aiComponent_COLORS);
|
||||
|
||||
@@ -24,17 +24,17 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName)
|
||||
int size=0;
|
||||
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
|
||||
{
|
||||
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];
|
||||
int actualBytesRead = fread(memoryBuffer,1,size,file);
|
||||
if (actualBytesRead!=size)
|
||||
{
|
||||
printf("Error reading from file %s",relativeFileName);
|
||||
b3Warning("Error reading from file %s",relativeFileName);
|
||||
} else
|
||||
{
|
||||
int numTriangles = *(int*)&memoryBuffer[80];
|
||||
@@ -69,10 +69,6 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName)
|
||||
MySTLTriangle* tri = (MySTLTriangle*) curPtr;
|
||||
|
||||
GLInstanceVertex v0,v1,v2;
|
||||
if (i==numTriangles-2)
|
||||
{
|
||||
printf("!\n");
|
||||
}
|
||||
v0.uv[0] = v1.uv[0] = v2.uv[0] = 0.5;
|
||||
v0.uv[1] = v1.uv[1] = v2.uv[1] = 0.5;
|
||||
for (int v=0;v<3;v++)
|
||||
|
||||
@@ -282,7 +282,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
{
|
||||
case URDF_GEOM_CYLINDER:
|
||||
{
|
||||
printf("processing a cylinder\n");
|
||||
btAlignedObjectArray<btVector3> vertices;
|
||||
|
||||
//int numVerts = sizeof(barrel_vertices)/(9*sizeof(float));
|
||||
@@ -306,7 +305,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
}
|
||||
case URDF_GEOM_BOX:
|
||||
{
|
||||
printf("processing a box\n");
|
||||
|
||||
btVector3 extents = visual->m_geometry.m_boxSize;
|
||||
|
||||
@@ -318,7 +316,6 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
}
|
||||
case URDF_GEOM_SPHERE:
|
||||
{
|
||||
printf("processing a sphere\n");
|
||||
btScalar radius = visual->m_geometry.m_sphereRadius;
|
||||
btSphereShape* sphereShape = new btSphereShape(radius);
|
||||
convexColShape = sphereShape;
|
||||
@@ -331,14 +328,14 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
{
|
||||
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 (visual->m_geometry.m_meshFileName.length())
|
||||
{
|
||||
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];
|
||||
int fileType = 0;
|
||||
|
||||
@@ -471,7 +468,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
}
|
||||
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);
|
||||
}
|
||||
}
|
||||
@@ -482,13 +479,13 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("issue extracting mesh from COLLADA/STL file %s\n", fullPath);
|
||||
b3Warning("issue extracting mesh from COLLADA/STL file %s\n", fullPath);
|
||||
}
|
||||
|
||||
}
|
||||
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:
|
||||
{
|
||||
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:
|
||||
{
|
||||
printf("processing a cylinder\n");
|
||||
btScalar cylRadius = collision->m_geometry.m_cylinderRadius;
|
||||
btScalar cylLength = collision->m_geometry.m_cylinderLength;
|
||||
|
||||
@@ -623,7 +619,6 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
}
|
||||
case URDF_GEOM_BOX:
|
||||
{
|
||||
printf("processing a box\n");
|
||||
btVector3 extents = collision->m_geometry.m_boxSize;
|
||||
btBoxShape* boxShape = new btBoxShape(extents*0.5f);
|
||||
//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:
|
||||
{
|
||||
printf("processing a sphere\n");
|
||||
|
||||
btScalar radius = collision->m_geometry.m_sphereRadius;
|
||||
btSphereShape* sphereShape = new btSphereShape(radius);
|
||||
@@ -647,14 +641,14 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
{
|
||||
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 (collision->m_geometry.m_meshFileName.length())
|
||||
{
|
||||
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];
|
||||
int fileType = 0;
|
||||
sprintf(fullPath,"%s%s",urdfPathPrefix,filename);
|
||||
@@ -783,7 +777,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
}
|
||||
default:
|
||||
{
|
||||
printf("Unsupported file type in Collision: %s\n",fullPath);
|
||||
b3Warning("Unsupported file type in Collision: %s\n",fullPath);
|
||||
btAssert(0);
|
||||
}
|
||||
}
|
||||
@@ -791,7 +785,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
|
||||
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());
|
||||
//convex->setUserIndex(shapeId);
|
||||
btAlignedObjectArray<btVector3> convertedVerts;
|
||||
@@ -809,12 +803,12 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
shape = cylZShape;
|
||||
} else
|
||||
{
|
||||
printf("issue extracting mesh from STL file %s\n", fullPath);
|
||||
b3Warning("issue extracting mesh from STL file %s\n", fullPath);
|
||||
}
|
||||
|
||||
} 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:
|
||||
{
|
||||
printf("Error: unknown visual geometry type\n");
|
||||
b3Warning("Error: unknown visual geometry type\n");
|
||||
}
|
||||
}
|
||||
return shape;
|
||||
|
||||
@@ -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());
|
||||
logger->printMessage(msg);
|
||||
|
||||
// char msg[1024];
|
||||
// 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"))
|
||||
|
||||
Reference in New Issue
Block a user