b3CreateBoxCommandSetColorRGBA: allow to specify color when creating bodies through shared memory API
Parse and use colors from URDF file (single rgba color per link, not per visual) Rename btMultiBody 'stepVelocities' to 'computeAccelerationsArticulatedBodyAlgorithmMultiDof' btHashMap, add const Value* operator[] remove a few more obsolete btMultiBody methods (on the non-multi-dof path) fix spelling typo in fillConstraintJacobianMultiDof (fil -> fill) Add mention to Jakub Stepien for his work on btMultiBody
This commit is contained in:
@@ -37,7 +37,7 @@ struct BulletURDFInternalData
|
||||
UrdfParser m_urdfParser;
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
char m_pathPrefix[1024];
|
||||
|
||||
btHashMap<btHashInt,btVector4> m_linkColors;
|
||||
};
|
||||
|
||||
void BulletURDFImporter::printTree()
|
||||
@@ -96,6 +96,8 @@ struct BulletErrorLogger : public ErrorLogger
|
||||
bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase)
|
||||
{
|
||||
|
||||
m_data->m_linkColors.clear();
|
||||
|
||||
|
||||
//int argc=0;
|
||||
char relativeFileName[1024];
|
||||
@@ -172,6 +174,17 @@ void BulletURDFImporter::getLinkChildIndices(int linkIndex, btAlignedObjectArray
|
||||
}
|
||||
}
|
||||
|
||||
bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
{
|
||||
btVector4* rgbaPtr = m_data->m_linkColors[linkIndex];
|
||||
if (rgbaPtr)
|
||||
{
|
||||
colorRGBA = *rgbaPtr;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
std::string BulletURDFImporter::getLinkName(int linkIndex) const
|
||||
{
|
||||
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex);
|
||||
@@ -852,8 +865,18 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
|
||||
for (int v = 0; v < link->m_visualArray.size();v++)
|
||||
{
|
||||
const UrdfVisual& vis = link->m_visualArray[v];
|
||||
btTransform childTrans = vis.m_linkLocalFrame;
|
||||
btTransform childTrans = vis.m_linkLocalFrame;
|
||||
btHashString matName(vis.m_materialName.c_str());
|
||||
UrdfMaterial *const * matPtr = model.m_materials[matName];
|
||||
if (matPtr)
|
||||
{
|
||||
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);
|
||||
}
|
||||
convertURDFToVisualShape(&vis, pathPrefix, inertialFrame.inverse()*childTrans, vertices, indices);
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -27,6 +27,8 @@ public:
|
||||
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
||||
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
virtual std::string getJointName(int linkIndex) const;
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ static btVector4 colors[4] =
|
||||
};
|
||||
|
||||
|
||||
static btVector3 selectColor2()
|
||||
static btVector4 selectColor2()
|
||||
{
|
||||
|
||||
static int curColor = 0;
|
||||
@@ -371,8 +371,8 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
||||
|
||||
world1->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||
|
||||
btVector3 color = selectColor2();//(0.0,0.0,0.5);
|
||||
|
||||
btVector4 color = selectColor2();//(0.0,0.0,0.5);
|
||||
u2b.getLinkColor(urdfLinkIndex,color);
|
||||
creation.createCollisionObjectGraphicsInstance(urdfLinkIndex,col,color);
|
||||
|
||||
btScalar friction = 0.5f;
|
||||
|
||||
@@ -24,6 +24,8 @@ public:
|
||||
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const =0;
|
||||
/// 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 std::string getJointName(int linkIndex) const = 0;
|
||||
|
||||
|
||||
@@ -346,6 +346,8 @@ bool UrdfParser::parseVisual(UrdfVisual& visual, TiXmlElement* config, ErrorLogg
|
||||
{
|
||||
if (parseMaterial(visual.m_localMaterial, mat,logger))
|
||||
{
|
||||
UrdfMaterial* matPtr = new UrdfMaterial(visual.m_localMaterial);
|
||||
m_model.m_materials.insert(matPtr->m_name.c_str(),matPtr);
|
||||
visual.m_hasLocalMaterial = true;
|
||||
}
|
||||
}
|
||||
@@ -786,7 +788,7 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
|
||||
for (int i=0;i<link->m_visualArray.size();i++)
|
||||
{
|
||||
UrdfVisual& vis = link->m_visualArray.at(i);
|
||||
if (!vis.m_hasLocalMaterial)
|
||||
if (!vis.m_hasLocalMaterial && vis.m_materialName.c_str())
|
||||
{
|
||||
UrdfMaterial** mat = m_model.m_materials.find(vis.m_materialName.c_str());
|
||||
if (mat && *mat)
|
||||
|
||||
@@ -284,6 +284,18 @@ int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandH
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_CREATE_BOX_COLLISION_SHAPE);
|
||||
command->m_updateFlags |=BOX_SHAPE_HAS_COLOR;
|
||||
command->m_createBoxShapeArguments.m_colorRGBA[0] = red;
|
||||
command->m_createBoxShapeArguments.m_colorRGBA[1] = green;
|
||||
command->m_createBoxShapeArguments.m_colorRGBA[2] = blue;
|
||||
command->m_createBoxShapeArguments.m_colorRGBA[3] = alpha;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW)
|
||||
{
|
||||
|
||||
@@ -94,6 +94,7 @@ int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHan
|
||||
int b3CreateBoxCommandSetHalfExtents(b3SharedMemoryCommandHandle commandHandle, double halfExtentsX,double halfExtentsY,double halfExtentsZ);
|
||||
int b3CreateBoxCommandSetMass(b3SharedMemoryCommandHandle commandHandle, double mass);
|
||||
int b3CreateBoxCommandSetCollisionShapeType(b3SharedMemoryCommandHandle commandHandle, int collisionShapeType);
|
||||
int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, double red,double green,double blue, double alpha);
|
||||
|
||||
|
||||
///Initialize (teleport) the pose of a body/robot. You can individually set the base position, base orientation and joint angles.
|
||||
|
||||
@@ -211,6 +211,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
|
||||
b3CreateBoxCommandSetStartPosition(commandHandle,0,0,-3);
|
||||
b3CreateBoxCommandSetColorRGBA(commandHandle,0,0,1,1);
|
||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||
break;
|
||||
}
|
||||
@@ -220,6 +221,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
b3CreateBoxCommandSetStartPosition(commandHandle,0,0,0);
|
||||
b3CreateBoxCommandSetMass(commandHandle,1);
|
||||
b3CreateBoxCommandSetCollisionShapeType(commandHandle,COLLISION_SHAPE_TYPE_CYLINDER_Y);
|
||||
b3CreateBoxCommandSetColorRGBA(commandHandle,1,1,0,1);
|
||||
double radius = 0.2;
|
||||
double halfHeight = 0.5;
|
||||
b3CreateBoxCommandSetHalfExtents(commandHandle,radius,halfHeight,radius);
|
||||
|
||||
@@ -1684,7 +1684,17 @@ void PhysicsServerSharedMemory::processClientCommands()
|
||||
bool isDynamic = (mass>0);
|
||||
btRigidBody* rb = worldImporter->createRigidBody(isDynamic,mass,startTrans,shape,0);
|
||||
rb->setRollingFriction(0.2);
|
||||
m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
|
||||
//m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
|
||||
btVector4 colorRGBA(1,0,0,1);
|
||||
if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLOR)
|
||||
{
|
||||
colorRGBA[0] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[0];
|
||||
colorRGBA[1] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[1];
|
||||
colorRGBA[2] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[2];
|
||||
colorRGBA[3] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[3];
|
||||
}
|
||||
m_data->m_guiHelper->createCollisionShapeGraphicsObject(rb->getCollisionShape());
|
||||
m_data->m_guiHelper->createCollisionObjectGraphicsObject(rb,colorRGBA);
|
||||
|
||||
SharedMemoryStatus& serverCmd =m_data->createServerStatus(CMD_RIGID_BODY_CREATION_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
|
||||
int bodyUniqueId = m_data->allocHandle();
|
||||
|
||||
@@ -205,6 +205,7 @@ enum EnumBoxShapeFlags
|
||||
BOX_SHAPE_HAS_HALF_EXTENTS=4,
|
||||
BOX_SHAPE_HAS_MASS=8,
|
||||
BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE=16,
|
||||
BOX_SHAPE_HAS_COLOR=32,
|
||||
};
|
||||
///This command will be replaced to allow arbitrary collision shape types
|
||||
struct CreateBoxShapeArgs
|
||||
@@ -218,6 +219,7 @@ struct CreateBoxShapeArgs
|
||||
|
||||
double m_initialPosition[3];
|
||||
double m_initialOrientation[4];
|
||||
double m_colorRGBA[4];
|
||||
};
|
||||
|
||||
struct SharedMemoryCommand
|
||||
|
||||
Reference in New Issue
Block a user