bullet3/examples/Importers/ImportURDFDemo/URDF2Bullet.h
erwin coumans 5cf8ee3360 Allow to compile pybullet using btDiscreteDynamicsWorld (no multibodies and no deformables), this allows to create Jacobian and Mass matrix (and A=J*M-1*J_transpose) with MLCP solvers
Add examples/pybullet/gym/pybullet_utils/readwriteurdf.py, this allows to read a URDF and write the URDF with more reasonable inertia tensors (based on mass and collision volumes)
2021-03-15 22:44:55 -07:00

46 lines
1.3 KiB
C++

#ifndef _URDF2BULLET_H
#define _URDF2BULLET_H
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btTransform.h"
#include <string>
#include "URDFJointTypes.h" //for UrdfMaterialColor cache
class btVector3;
class btTransform;
class btMultiBodyDynamicsWorld;
class btDiscreteDynamicsWorld;
class btTransform;
class URDFImporterInterface;
class MultiBodyCreationInterface;
struct UrdfVisualShapeCache
{
btAlignedObjectArray<UrdfMaterialColor> m_cachedUrdfLinkColors;
btAlignedObjectArray<int> m_cachedUrdfLinkVisualShapeIndices;
};
//#define USE_DISCRETE_DYNAMICS_WORLD
#ifdef USE_DISCRETE_DYNAMICS_WORLD
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
MultiBodyCreationInterface& creationCallback,
const btTransform& rootTransformInWorldSpace,
btDiscreteDynamicsWorld* world,
bool createMultiBody,
const char* pathPrefix,
int flags = 0,
UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0);
#else
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
MultiBodyCreationInterface& creationCallback,
const btTransform& rootTransformInWorldSpace,
btMultiBodyDynamicsWorld* world,
bool createMultiBody,
const char* pathPrefix,
int flags = 0,
UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0);
#endif
#endif //_URDF2BULLET_H