implement specular, URDF non-standard specular part (see sphere2.urdf) and SDF specular support.

pybullet.changeVisualShape(obUid,linkIndex,specularColor=[R,G,B]) and Bullet C-API b3UpdateVisualShapeSpecularColor
Bug fixes in b3ResourcePath::findResourcePath resolution.
add stadium.sdf and roboschool/models_outdoor/stadium assets https://github.com/openai/roboschool/tree/master/roboschool/models_outdoor/stadium
minor fixes to obj2sdf
This commit is contained in:
Erwin Coumans
2017-06-01 12:32:44 -07:00
parent 439e8c84cf
commit 87293e835c
36 changed files with 78766 additions and 87 deletions

View File

@@ -53,11 +53,31 @@ int b3ResourcePath::getExePath(char* path, int maxPathLenInBytes)
return numBytes;
}
int b3ResourcePath::findResourcePath(const char* resourceName, char* resourcePath, int resourcePathMaxNumBytes)
struct TempResourcePath
{
char* m_path;
TempResourcePath(int len)
{
m_path = (char*)malloc(len);
memset(m_path,0,len);
}
virtual ~TempResourcePath()
{
free(m_path);
}
};
int b3ResourcePath::findResourcePath(const char* resourceName, char* resourcePathOut, int resourcePathMaxNumBytes)
{
//first find in a resource/<exeName> location, then in various folders within 'data' using b3FileUtils
char exePath[B3_MAX_EXE_PATH_LEN];
bool res = b3FileUtils::findFile(resourceName, resourcePathOut, resourcePathMaxNumBytes);
if (res)
{
return strlen(resourcePathOut);
}
int l = b3ResourcePath::getExePath(exePath, B3_MAX_EXE_PATH_LEN);
if (l)
{
@@ -66,33 +86,31 @@ int b3ResourcePath::findResourcePath(const char* resourceName, char* resourcePat
int exeNamePos = b3FileUtils::extractPath(exePath,pathToExe,B3_MAX_EXE_PATH_LEN);
if (exeNamePos)
{
sprintf(resourcePath,"%s../data/%s",pathToExe,resourceName);
TempResourcePath tmpPath(resourcePathMaxNumBytes+1024);
char* resourcePathIn = tmpPath.m_path;
sprintf(resourcePathIn,"%s../data/%s",pathToExe,resourceName);
//printf("try resource at %s\n", resourcePath);
if (b3FileUtils::findFile(resourcePath, resourcePath, resourcePathMaxNumBytes))
if (b3FileUtils::findFile(resourcePathIn, resourcePathOut, resourcePathMaxNumBytes))
{
return strlen(resourcePath);
return strlen(resourcePathOut);
}
sprintf(resourcePath,"%s../resources/%s/%s",pathToExe,&exePath[exeNamePos],resourceName);
sprintf(resourcePathIn,"%s../resources/%s/%s",pathToExe,&exePath[exeNamePos],resourceName);
//printf("try resource at %s\n", resourcePath);
if (b3FileUtils::findFile(resourcePath, resourcePath, resourcePathMaxNumBytes))
if (b3FileUtils::findFile(resourcePathIn, resourcePathOut, resourcePathMaxNumBytes))
{
return strlen(resourcePath);
return strlen(resourcePathOut);
}
sprintf(resourcePath,"%s.runfiles/google3/third_party/bullet/data/%s",exePath,resourceName);
sprintf(resourcePathIn,"%s.runfiles/google3/third_party/bullet/data/%s",exePath,resourceName);
//printf("try resource at %s\n", resourcePath);
if (b3FileUtils::findFile(resourcePath, resourcePath, resourcePathMaxNumBytes))
if (b3FileUtils::findFile(resourcePathIn, resourcePathOut, resourcePathMaxNumBytes))
{
return strlen(resourcePath);
return strlen(resourcePathOut);
}
}
}
bool res = b3FileUtils::findFile(resourceName, resourcePath, resourcePathMaxNumBytes);
if (res)
{
return strlen(resourcePath);
}
return 0;
}