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:
@@ -16,6 +16,24 @@
|
||||
|
||||
#define MAX_PATH_LEN 1024
|
||||
|
||||
std::string StripExtension( const std::string & sPath )
|
||||
{
|
||||
for( std::string::const_reverse_iterator i = sPath.rbegin(); i != sPath.rend(); i++ )
|
||||
{
|
||||
if( *i == '.' )
|
||||
{
|
||||
return std::string( sPath.begin(), i.base() - 1 );
|
||||
}
|
||||
|
||||
// if we find a slash there is no extension
|
||||
if( *i == '\\' || *i == '/' )
|
||||
break;
|
||||
}
|
||||
|
||||
// we didn't find an extension
|
||||
return sPath;
|
||||
}
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
|
||||
@@ -23,6 +41,8 @@ int main(int argc, char* argv[])
|
||||
char* fileName;
|
||||
args.GetCmdLineArgument("fileName",fileName);
|
||||
|
||||
std::string matLibName = StripExtension(fileName);
|
||||
|
||||
printf("fileName = %s\n", fileName);
|
||||
if (fileName==0)
|
||||
{
|
||||
@@ -58,7 +78,13 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
|
||||
char objFileName[MAX_PATH_LEN];
|
||||
sprintf(objFileName,"%s/part%d.obj",materialPrefixPath,s);
|
||||
if (strlen(materialPrefixPath)>0)
|
||||
{
|
||||
sprintf(objFileName,"%s/part%d.obj",materialPrefixPath,s);
|
||||
} else
|
||||
{
|
||||
sprintf(objFileName,"part%d.obj",s);
|
||||
}
|
||||
FILE* f = fopen(objFileName,"w");
|
||||
if (f==0)
|
||||
{
|
||||
@@ -66,7 +92,15 @@ int main(int argc, char* argv[])
|
||||
exit(0);
|
||||
}
|
||||
fprintf(f,"# Exported using automatic converter by Erwin Coumans\n");
|
||||
fprintf(f,"mtllib bedroom.mtl\n");
|
||||
if (matLibName.length())
|
||||
{
|
||||
fprintf(f,"mtllib %s.mtl\n", matLibName.c_str());
|
||||
} else
|
||||
{
|
||||
fprintf(f,"mtllib bedroom.mtl\n");
|
||||
|
||||
}
|
||||
|
||||
|
||||
int faceCount = shape.mesh.indices.size();
|
||||
int vertexCount = shape.mesh.positions.size();
|
||||
|
||||
23154
data/roboschool/models_outdoor/stadium/part0.obj
Normal file
23154
data/roboschool/models_outdoor/stadium/part0.obj
Normal file
File diff suppressed because it is too large
Load Diff
16210
data/roboschool/models_outdoor/stadium/part1.obj
Normal file
16210
data/roboschool/models_outdoor/stadium/part1.obj
Normal file
File diff suppressed because it is too large
Load Diff
8350
data/roboschool/models_outdoor/stadium/part2.obj
Normal file
8350
data/roboschool/models_outdoor/stadium/part2.obj
Normal file
File diff suppressed because it is too large
Load Diff
16
data/roboschool/models_outdoor/stadium/stadium.mtl
Normal file
16
data/roboschool/models_outdoor/stadium/stadium.mtl
Normal file
@@ -0,0 +1,16 @@
|
||||
newmtl stadium_white
|
||||
Ns 96.078431
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 1.000000 1.000000 1.000000
|
||||
Ks 0.500000 0.500000 0.500000
|
||||
|
||||
newmtl stadium_grass
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.000000 0.500000 0.000000
|
||||
Ks 0.000000 0.000000 0.000000
|
||||
map_Kd stadium_grass.jpg
|
||||
|
||||
newmtl stadium_dirt
|
||||
Ka 0.000000 0.000000 0.000000
|
||||
Kd 0.600000 0.400000 0.000000
|
||||
Ks 0.000000 0.000000 0.000000
|
||||
30561
data/roboschool/models_outdoor/stadium/stadium.obj
Normal file
30561
data/roboschool/models_outdoor/stadium/stadium.obj
Normal file
File diff suppressed because it is too large
Load Diff
BIN
data/roboschool/models_outdoor/stadium/stadium_grass.jpg
Normal file
BIN
data/roboschool/models_outdoor/stadium/stadium_grass.jpg
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 1.0 MiB |
@@ -18,6 +18,7 @@
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
<specular rgb="11 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
|
||||
108
data/stadium.sdf
Normal file
108
data/stadium.sdf
Normal file
@@ -0,0 +1,108 @@
|
||||
<sdf version='1.6'>
|
||||
<world name='default'>
|
||||
<gravity>0 0 -9.8</gravity>
|
||||
<model name='roboschool/models_outdoor/stadium/part0.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d0'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part0.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>1.00000 1.00000 1.000000 1</diffuse>
|
||||
<specular>0.1 .1 .1 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<model name='roboschool/models_outdoor/stadium/part1.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d1'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='collision_1'>
|
||||
<pose frame=''>0 0 -0.5 0 0 0</pose>
|
||||
<geometry>
|
||||
|
||||
<box>
|
||||
<size>100 100 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part1.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 1 1 1</ambient>
|
||||
<diffuse>0.600000 0.400000 0.000000 1</diffuse>
|
||||
<specular>.5 .5 .5 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<model name='part2.obj'>
|
||||
<static>1</static>
|
||||
<pose frame=''>0 0 0 0 0 0</pose>
|
||||
<link name='link_d2'>
|
||||
<inertial>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>0.166667</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.166667</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>roboschool/models_outdoor/stadium/part2.obj</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>1 0 0 1</ambient>
|
||||
<diffuse>0.000000 0.500000 0.000000 1</diffuse>
|
||||
<specular>0.4 0.4 0.4 1</specular>
|
||||
<emissive>0 0 0 0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</world>
|
||||
</sdf>
|
||||
@@ -20,7 +20,7 @@
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>1 2 3</normal>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
@@ -46,7 +46,7 @@
|
||||
<cast_shadows>0</cast_shadows>
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>4 5 6</normal>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
@@ -102,6 +102,8 @@
|
||||
</inertial>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<pose frame=''>0 0 -1 0 0 0</pose>
|
||||
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
@@ -154,26 +156,7 @@
|
||||
<izz>0.166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
|
||||
@@ -39,6 +39,8 @@ struct GUIHelperInterface
|
||||
virtual void removeAllGraphicsInstances()=0;
|
||||
virtual void removeGraphicsInstance(int graphicsUid) {}
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
|
||||
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]) {}
|
||||
|
||||
|
||||
virtual Common2dCanvasInterface* get2dCanvasInterface()=0;
|
||||
|
||||
|
||||
@@ -79,6 +79,9 @@ struct CommonRenderInterface
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex)=0;
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex)=0;
|
||||
|
||||
|
||||
virtual int getTotalNumInstances() const = 0;
|
||||
|
||||
|
||||
@@ -325,7 +325,13 @@ void OpenGLGuiHelper::changeRGBAColor(int instanceUid, const double rgbaColor[4]
|
||||
m_data->m_glApp->m_renderer->writeSingleInstanceColorToCPU(rgbaColor,instanceUid);
|
||||
};
|
||||
}
|
||||
|
||||
void OpenGLGuiHelper::changeSpecularColor(int instanceUid, const double specularColor[3])
|
||||
{
|
||||
if (instanceUid>=0)
|
||||
{
|
||||
m_data->m_glApp->m_renderer->writeSingleInstanceSpecularColorToCPU(specularColor,instanceUid);
|
||||
};
|
||||
}
|
||||
int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue)
|
||||
{
|
||||
int texWidth=1024;
|
||||
|
||||
@@ -27,6 +27,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
virtual void removeAllGraphicsInstances();
|
||||
virtual void removeGraphicsInstance(int graphicsUid);
|
||||
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]);
|
||||
virtual void changeSpecularColor(int instanceUid, const double specularColor[3]);
|
||||
|
||||
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);
|
||||
|
||||
|
||||
@@ -706,7 +706,7 @@ struct BulletMJCFImporterInternalData
|
||||
if (!rgba.empty())
|
||||
{
|
||||
// "0 0.7 0.7 1"
|
||||
parseVector4(geom.m_localMaterial.m_rgbaColor, rgba);
|
||||
parseVector4(geom.m_localMaterial.m_matColor.m_rgbaColor, rgba);
|
||||
geom.m_hasLocalMaterial = true;
|
||||
geom.m_localMaterial.m_name = rgba;
|
||||
}
|
||||
|
||||
@@ -42,6 +42,7 @@ struct MyTexture
|
||||
unsigned char* textureData;
|
||||
};
|
||||
|
||||
|
||||
ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
{
|
||||
BT_DECLARE_ALIGNED_ALLOCATOR();
|
||||
@@ -51,7 +52,7 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
std::string m_sourceFile;
|
||||
char m_pathPrefix[1024];
|
||||
int m_bodyId;
|
||||
btHashMap<btHashInt,btVector4> m_linkColors;
|
||||
btHashMap<btHashInt,UrdfMaterialColor> m_linkColors;
|
||||
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
|
||||
|
||||
LinkVisualShapesConverter* m_customVisualShapesConverter;
|
||||
@@ -1094,7 +1095,10 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
|
||||
{
|
||||
UrdfMaterial *const mat = *matPtr;
|
||||
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
|
||||
m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
UrdfMaterialColor matCol;
|
||||
matCol.m_rgbaColor = mat->m_matColor.m_rgbaColor;
|
||||
matCol.m_specularColor = mat->m_matColor.m_specularColor;
|
||||
m_data->m_linkColors.insert(linkIndex,matCol);
|
||||
}
|
||||
convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures);
|
||||
|
||||
@@ -1132,10 +1136,21 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
|
||||
|
||||
bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
{
|
||||
const btVector4* rgbaPtr = m_data->m_linkColors[linkIndex];
|
||||
if (rgbaPtr)
|
||||
const UrdfMaterialColor* matColPtr = m_data->m_linkColors[linkIndex];
|
||||
if (matColPtr)
|
||||
{
|
||||
colorRGBA = *rgbaPtr;
|
||||
colorRGBA = matColPtr->m_rgbaColor;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool BulletURDFImporter::getLinkColor2(int linkIndex, UrdfMaterialColor& matCol) const
|
||||
{
|
||||
UrdfMaterialColor* matColPtr = m_data->m_linkColors[linkIndex];
|
||||
if (matColPtr)
|
||||
{
|
||||
matCol = *matColPtr;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
||||
@@ -41,6 +41,8 @@ public:
|
||||
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
virtual bool getLinkColor2(int linkIndex, UrdfMaterialColor& matCol) const;
|
||||
|
||||
virtual bool getLinkContactInfo(int urdflinkIndex, URDFLinkContactInfo& contactInfo ) const;
|
||||
|
||||
virtual bool getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const;
|
||||
|
||||
@@ -11,9 +11,17 @@ public:
|
||||
|
||||
|
||||
virtual void createRigidBodyGraphicsInstance(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, int graphicsIndex) = 0;
|
||||
virtual void createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int graphicsIndex)
|
||||
{
|
||||
createRigidBodyGraphicsInstance(linkIndex,body,colorRgba,graphicsIndex);
|
||||
}
|
||||
|
||||
///optionally create some graphical representation from a collision object, usually for visual debugging purposes.
|
||||
virtual void createCollisionObjectGraphicsInstance(int linkIndex, class btCollisionObject* col, const btVector3& colorRgba) = 0;
|
||||
virtual void createCollisionObjectGraphicsInstance2(int linkIndex, class btCollisionObject* col, const btVector4& colorRgba, const btVector3& specularColor)
|
||||
{
|
||||
createCollisionObjectGraphicsInstance(linkIndex,col,colorRgba);
|
||||
}
|
||||
|
||||
virtual class btMultiBody* allocateMultiBody(int urdfLinkIndex, int totalNumJoints,btScalar mass, const btVector3& localInertiaDiagonal, bool isFixedBase, bool canSleep) =0;
|
||||
|
||||
|
||||
@@ -194,15 +194,33 @@ void MyMultiBodyCreator::addLinkMapping(int urdfLinkIndex, int mbLinkIndex)
|
||||
|
||||
void MyMultiBodyCreator::createRigidBodyGraphicsInstance(int linkIndex, btRigidBody* body, const btVector3& colorRgba, int graphicsIndex)
|
||||
{
|
||||
|
||||
m_guiHelper->createRigidBodyGraphicsObject(body, colorRgba);
|
||||
}
|
||||
|
||||
void MyMultiBodyCreator::createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int graphicsIndex)
|
||||
{
|
||||
m_guiHelper->createRigidBodyGraphicsObject(body, colorRgba);
|
||||
int graphicsInstanceId = body->getUserIndex();
|
||||
m_guiHelper->changeSpecularColor(graphicsInstanceId,specularColor);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void MyMultiBodyCreator::createCollisionObjectGraphicsInstance(int linkIndex, class btCollisionObject* colObj, const btVector3& colorRgba)
|
||||
{
|
||||
m_guiHelper->createCollisionObjectGraphicsObject(colObj,colorRgba);
|
||||
}
|
||||
|
||||
void MyMultiBodyCreator::createCollisionObjectGraphicsInstance2(int linkIndex, class btCollisionObject* col, const btVector4& colorRgba, const btVector3& specularColor)
|
||||
{
|
||||
createCollisionObjectGraphicsInstance(linkIndex,col,colorRgba);
|
||||
int graphicsInstanceId = col->getUserIndex();
|
||||
m_guiHelper->changeSpecularColor(graphicsInstanceId,specularColor);
|
||||
|
||||
}
|
||||
|
||||
|
||||
btMultiBody* MyMultiBodyCreator::getBulletMultiBody()
|
||||
{
|
||||
return m_bulletMultiBody;
|
||||
|
||||
@@ -41,9 +41,11 @@ public:
|
||||
virtual ~MyMultiBodyCreator() {}
|
||||
|
||||
virtual void createRigidBodyGraphicsInstance(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, int graphicsIndex) ;
|
||||
virtual void createRigidBodyGraphicsInstance2(int linkIndex, class btRigidBody* body, const btVector3& colorRgba, const btVector3& specularColor, int graphicsIndex) ;
|
||||
|
||||
///optionally create some graphical representation from a collision object, usually for visual debugging purposes.
|
||||
virtual void createCollisionObjectGraphicsInstance(int linkIndex, class btCollisionObject* col, const btVector3& colorRgba);
|
||||
virtual void createCollisionObjectGraphicsInstance2(int linkIndex, class btCollisionObject* col, const btVector4& colorRgba, const btVector3& specularColor);
|
||||
|
||||
virtual class btMultiBody* allocateMultiBody(int urdfLinkIndex, int totalNumJoints,btScalar mass, const btVector3& localInertiaDiagonal, bool isFixedBase, bool canSleep);
|
||||
|
||||
|
||||
@@ -272,8 +272,15 @@ void ConvertURDF2BulletInternal(
|
||||
{
|
||||
|
||||
|
||||
btVector4 color = selectColor2();
|
||||
u2b.getLinkColor(urdfLinkIndex,color);
|
||||
UrdfMaterialColor matColor;
|
||||
btVector4 color2 = selectColor2();
|
||||
btVector3 specular(0.5,0.5,0.5);
|
||||
if (u2b.getLinkColor2(urdfLinkIndex,matColor))
|
||||
{
|
||||
color2 = matColor.m_rgbaColor;
|
||||
specular = matColor.m_specularColor;
|
||||
}
|
||||
|
||||
/*
|
||||
if (visual->material.get())
|
||||
{
|
||||
@@ -315,7 +322,7 @@ void ConvertURDF2BulletInternal(
|
||||
u2b.getLinkContactInfo(urdfLinkIndex, contactInfo);
|
||||
|
||||
processContactParameters(contactInfo, body);
|
||||
creation.createRigidBodyGraphicsInstance(urdfLinkIndex, body, color, graphicsIndex);
|
||||
creation.createRigidBodyGraphicsInstance2(urdfLinkIndex, body, color2,specular, graphicsIndex);
|
||||
cache.registerRigidBody(urdfLinkIndex, body, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame);
|
||||
|
||||
|
||||
@@ -490,9 +497,16 @@ void ConvertURDF2BulletInternal(
|
||||
}
|
||||
world1->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||
|
||||
btVector4 color = selectColor2();//(0.0,0.0,0.5);
|
||||
u2b.getLinkColor(urdfLinkIndex,color);
|
||||
creation.createCollisionObjectGraphicsInstance(urdfLinkIndex,col,color);
|
||||
btVector4 color2 = selectColor2();//(0.0,0.0,0.5);
|
||||
btVector3 specularColor(1,1,1);
|
||||
UrdfMaterialColor matCol;
|
||||
if (u2b.getLinkColor2(urdfLinkIndex,matCol))
|
||||
{
|
||||
color2 = matCol.m_rgbaColor;
|
||||
specularColor = matCol.m_specularColor;
|
||||
}
|
||||
|
||||
creation.createCollisionObjectGraphicsInstance2(urdfLinkIndex,col,color2,specularColor);
|
||||
|
||||
u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame,col, u2b.getBodyUniqueId());
|
||||
|
||||
|
||||
@@ -36,6 +36,9 @@ public:
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const { return false;}
|
||||
|
||||
virtual bool getLinkColor2(int linkIndex, struct UrdfMaterialColor& matCol) const { return false;}
|
||||
|
||||
|
||||
virtual int getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const { return 0;}
|
||||
///this API will likely change, don't override it!
|
||||
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const { return false;}
|
||||
|
||||
@@ -63,4 +63,15 @@ enum UrdfCollisionFlags
|
||||
URDF_HAS_COLLISION_MASK=4,
|
||||
};
|
||||
|
||||
struct UrdfMaterialColor
|
||||
{
|
||||
btVector4 m_rgbaColor;
|
||||
btVector3 m_specularColor;
|
||||
UrdfMaterialColor()
|
||||
:m_rgbaColor(0.8, 0.8, 0.8, 1),
|
||||
m_specularColor(0.5,0.5,0.5)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
#endif //URDF_JOINT_TYPES_H
|
||||
|
||||
@@ -100,17 +100,33 @@ bool UrdfParser::parseMaterial(UrdfMaterial& material, TiXmlElement *config, Err
|
||||
}
|
||||
|
||||
// color
|
||||
TiXmlElement *c = config->FirstChildElement("color");
|
||||
if (c)
|
||||
{
|
||||
if (c->Attribute("rgba"))
|
||||
{
|
||||
if (!parseVector4(material.m_rgbaColor,c->Attribute("rgba")))
|
||||
TiXmlElement *c = config->FirstChildElement("color");
|
||||
if (c)
|
||||
{
|
||||
if (c->Attribute("rgba"))
|
||||
{
|
||||
std::string msg = material.m_name+" has no rgba";
|
||||
logger->reportWarning(msg.c_str());
|
||||
if (!parseVector4(material.m_matColor.m_rgbaColor,c->Attribute("rgba")))
|
||||
{
|
||||
std::string msg = material.m_name+" has no rgba";
|
||||
logger->reportWarning(msg.c_str());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
// specular (non-standard)
|
||||
TiXmlElement *s = config->FirstChildElement("specular");
|
||||
if (s)
|
||||
{
|
||||
if (s->Attribute("rgb"))
|
||||
{
|
||||
if (!parseVector3(material.m_matColor.m_specularColor,s->Attribute("rgb"),logger))
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return true;
|
||||
|
||||
@@ -552,16 +568,29 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement*
|
||||
if (name_char)
|
||||
matPtr->m_name = name_char;
|
||||
model.m_materials.insert(matPtr->m_name.c_str(),matPtr);
|
||||
TiXmlElement *diffuse = mat->FirstChildElement("diffuse");
|
||||
if (diffuse) {
|
||||
std::string diffuseText = diffuse->GetText();
|
||||
btVector4 rgba(1,0,0,1);
|
||||
parseVector4(rgba,diffuseText);
|
||||
matPtr->m_rgbaColor = rgba;
|
||||
{
|
||||
TiXmlElement *diffuse = mat->FirstChildElement("diffuse");
|
||||
if (diffuse) {
|
||||
std::string diffuseText = diffuse->GetText();
|
||||
btVector4 rgba(1,0,0,1);
|
||||
parseVector4(rgba,diffuseText);
|
||||
matPtr->m_matColor.m_rgbaColor = rgba;
|
||||
|
||||
visual.m_materialName = matPtr->m_name;
|
||||
visual.m_geometry.m_hasLocalMaterial = true;
|
||||
}
|
||||
visual.m_materialName = matPtr->m_name;
|
||||
visual.m_geometry.m_hasLocalMaterial = true;
|
||||
}
|
||||
}
|
||||
{
|
||||
TiXmlElement *specular = mat->FirstChildElement("specular");
|
||||
if (specular) {
|
||||
std::string specularText = specular->GetText();
|
||||
btVector3 rgba(1,1,1);
|
||||
parseVector3(rgba,specularText,logger);
|
||||
matPtr->m_matColor.m_specularColor = rgba;
|
||||
visual.m_materialName = matPtr->m_name;
|
||||
visual.m_geometry.m_hasLocalMaterial = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -577,7 +606,8 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement*
|
||||
|
||||
TiXmlElement *t = mat->FirstChildElement("texture");
|
||||
TiXmlElement *c = mat->FirstChildElement("color");
|
||||
if (t||c)
|
||||
TiXmlElement *s = mat->FirstChildElement("specular");
|
||||
if (t||c||s)
|
||||
{
|
||||
if (parseMaterial(visual.m_geometry.m_localMaterial, mat,logger))
|
||||
{
|
||||
|
||||
@@ -17,13 +17,15 @@ struct ErrorLogger
|
||||
virtual void printMessage(const char* msg)=0;
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct UrdfMaterial
|
||||
{
|
||||
std::string m_name;
|
||||
std::string m_textureFilename;
|
||||
btVector4 m_rgbaColor; // [0]==r [1]==g [2]==b [3]==a
|
||||
UrdfMaterial():
|
||||
m_rgbaColor(0.8, 0.8, 0.8, 1)
|
||||
UrdfMaterialColor m_matColor;
|
||||
|
||||
UrdfMaterial()
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
@@ -492,6 +492,60 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int
|
||||
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
|
||||
}
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const double* specular, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
int srcIndex = pg->m_internalInstanceIndex;
|
||||
|
||||
int totalNumInstances = 0;
|
||||
|
||||
int gfxObjIndex = -1;
|
||||
|
||||
for (int i=0;i<m_graphicsInstances.size();i++)
|
||||
{
|
||||
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
|
||||
if (srcIndex<totalNumInstances)
|
||||
{
|
||||
gfxObjIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (gfxObjIndex>0)
|
||||
{
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
|
||||
}
|
||||
}
|
||||
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const float* specular, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
int srcIndex = pg->m_internalInstanceIndex;
|
||||
|
||||
int totalNumInstances = 0;
|
||||
|
||||
int gfxObjIndex = -1;
|
||||
|
||||
for (int i=0;i<m_graphicsInstances.size();i++)
|
||||
{
|
||||
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
|
||||
if (srcIndex<totalNumInstances)
|
||||
{
|
||||
gfxObjIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (gfxObjIndex>0)
|
||||
{
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
|
||||
@@ -95,6 +95,7 @@ public:
|
||||
|
||||
}
|
||||
|
||||
|
||||
virtual void readSingleInstanceTransformFromCPU(int srcIndex, float* position, float* orientation);
|
||||
|
||||
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
|
||||
@@ -102,6 +103,9 @@ public:
|
||||
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex);
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
|
||||
|
||||
@@ -39,6 +39,9 @@ public:
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex){}
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex){}
|
||||
|
||||
virtual void getCameraViewMatrix(float viewMat[16]) const;
|
||||
virtual void getCameraProjectionMatrix(float projMat[16]) const;
|
||||
virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex=-1, int vertexLayout=0)
|
||||
|
||||
@@ -2452,6 +2452,21 @@ void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, dou
|
||||
}
|
||||
}
|
||||
|
||||
void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[3])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_UPDATE_VISUAL_SHAPE);
|
||||
|
||||
if (command->m_type == CMD_UPDATE_VISUAL_SHAPE)
|
||||
{
|
||||
command->m_updateVisualShapeDataArguments.m_specularColor[0] = specularColor[0];
|
||||
command->m_updateVisualShapeDataArguments.m_specularColor[1] = specularColor[1];
|
||||
command->m_updateVisualShapeDataArguments.m_specularColor[2] = specularColor[2];
|
||||
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR;
|
||||
}
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
||||
@@ -210,6 +210,8 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
|
||||
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
|
||||
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
|
||||
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]);
|
||||
void b3UpdateVisualShapeSpecularColor(b3SharedMemoryCommandHandle commandHandle, double specularColor[3]);
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
|
||||
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
|
||||
|
||||
@@ -5664,7 +5664,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
int bodyUniqueId = clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId;
|
||||
int linkIndex = clientCmd.m_updateVisualShapeDataArguments.m_jointIndex;
|
||||
@@ -5680,7 +5679,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR)
|
||||
{
|
||||
m_data->m_guiHelper->changeSpecularColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_specularColor);
|
||||
}
|
||||
|
||||
}
|
||||
} else
|
||||
{
|
||||
@@ -5690,7 +5697,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
||||
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR)
|
||||
{
|
||||
m_data->m_guiHelper->changeSpecularColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_specularColor);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -123,6 +123,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
||||
eGUIDumpFramesToVideo,
|
||||
eGUIHelperRemoveGraphicsInstance,
|
||||
eGUIHelperChangeGraphicsInstanceRGBAColor,
|
||||
eGUIHelperChangeGraphicsInstanceSpecularColor,
|
||||
eGUIHelperSetVisualizerFlag,
|
||||
};
|
||||
|
||||
@@ -918,6 +919,19 @@ public:
|
||||
workerThreadWait();
|
||||
}
|
||||
|
||||
double m_specularColor[3];
|
||||
int m_graphicsInstanceChangeSpecular;
|
||||
virtual void changeSpecularColor(int instanceUid, const double specularColor[3])
|
||||
{
|
||||
m_graphicsInstanceChangeSpecular = instanceUid;
|
||||
m_specularColor[0] = specularColor[0];
|
||||
m_specularColor[1] = specularColor[1];
|
||||
m_specularColor[2] = specularColor[2];
|
||||
m_cs->lock();
|
||||
m_cs->setSharedParam(1,eGUIHelperChangeGraphicsInstanceSpecularColor);
|
||||
workerThreadWait();
|
||||
}
|
||||
|
||||
virtual Common2dCanvasInterface* get2dCanvasInterface()
|
||||
{
|
||||
return 0;
|
||||
@@ -1734,6 +1748,13 @@ void PhysicsServerExample::updateGraphics()
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
case eGUIHelperChangeGraphicsInstanceSpecularColor:
|
||||
{
|
||||
m_multiThreadedHelper->m_childGuiHelper->changeSpecularColor(m_multiThreadedHelper->m_graphicsInstanceChangeSpecular,m_multiThreadedHelper->m_specularColor);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
case eGUIHelperCopyCameraImageData:
|
||||
{
|
||||
|
||||
@@ -255,6 +255,7 @@ enum EnumUpdateVisualShapeData
|
||||
{
|
||||
CMD_UPDATE_VISUAL_SHAPE_TEXTURE=1,
|
||||
CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR=2,
|
||||
CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR=4,
|
||||
};
|
||||
|
||||
struct UpdateVisualShapeDataArgs
|
||||
@@ -264,6 +265,7 @@ struct UpdateVisualShapeDataArgs
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
double m_rgbaColor[4];
|
||||
double m_specularColor[3];
|
||||
};
|
||||
|
||||
struct LoadTextureArgs
|
||||
|
||||
@@ -179,10 +179,10 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
|
||||
visualShapeOut.m_dimensions[2] = 0;
|
||||
visualShapeOut.m_meshAssetFileName[0] = 0;
|
||||
if (visual->m_geometry.m_hasLocalMaterial) {
|
||||
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_rgbaColor[0];
|
||||
visualShapeOut.m_rgbaColor[1] = visual->m_geometry.m_localMaterial.m_rgbaColor[1];
|
||||
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_rgbaColor[2];
|
||||
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_rgbaColor[3];
|
||||
visualShapeOut.m_rgbaColor[0] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[0];
|
||||
visualShapeOut.m_rgbaColor[1] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[1];
|
||||
visualShapeOut.m_rgbaColor[2] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[2];
|
||||
visualShapeOut.m_rgbaColor[3] = visual->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[3];
|
||||
}
|
||||
|
||||
GLInstanceGraphicsShape* glmesh = 0;
|
||||
@@ -555,7 +555,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
{
|
||||
for (int i=0; i<4; i++)
|
||||
{
|
||||
rgbaColor[i] = (*matPtr)->m_rgbaColor[i];
|
||||
rgbaColor[i] = (*matPtr)->m_matColor.m_rgbaColor[i];
|
||||
}
|
||||
//printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]);
|
||||
//m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor);
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
@@ -4244,10 +4244,13 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
|
||||
int statusType;
|
||||
int physicsClientId = 0;
|
||||
PyObject* rgbaColorObj = 0;
|
||||
PyObject* specularColorObj = 0;
|
||||
|
||||
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOi", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &physicsClientId))
|
||||
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "specularColor", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOOi", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &specularColorObj, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -4261,6 +4264,14 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb
|
||||
{
|
||||
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
|
||||
|
||||
if (specularColorObj)
|
||||
{
|
||||
double specularColor[3] = {1,1,1};
|
||||
pybullet_internalSetVectord(specularColorObj, specularColor);
|
||||
b3UpdateVisualShapeSpecularColor(commandHandle,specularColor);
|
||||
|
||||
}
|
||||
|
||||
if (rgbaColorObj)
|
||||
{
|
||||
double rgbaColor[4] = {1,1,1,1};
|
||||
|
||||
Reference in New Issue
Block a user