Files
bullet3/examples/Importers/ImportURDFDemo/URDF2Bullet.h
erwincoumans 22b4809891 leave m_useGlobalVelocities to false, until enabled, for backward compatibility
use URDF_GLOBAL_VELOCITIES_MB flag in PyBullet loadURDF.
fix robot_bases.py due to new fields in getJointInfo.
backward compabitibility: BulletMJCFImporter, keep creating btMultiSphereShape for MJCF capsules with fromto, instead of shifted btCapsuleShapeZ, unless if CUF_USE_IMPLICIT_CYLINDER is used.
2018-01-10 11:16:50 -08:00

41 lines
1.0 KiB
C++

#ifndef _URDF2BULLET_H
#define _URDF2BULLET_H
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btTransform.h"
#include <string>
class btVector3;
class btTransform;
class btMultiBodyDynamicsWorld;
class btTransform;
class URDFImporterInterface;
class MultiBodyCreationInterface;
//manually sync with eURDF_Flags in SharedMemoryPublic.h!
enum ConvertURDFFlags {
CUF_USE_SDF = 1,
// Use inertia values in URDF instead of recomputing them from collision shape.
CUF_USE_URDF_INERTIA = 2,
CUF_USE_MJCF = 4,
CUF_USE_SELF_COLLISION=8,
CUF_USE_SELF_COLLISION_EXCLUDE_PARENT=16,
CUF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32,
CUF_RESERVED=64,
CUF_USE_IMPLICIT_CYLINDER=128,
CUF_GLOBAL_VELOCITIES_MB=256,
};
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
MultiBodyCreationInterface& creationCallback,
const btTransform& rootTransformInWorldSpace,
btMultiBodyDynamicsWorld* world,
bool createMultiBody,
const char* pathPrefix,
int flags = 0);
#endif //_URDF2BULLET_H