Add preliminary PhysX 4.0 backend for PyBullet
Add inverse dynamics / mass matrix code from DeepMimic, thanks to Xue Bin (Jason) Peng Add example how to use stable PD control for humanoid with spherical joints (see humanoidMotionCapture.py) Fix related to TinyRenderer object transforms not updating when using collision filtering
This commit is contained in:
@@ -13,28 +13,7 @@ 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,
|
||||
CUF_MJCF_COLORS_FROM_FILE = 512,
|
||||
CUF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
|
||||
CUF_ENABLE_SLEEPING = 2048,
|
||||
CUF_INITIALIZE_SAT_FEATURES = 4096,
|
||||
CUF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
|
||||
CUF_PARSE_SENSORS = 16384,
|
||||
CUF_USE_MATERIAL_COLORS_FROM_MTL = 32768,
|
||||
CUF_USE_MATERIAL_TRANSPARANCY_FROM_MTL = 64738,
|
||||
};
|
||||
|
||||
|
||||
struct UrdfVisualShapeCache
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user