mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
Merge remote-tracking branch 'bp/master'
This commit is contained in:
commit
696837af16
@ -24,6 +24,7 @@ SET(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} -D_DEBUG")
|
||||
#MESSAGE("CMAKE_CXX_FLAGS_DEBUG="+${CMAKE_CXX_FLAGS_DEBUG})
|
||||
|
||||
OPTION(USE_DOUBLE_PRECISION "Use double precision" OFF)
|
||||
SET(CLAMP_VELOCITIES "0" CACHE STRING "Clamp rigid bodies' velocity to this value, if larger than zero. Useful to prevent floating point errors or in general runaway velocities in complex scenarios")
|
||||
OPTION(USE_GRAPHICAL_BENCHMARK "Use Graphical Benchmark" ON)
|
||||
OPTION(BUILD_SHARED_LIBS "Use shared libraries" OFF)
|
||||
OPTION(USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD "Use btSoftMultiBodyDynamicsWorld" ON)
|
||||
@ -211,6 +212,10 @@ IF (INTERNAL_UPDATE_SERIALIZATION_STRUCTURES)
|
||||
ADD_DEFINITIONS( -DBT_INTERNAL_UPDATE_SERIALIZATION_STRUCTURES)
|
||||
ENDIF (INTERNAL_UPDATE_SERIALIZATION_STRUCTURES)
|
||||
|
||||
IF (CLAMP_VELOCITIES)
|
||||
ADD_DEFINITIONS( -DBT_CLAMP_VELOCITY_TO=${CLAMP_VELOCITIES})
|
||||
ENDIF (CLAMP_VELOCITIES)
|
||||
|
||||
IF (USE_DOUBLE_PRECISION)
|
||||
ADD_DEFINITIONS( -DBT_USE_DOUBLE_PRECISION)
|
||||
SET( BULLET_DOUBLE_DEF "-DBT_USE_DOUBLE_PRECISION")
|
||||
|
@ -337,6 +337,12 @@ end
|
||||
trigger = "double",
|
||||
description = "Double precision version of Bullet"
|
||||
}
|
||||
|
||||
newoption
|
||||
{
|
||||
trigger = "clamp-velocities",
|
||||
description = "Limit maximum velocities to reduce FP exception risk"
|
||||
}
|
||||
|
||||
newoption
|
||||
{
|
||||
@ -360,6 +366,9 @@ end
|
||||
if _OPTIONS["double"] then
|
||||
defines {"BT_USE_DOUBLE_PRECISION"}
|
||||
end
|
||||
if _OPTIONS["clamp-velocities"] then
|
||||
defines {"BT_CLAMP_VELOCITY_TO=9999"}
|
||||
end
|
||||
|
||||
configurations {"Release", "Debug"}
|
||||
configuration "Release"
|
||||
|
@ -6,6 +6,7 @@
|
||||
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
|
||||
</inertial>
|
||||
<collision_margin value="0.006"/>
|
||||
<repulsion_stiffness value="50.0"/>
|
||||
<friction value= "0.5"/>
|
||||
<neohookean mu= "60" lambda= "200" damping= "0.01" />
|
||||
<visual filename="torus.vtk"/>
|
||||
|
@ -73,10 +73,10 @@ public:
|
||||
|
||||
void resetCamera()
|
||||
{
|
||||
float dist = 2;
|
||||
float dist = 0.3;
|
||||
float pitch = -45;
|
||||
float yaw = 100;
|
||||
float targetPos[3] = {0, -0, 0};
|
||||
float targetPos[3] = {0, -0.1, 0};
|
||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||
}
|
||||
|
||||
@ -105,12 +105,12 @@ public:
|
||||
if (dofIndex == 6)
|
||||
{
|
||||
motor->setVelocityTarget(-fingerTargetVelocities[1], 1);
|
||||
motor->setMaxAppliedImpulse(2);
|
||||
motor->setMaxAppliedImpulse(20);
|
||||
}
|
||||
if (dofIndex == 7)
|
||||
{
|
||||
motor->setVelocityTarget(fingerTargetVelocities[1], 1);
|
||||
motor->setMaxAppliedImpulse(2);
|
||||
motor->setMaxAppliedImpulse(20);
|
||||
}
|
||||
motor->setMaxAppliedImpulse(1);
|
||||
}
|
||||
@ -208,9 +208,9 @@ void GraspDeformable::initPhysics()
|
||||
bool canSleep = false;
|
||||
bool selfCollide = true;
|
||||
int numLinks = 2;
|
||||
btVector3 linkHalfExtents(.1, .2, .04);
|
||||
btVector3 baseHalfExtents(.1, 0.02, .2);
|
||||
btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, .7f,0.f), linkHalfExtents, baseHalfExtents, false);
|
||||
btVector3 linkHalfExtents(0.02, 0.018, .003);
|
||||
btVector3 baseHalfExtents(0.02, 0.002, .002);
|
||||
btMultiBody* mbC = createFeatherstoneMultiBody(getDeformableDynamicsWorld(), btVector3(0.f, 0.05f,0.f), linkHalfExtents, baseHalfExtents, false);
|
||||
|
||||
mbC->setCanSleep(canSleep);
|
||||
mbC->setHasSelfCollision(selfCollide);
|
||||
@ -258,7 +258,7 @@ void GraspDeformable::initPhysics()
|
||||
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -5.3, 0));
|
||||
groundTransform.setOrigin(btVector3(0, -5.1, 0));
|
||||
groundTransform.setRotation(btQuaternion(btVector3(1, 0, 0), SIMD_PI * 0));
|
||||
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
|
||||
btScalar mass(0.);
|
||||
@ -309,7 +309,7 @@ void GraspDeformable::initPhysics()
|
||||
// psb->scale(btVector3(.3, .3, .3)); // for tube, torus, boot
|
||||
// psb->scale(btVector3(.1, .1, .1)); // for ditto
|
||||
// psb->translate(btVector3(.25, 10, 0.4));
|
||||
psb->getCollisionShape()->setMargin(0.0005);
|
||||
psb->getCollisionShape()->setMargin(0.01);
|
||||
psb->setMaxStress(50);
|
||||
psb->setTotalMass(.1);
|
||||
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
|
||||
@ -334,8 +334,8 @@ void GraspDeformable::initPhysics()
|
||||
if(1)
|
||||
{
|
||||
bool onGround = false;
|
||||
const btScalar s = .5;
|
||||
const btScalar h = .1;
|
||||
const btScalar s = .05;
|
||||
const btScalar h = -0.02;
|
||||
btSoftBody* psb = btSoftBodyHelpers::CreatePatch(getDeformableDynamicsWorld()->getWorldInfo(), btVector3(-s, h, -s),
|
||||
btVector3(+s, h, -s),
|
||||
btVector3(-s, h, +s),
|
||||
@ -352,37 +352,35 @@ void GraspDeformable::initPhysics()
|
||||
2,2,
|
||||
0, true);
|
||||
|
||||
psb->getCollisionShape()->setMargin(0.01);
|
||||
psb->getCollisionShape()->setMargin(0.003);
|
||||
psb->generateBendingConstraints(2);
|
||||
psb->setTotalMass(1);
|
||||
psb->setTotalMass(0.005);
|
||||
psb->setSpringStiffness(10);
|
||||
psb->setDampingCoefficient(0.05);
|
||||
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
|
||||
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
|
||||
psb->m_cfg.kDF = 2;
|
||||
psb->m_cfg.kDF = 1;
|
||||
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
|
||||
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDF;
|
||||
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_MDF;
|
||||
// psb->m_cfg.collisions |= btSoftBody::fCollision::VF_DD;
|
||||
getDeformableDynamicsWorld()->addSoftBody(psb);
|
||||
// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(.0,0.0, true));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(10,1, true));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(0.05,0.005, true));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity*0.1));
|
||||
}
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
||||
{
|
||||
SliderParams slider("Moving velocity", &sGripperVerticalVelocity);
|
||||
slider.m_minVal = -.2;
|
||||
slider.m_maxVal = .2;
|
||||
slider.m_minVal = -.02;
|
||||
slider.m_maxVal = .02;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
{
|
||||
SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity);
|
||||
slider.m_minVal = -.5;
|
||||
slider.m_maxVal = .5;
|
||||
slider.m_minVal = -1;
|
||||
slider.m_maxVal = 1;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
@ -436,8 +434,8 @@ btMultiBody* GraspDeformable::createFeatherstoneMultiBody(btMultiBodyDynamicsWor
|
||||
{
|
||||
//init the base
|
||||
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
|
||||
float baseMass = 100.f;
|
||||
float linkMass = 100.f;
|
||||
float baseMass = 0.1;
|
||||
float linkMass = 0.1;
|
||||
int numLinks = 2;
|
||||
|
||||
if (baseMass)
|
||||
@ -465,8 +463,8 @@ btMultiBody* GraspDeformable::createFeatherstoneMultiBody(btMultiBodyDynamicsWor
|
||||
|
||||
//y-axis assumed up
|
||||
btAlignedObjectArray<btVector3> parentComToCurrentCom;
|
||||
parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, -baseHalfExtents[2] * 4.f));
|
||||
parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, +baseHalfExtents[2] * 4.f));//par body's COM to cur body's COM offset
|
||||
parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, -baseHalfExtents[2] * 2.f));
|
||||
parentComToCurrentCom.push_back(btVector3(0, -linkHalfExtents[1] * 8.f, +baseHalfExtents[2] * 2.f));//par body's COM to cur body's COM offset
|
||||
|
||||
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1]*8.f, 0); //cur body's COM to cur body's PIV offset
|
||||
|
||||
@ -507,6 +505,7 @@ void GraspDeformable::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsW
|
||||
if (1)
|
||||
{
|
||||
btCollisionShape* box = new btBoxShape(baseHalfExtents);
|
||||
box->setMargin(0.001);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
|
||||
col->setCollisionShape(box);
|
||||
|
||||
@ -537,6 +536,7 @@ void GraspDeformable::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsW
|
||||
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
|
||||
|
||||
btCollisionShape* box = new btBoxShape(linkHalfExtents);
|
||||
box->setMargin(0.001);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
|
||||
|
||||
col->setCollisionShape(box);
|
||||
|
@ -300,21 +300,21 @@ void Pinch::initPhysics()
|
||||
psb->setTotalMass(1);
|
||||
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
|
||||
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
|
||||
psb->m_cfg.kDF = 2;
|
||||
psb->m_cfg.kDF = .5;
|
||||
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
|
||||
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDF;
|
||||
getDeformableDynamicsWorld()->addSoftBody(psb);
|
||||
btSoftBodyHelpers::generateBoundaryFaces(psb);
|
||||
|
||||
btDeformableMassSpringForce* mass_spring = new btDeformableMassSpringForce(1,0.05);
|
||||
getDeformableDynamicsWorld()->addForce(psb, mass_spring);
|
||||
m_forces.push_back(mass_spring);
|
||||
|
||||
btDeformableGravityForce* gravity_force = new btDeformableGravityForce(gravity);
|
||||
getDeformableDynamicsWorld()->addForce(psb, gravity_force);
|
||||
m_forces.push_back(gravity_force);
|
||||
|
||||
btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(.2,1);
|
||||
btDeformableNeoHookeanForce* neohookean = new btDeformableNeoHookeanForce(8,3, 0.02);
|
||||
neohookean->setPoissonRatio(0.3);
|
||||
neohookean->setYoungsModulus(25);
|
||||
neohookean->setDamping(0.01);
|
||||
psb->m_cfg.drag = 0.001;
|
||||
getDeformableDynamicsWorld()->addForce(psb, neohookean);
|
||||
m_forces.push_back(neohookean);
|
||||
// add a grippers
|
||||
|
@ -165,7 +165,7 @@ void SplitImpulse::initPhysics()
|
||||
psb->setTotalMass(1);
|
||||
psb->m_cfg.kKHR = 1; // collision hardness with kinematic objects
|
||||
psb->m_cfg.kCHR = 1; // collision hardness with rigid body
|
||||
psb->m_cfg.kDF = 0.1;
|
||||
psb->m_cfg.kDF = 1;
|
||||
psb->m_cfg.collisions = btSoftBody::fCollision::SDF_RD;
|
||||
psb->m_cfg.collisions |= btSoftBody::fCollision::SDF_RDF;
|
||||
getDeformableDynamicsWorld()->addSoftBody(psb);
|
||||
|
@ -1163,6 +1163,17 @@ bool UrdfParser::parseDeformable(UrdfModel& model, tinyxml2::XMLElement* config,
|
||||
}
|
||||
deformable.m_friction = urdfLexicalCast<double>(friction_xml->Attribute("value"));
|
||||
}
|
||||
|
||||
XMLElement* repulsion_xml = config->FirstChildElement("repulsion_stiffness");
|
||||
if (repulsion_xml)
|
||||
{
|
||||
if (!repulsion_xml->Attribute("value"))
|
||||
{
|
||||
logger->reportError("repulsion_stiffness element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
deformable.m_repulsionStiffness = urdfLexicalCast<double>(repulsion_xml->Attribute("value"));
|
||||
}
|
||||
|
||||
XMLElement* spring_xml = config->FirstChildElement("spring");
|
||||
if (spring_xml)
|
||||
|
@ -225,6 +225,7 @@ struct UrdfDeformable
|
||||
double m_mass;
|
||||
double m_collisionMargin;
|
||||
double m_friction;
|
||||
double m_repulsionStiffness;
|
||||
|
||||
SpringCoeffcients m_springCoefficients;
|
||||
LameCoefficients m_corotatedCoefficients;
|
||||
@ -234,7 +235,7 @@ struct UrdfDeformable
|
||||
std::string m_simFileName;
|
||||
btHashMap<btHashString, std::string> m_userData;
|
||||
|
||||
UrdfDeformable() : m_mass(1.), m_collisionMargin(0.02), m_friction(1.), m_visualFileName(""), m_simFileName("")
|
||||
UrdfDeformable() : m_mass(1.), m_collisionMargin(0.02), m_friction(1.), m_repulsionStiffness(0.5), m_visualFileName(""), m_simFileName("")
|
||||
{
|
||||
}
|
||||
};
|
||||
|
@ -404,6 +404,15 @@ B3_SHARED_API int b3LoadSoftBodySetCollisionHardness(b3SharedMemoryCommandHandle
|
||||
return 0;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3LoadSoftBodySetRepulsionStiffness(b3SharedMemoryCommandHandle commandHandle, double stiffness)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||
b3Assert(command->m_type == CMD_LOAD_SOFT_BODY);
|
||||
command->m_loadSoftBodyArguments.m_repulsionStiffness = stiffness;
|
||||
command->m_updateFlags |= LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS;
|
||||
return 0;
|
||||
}
|
||||
|
||||
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||
|
@ -648,7 +648,8 @@ extern "C"
|
||||
B3_SHARED_API int b3LoadSoftBodyAddGravityForce(b3SharedMemoryCommandHandle commandHandle, double gravityX, double gravityY, double gravityZ);
|
||||
B3_SHARED_API int b3LoadSoftBodySetCollisionHardness(b3SharedMemoryCommandHandle commandHandle, double collisionHardness);
|
||||
B3_SHARED_API int b3LoadSoftBodySetSelfCollision(b3SharedMemoryCommandHandle commandHandle, int useSelfCollision);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseFaceContact(b3SharedMemoryCommandHandle commandHandle, int useFaceContact);
|
||||
B3_SHARED_API int b3LoadSoftBodySetRepulsionStiffness(b3SharedMemoryCommandHandle commandHandle, double stiffness);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseFaceContact(b3SharedMemoryCommandHandle commandHandle, int useFaceContact);
|
||||
B3_SHARED_API int b3LoadSoftBodySetFrictionCoefficient(b3SharedMemoryCommandHandle commandHandle, double frictionCoefficient);
|
||||
B3_SHARED_API int b3LoadSoftBodyUseBendingSprings(b3SharedMemoryCommandHandle commandHandle, int useBendingSprings, double bendingStiffness);
|
||||
|
||||
|
@ -8312,6 +8312,10 @@ void constructUrdfDeformable(const struct SharedMemoryCommand& clientCmd, UrdfDe
|
||||
{
|
||||
deformable.m_friction = loadSoftBodyArgs.m_frictionCoeff;
|
||||
}
|
||||
if (clientCmd.m_updateFlags & LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS)
|
||||
{
|
||||
deformable.m_repulsionStiffness = loadSoftBodyArgs.m_repulsionStiffness;
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
@ -8531,6 +8535,7 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
|
||||
psb->setCollisionFlags(0);
|
||||
psb->setTotalMass(deformable.m_mass);
|
||||
psb->setSelfCollision(useSelfCollision);
|
||||
psb->setSpringStiffness(deformable.m_repulsionStiffness);
|
||||
psb->initializeFaceTree();
|
||||
}
|
||||
#endif //SKIP_DEFORMABLE_BODY
|
||||
@ -12469,7 +12474,7 @@ bool PhysicsServerCommandProcessor::processRequestCollisionShapeInfoCommand(cons
|
||||
{
|
||||
//extract shape info from base collider
|
||||
int numConvertedCollisionShapes = extractCollisionShapes(bodyHandle->m_multiBody->getBaseCollider()->getCollisionShape(), childTrans, collisionShapeStoragePtr, maxNumColObjects);
|
||||
serverCmd.m_numDataStreamBytes = numConvertedCollisionShapes*sizeof(b3CollisionShapeData);
|
||||
serverCmd.m_numDataStreamBytes = numConvertedCollisionShapes * sizeof(b3CollisionShapeData);
|
||||
serverCmd.m_sendCollisionShapeArgs.m_numCollisionShapes = numConvertedCollisionShapes;
|
||||
serverCmd.m_type = CMD_COLLISION_SHAPE_INFO_COMPLETED;
|
||||
}
|
||||
@ -12704,6 +12709,17 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
m_data->m_guiHelper->changeSpecularColor(graphicsIndex, clientCmd.m_updateVisualShapeDataArguments.m_specularColor);
|
||||
}
|
||||
}
|
||||
else if (bodyHandle->m_softBody)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
{
|
||||
if (m_data->m_pluginManager.getRenderInterface())
|
||||
{
|
||||
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId, linkIndex,
|
||||
clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -497,17 +497,18 @@ enum EnumLoadSoftBodyUpdateFlags
|
||||
LOAD_SOFT_BODY_UPDATE_MASS = 1<<2,
|
||||
LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN = 1<<3,
|
||||
LOAD_SOFT_BODY_INITIAL_POSITION = 1<<4,
|
||||
LOAD_SOFT_BODY_INITIAL_ORIENTATION = 1<<5,
|
||||
LOAD_SOFT_BODY_ADD_COROTATED_FORCE = 1<<6,
|
||||
LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE = 1<<7,
|
||||
LOAD_SOFT_BODY_ADD_GRAVITY_FORCE = 1<<8,
|
||||
LOAD_SOFT_BODY_SET_COLLISION_HARDNESS = 1<<9,
|
||||
LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1<<10,
|
||||
LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1<<11,
|
||||
LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1<<12,
|
||||
LOAD_SOFT_BODY_USE_SELF_COLLISION = 1<<13,
|
||||
LOAD_SOFT_BODY_USE_FACE_CONTACT = 1<<14,
|
||||
LOAD_SOFT_BODY_SIM_MESH = 1<<15,
|
||||
LOAD_SOFT_BODY_INITIAL_ORIENTATION = 1<<5,
|
||||
LOAD_SOFT_BODY_ADD_COROTATED_FORCE = 1<<6,
|
||||
LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE = 1<<7,
|
||||
LOAD_SOFT_BODY_ADD_GRAVITY_FORCE = 1<<8,
|
||||
LOAD_SOFT_BODY_SET_COLLISION_HARDNESS = 1<<9,
|
||||
LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1<<10,
|
||||
LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1<<11,
|
||||
LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1<<12,
|
||||
LOAD_SOFT_BODY_USE_SELF_COLLISION = 1<<13,
|
||||
LOAD_SOFT_BODY_USE_FACE_CONTACT = 1<<14,
|
||||
LOAD_SOFT_BODY_SIM_MESH = 1<<15,
|
||||
LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS = 1<<16,
|
||||
};
|
||||
|
||||
enum EnumSimParamInternalSimFlags
|
||||
@ -540,6 +541,7 @@ struct LoadSoftBodyArgs
|
||||
double m_NeoHookeanDamping;
|
||||
int m_useFaceContact;
|
||||
char m_simFileName[MAX_FILENAME_LENGTH];
|
||||
double m_repulsionStiffness;
|
||||
};
|
||||
|
||||
struct b3LoadSoftBodyResultArgs
|
||||
|
@ -5,7 +5,9 @@ import time
|
||||
GRAVITY = -9.8
|
||||
dt = 1e-3
|
||||
iters = 2000
|
||||
import pybullet_data
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
physicsClient = p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation()
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
cube2 = p.loadURDF("cube.urdf", [0, 0, 3], useFixedBase=True)
|
||||
cube = p.loadURDF("cube.urdf", useFixedBase=True)
|
||||
p.setGravity(0, 0, -10)
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
planeUidA = p.loadURDF("plane_transparent.urdf", [0, 0, 0])
|
||||
planeUid = p.loadURDF("plane_transparent.urdf", [0, 0, -1])
|
||||
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
planeId = p.loadURDF("plane.urdf", useMaximalCoordinates=False)
|
||||
cubeId = p.loadURDF("cube_collisionfilter.urdf", [0, 0, 3], useMaximalCoordinates=False)
|
||||
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_ALL_COMMANDS, "commandLog.bin")
|
||||
p.loadURDF("plane.urdf")
|
||||
p.loadURDF("r2d2.urdf", [0, 0, 1])
|
||||
|
@ -2,8 +2,10 @@ import pybullet as p
|
||||
import math
|
||||
import time
|
||||
dt = 1./240.
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)#SHARED_MEMORY_GUI)
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("r2d2.urdf",[0,0,1])
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0,0,-10)
|
||||
@ -18,4 +20,4 @@ while (1):
|
||||
p.configureDebugVisualizer(lightPosition=[radius*math.sin(t),radius*math.cos(t),3])
|
||||
|
||||
p.stepSimulation()
|
||||
time.sleep(dt)
|
||||
time.sleep(dt)
|
||||
|
@ -2,7 +2,9 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
import pybullet_data
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
cubeId = p.loadURDF("cube_small.urdf", 0, 0, 1)
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
useMaximalCoordinates = False
|
||||
p.loadURDF("plane.urdf", useMaximalCoordinates=useMaximalCoordinates)
|
||||
#p.loadURDF("sphere2.urdf",[0,0,1])
|
||||
|
@ -1,8 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
#don't create a ground plane, to allow for gaps etc
|
||||
p.resetSimulation()
|
||||
#p.createCollisionShape(p.GEOM_PLANE)
|
||||
|
@ -1,10 +1,11 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
import pybullet_data
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI, options="--minGraphicsUpdateTimeMs=16000")
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.setPhysicsEngineParameter(numSolverIterations=4, minimumSolverIslandSize=1024)
|
||||
p.setTimeStep(1. / 120.)
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.createCollisionShape(p.GEOM_PLANE)
|
||||
p.createMultiBody(0, 0)
|
||||
|
||||
|
@ -1,8 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
#don't create a ground plane, to allow for gaps etc
|
||||
p.resetSimulation()
|
||||
#p.createCollisionShape(p.GEOM_PLANE)
|
||||
|
@ -2,8 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
|
||||
useMaximalCoordinates = 0
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
#p.loadSDF("stadium.sdf",useMaximalCoordinates=useMaximalCoordinates)
|
||||
monastryId = concaveEnv = p.createCollisionShape(p.GEOM_MESH,
|
||||
fileName="samurai_monastry.obj",
|
||||
|
@ -1,6 +1,7 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
|
||||
def getRayFromTo(mouseX, mouseY):
|
||||
@ -35,6 +36,7 @@ def getRayFromTo(mouseX, mouseY):
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setTimeStep(1. / 120.)
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "visualShapeBench.json")
|
||||
|
@ -1,6 +1,7 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
|
||||
def getRayFromTo(mouseX, mouseY):
|
||||
@ -36,6 +37,8 @@ def getRayFromTo(mouseX, mouseY):
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setTimeStep(1. / 120.)
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "visualShapeBench.json")
|
||||
|
@ -1,6 +1,7 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
|
||||
def getRayFromTo(mouseX, mouseY):
|
||||
@ -35,6 +36,8 @@ def getRayFromTo(mouseX, mouseY):
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setTimeStep(1. / 120.)
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "visualShapeBench.json")
|
||||
|
@ -1,9 +1,12 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf")
|
||||
kuka = p.loadURDF("kuka_iiwa/model.urdf")
|
||||
p.addUserDebugText("tip", [0, 0, 0.1],
|
||||
|
@ -2,6 +2,9 @@ import pybullet as p
|
||||
from time import sleep
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
import pybullet_data
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
||||
gravZ=-10
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
||||
|
@ -1,8 +1,11 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
@ -11,7 +14,7 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
||||
bunnyId = p.loadSoftBody("torus.vtk", useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, useSelfCollision = 1, frictionCoeff = 0.5)
|
||||
bunnyId = p.loadSoftBody("torus.vtk", mass = 1, useNeoHookean = 1, NeoHookeanMu = 60, NeoHookeanLambda = 200, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 50)
|
||||
|
||||
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0], flags=p.URDF_USE_SELF_COLLISION)
|
||||
|
||||
@ -20,4 +23,3 @@ p.setRealTimeSimulation(1)
|
||||
|
||||
while p.isConnected():
|
||||
p.setGravity(0,0,-10)
|
||||
sleep(1./240.)
|
||||
|
@ -2,9 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
import pkgutil
|
||||
egl = pkgutil.get_loader('eglRenderer')
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.DIRECT)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plugin = p.loadPlugin(egl.get_filename(), "_eglRendererPlugin")
|
||||
print("plugin=", plugin)
|
||||
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setPhysicsEngineParameter(allowedCcdPenetration=0.0)
|
||||
|
||||
terrain_mass = 0
|
||||
|
@ -1,9 +1,11 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadSDF("stadium.sdf")
|
||||
p.setGravity(0, 0, -10)
|
||||
objects = p.loadMJCF("mjcf/sphere.xml")
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
fileIO = p.loadPlugin("fileIOPlugin")
|
||||
if (fileIO >= 0):
|
||||
#we can have a zipfile (pickup.zip) inside a zipfile (pickup2.zip)
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
p.connect(p.DIRECT)
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
hinge = p.loadURDF("hinge.urdf")
|
||||
print("mass of linkA = 1kg, linkB = 1kg, total mass = 2kg")
|
||||
|
||||
|
@ -2,7 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
useMaximalCoordinates = False
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
|
@ -1,4 +1,5 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
draw = 1
|
||||
printtext = 0
|
||||
|
||||
@ -6,6 +7,8 @@ if (draw):
|
||||
p.connect(p.GUI)
|
||||
else:
|
||||
p.connect(p.DIRECT)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
r2d2 = p.loadURDF("r2d2.urdf")
|
||||
|
||||
|
||||
|
@ -2,10 +2,12 @@ import matplotlib.pyplot as plt
|
||||
import numpy as np
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
direct = p.connect(p.GUI) #, options="--window_backend=2 --render_device=0")
|
||||
#egl = p.loadPlugin("eglRendererPlugin")
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF('plane.urdf')
|
||||
p.loadURDF("r2d2.urdf", [0, 0, 1])
|
||||
p.loadURDF('cube_small.urdf', basePosition=[0.0, 0.0, 0.025])
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
useCollisionShapeQuery = True
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
|
||||
geom = p.createCollisionShape(p.GEOM_SPHERE, radius=0.1)
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plane = p.loadURDF("plane.urdf")
|
||||
visualData = p.getVisualShapeData(plane, p.VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS)
|
||||
print(visualData)
|
||||
|
@ -1,4 +1,6 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
|
||||
usePort = True
|
||||
|
||||
@ -13,5 +15,7 @@ if (id < 0):
|
||||
exit(0)
|
||||
|
||||
print("Connected to GRPC")
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
r2d2 = p.loadURDF("r2d2.urdf")
|
||||
print("numJoints = ", p.getNumJoints(r2d2))
|
||||
|
@ -4,7 +4,10 @@ import time
|
||||
useDirect = False
|
||||
usePort = True
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
id = p.loadPlugin("grpcPlugin")
|
||||
#dynamically loading the plugin
|
||||
#id = p.loadPlugin("E:/develop/bullet3/bin/pybullet_grpcPlugin_vs2010_x64_debug.dll", postFix="_grpcPlugin")
|
||||
|
@ -8,6 +8,8 @@
|
||||
import serial
|
||||
import time
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
|
||||
#first try to connect to shared memory (VR), if it fails use local GUI
|
||||
c = p.connect(p.SHARED_MEMORY)
|
||||
@ -15,6 +17,8 @@ print(c)
|
||||
if (c < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
#load the MuJoCo MJCF hand
|
||||
objects = p.loadMJCF("MPL/MPL.xml")
|
||||
|
||||
|
@ -1,8 +1,12 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
planeId = p.loadURDF("plane.urdf")
|
||||
cubeStartPos = [0, 0, 1]
|
||||
|
@ -1,12 +1,15 @@
|
||||
import pybullet as p
|
||||
import json
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
|
||||
useGUI = True
|
||||
if useGUI:
|
||||
p.connect(p.GUI)
|
||||
else:
|
||||
p.connect(p.DIRECT)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
useZUp = False
|
||||
useYUp = not useZUp
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.DIRECT)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setGravity(0, 0, -10)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=5)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=1. / 240.)
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
@ -11,6 +14,8 @@ useRealTime = 0
|
||||
|
||||
p.setRealTimeSimulation(useRealTime)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
|
||||
p.loadSDF("stadium.sdf")
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
obUids = p.loadMJCF("mjcf/humanoid.xml")
|
||||
humanoid = obUids[1]
|
||||
|
||||
|
@ -4,7 +4,10 @@ import math
|
||||
from datetime import datetime
|
||||
from time import sleep
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
kukaId = p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 0])
|
||||
p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1])
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
cube = p.loadURDF("cube.urdf")
|
||||
frequency = 240
|
||||
timeStep = 1. / frequency
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
if (1):
|
||||
box_collision_shape_id = p.createCollisionShape(shapeType=p.GEOM_BOX,
|
||||
|
@ -2,12 +2,15 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
from datetime import datetime
|
||||
import pybullet_data
|
||||
|
||||
clid = p.connect(p.SHARED_MEMORY)
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
#p.connect(p.SHARED_MEMORY_GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
kukaId = p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 0])
|
||||
p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1])
|
||||
|
@ -3,8 +3,11 @@ import time
|
||||
import math
|
||||
from datetime import datetime
|
||||
from datetime import datetime
|
||||
import pybullet_data
|
||||
|
||||
clid = p.connect(p.SHARED_MEMORY)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
|
@ -2,10 +2,13 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
from datetime import datetime
|
||||
import pybullet_data
|
||||
|
||||
clid = p.connect(p.SHARED_MEMORY)
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", [0, 0, -1.3])
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
|
||||
sawyerId = p.loadURDF("pole.urdf", [0, 0, 0])
|
||||
|
@ -1,4 +1,6 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
|
||||
|
||||
def getJointStates(robot):
|
||||
@ -51,6 +53,8 @@ clid = p.connect(p.SHARED_MEMORY)
|
||||
if (clid < 0):
|
||||
p.connect(p.DIRECT)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
time_step = 0.001
|
||||
gravity_constant = -9.81
|
||||
p.resetSimulation()
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
door = p.loadURDF("door.urdf")
|
||||
|
||||
#linear/angular damping for base and all children=0
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.25])
|
||||
minitaur = p.loadURDF("quadruped/minitaur_single_motor.urdf", useFixedBase=True)
|
||||
print(p.getNumJoints(minitaur))
|
||||
|
@ -43,7 +43,10 @@ def readLogFile(filename, verbose=True):
|
||||
|
||||
|
||||
#clid = p.connect(p.SHARED_MEMORY)
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadSDF("kuka_iiwa/kuka_with_gripper.sdf")
|
||||
p.loadURDF("tray/tray.urdf", [0, 0, 0])
|
||||
p.loadURDF("block.urdf", [0, 0, 2])
|
||||
|
@ -4,7 +4,10 @@ import math
|
||||
from datetime import datetime
|
||||
|
||||
#clid = p.connect(p.SHARED_MEMORY)
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3], useFixedBase=True)
|
||||
kukaId = p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 0], useFixedBase=True)
|
||||
p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1])
|
||||
|
@ -52,7 +52,10 @@ def readLogFile(filename, verbose=True):
|
||||
|
||||
|
||||
#clid = p.connect(p.SHARED_MEMORY)
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
p.loadURDF("kuka_iiwa/model.urdf", [0, 0, 1])
|
||||
p.loadURDF("cube.urdf", [2, 2, 5])
|
||||
|
@ -1,7 +1,11 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setGravity(0, 0, -10)
|
||||
planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.resetSimulation()
|
||||
timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "loadingBenchVR.json")
|
||||
|
@ -1,7 +1,12 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf")
|
||||
|
||||
quadruped = p.loadURDF("quadruped/quadruped.urdf")
|
||||
|
@ -1,10 +1,13 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
|
||||
conid = p.connect(p.SHARED_MEMORY)
|
||||
if (conid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setInternalSimFlags(0)
|
||||
p.resetSimulation()
|
||||
|
||||
|
@ -3,7 +3,10 @@
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf", 0, 0, -2)
|
||||
wheelA = p.loadURDF("differential/diff_ring.urdf", [0, 0, 0])
|
||||
for i in range(p.getNumJoints(wheelA)):
|
||||
|
@ -9,6 +9,9 @@ from minitaur_evaluate import *
|
||||
import time
|
||||
import math
|
||||
import numpy as np
|
||||
import pybullet_data
|
||||
|
||||
|
||||
|
||||
|
||||
def main(unused_args):
|
||||
@ -16,7 +19,7 @@ def main(unused_args):
|
||||
c = p.connect(p.SHARED_MEMORY)
|
||||
if (c < 0):
|
||||
c = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
params = [
|
||||
0.1903581461951056, 0.0006732219568880068, 0.05018085615283363, 3.219916795483583,
|
||||
6.2406418167980595, 4.189869754607539
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
cartpole = p.loadURDF("cartpole.urdf")
|
||||
p.setRealTimeSimulation(1)
|
||||
p.setJointMotorControl2(cartpole,
|
||||
|
@ -2,6 +2,7 @@ import pybullet as p
|
||||
import pybullet_data as pd
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
usePhysX = True
|
||||
useMaximalCoordinates = True
|
||||
@ -11,6 +12,7 @@ if usePhysX:
|
||||
else:
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=1. / 240.,
|
||||
numSolverIterations=4,
|
||||
minimumSolverIslandSize=1024)
|
||||
|
@ -6,7 +6,10 @@ from pdControllerStable import PDControllerStable
|
||||
import time
|
||||
|
||||
useMaximalCoordinates = False
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
pole = p.loadURDF("cartpole.urdf", [0, 0, 0], useMaximalCoordinates=useMaximalCoordinates)
|
||||
pole2 = p.loadURDF("cartpole.urdf", [0, 1, 0], useMaximalCoordinates=useMaximalCoordinates)
|
||||
pole3 = p.loadURDF("cartpole.urdf", [0, 2, 0], useMaximalCoordinates=useMaximalCoordinates)
|
||||
|
@ -1,8 +1,10 @@
|
||||
import pybullet as p
|
||||
import math
|
||||
import numpy as np
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plane = p.loadURDF("plane100.urdf")
|
||||
cube = p.loadURDF("cube.urdf", [0, 0, 1])
|
||||
|
||||
|
@ -2,7 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
#you can visualize the timings using Google Chrome, visit about://tracing
|
||||
#and load the json file
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
t = time.time() + 3.1
|
||||
|
||||
|
@ -2,9 +2,11 @@ import pybullet as p
|
||||
from time import sleep
|
||||
import matplotlib.pyplot as plt
|
||||
import numpy as np
|
||||
import pybullet_data
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setGravity(0, 0, 0)
|
||||
bearStartPos1 = [-3.3, 0, 0]
|
||||
bearStartOrientation1 = p.getQuaternionFromEuler([0, 0, 0])
|
||||
|
@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import math
|
||||
import pybullet_data
|
||||
|
||||
|
||||
|
||||
|
||||
def drawInertiaBox(parentUid, parentLinkIndex, color):
|
||||
@ -128,6 +131,7 @@ if (physId < 0):
|
||||
p.connect(p.GUI)
|
||||
#p.resetSimulation()
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
angle = 0 # pick in range 0..0.2 radians
|
||||
orn = p.getQuaternionFromEuler([0, angle, 0])
|
||||
p.loadURDF("plane.urdf", [0, 0, 0], orn)
|
||||
|
@ -9,6 +9,7 @@ import sys
|
||||
import os, fnmatch
|
||||
import argparse
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
|
||||
def readLogFile(filename, verbose=True):
|
||||
@ -56,6 +57,7 @@ def readLogFile(filename, verbose=True):
|
||||
|
||||
clid = p.connect(p.SHARED_MEMORY)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
log = readLogFile("LOG00076.TXT")
|
||||
|
||||
recordNum = len(log)
|
||||
|
@ -1,5 +1,9 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.SHARED_MEMORY)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
objects = [
|
||||
p.loadURDF("plane.urdf", 0.000000, 0.000000, -.300000, 0.000000, 0.000000, 0.000000, 1.000000)
|
||||
]
|
||||
|
@ -1,10 +1,13 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.resetSimulation()
|
||||
p.setGravity(0, 0, -10)
|
||||
useRealTimeSim = 1
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll",
|
||||
"_testPlugin")
|
||||
print("plugin=", plugin)
|
||||
|
@ -10,6 +10,8 @@ import subprocess
|
||||
import numpy as np
|
||||
import pybullet
|
||||
from multiprocessing import Process
|
||||
import pybullet_data
|
||||
|
||||
|
||||
camTargetPos = [0, 0, 0]
|
||||
cameraUp = [0, 0, 1]
|
||||
@ -41,6 +43,7 @@ class BulletSim():
|
||||
|
||||
print(self.connection_mode, optionstring, *self.argv)
|
||||
cid = pybullet.connect(self.connection_mode, options=optionstring, *self.argv)
|
||||
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
if cid < 0:
|
||||
raise ValueError
|
||||
print("connected")
|
||||
|
@ -2,7 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
planeId = p.loadURDF(fileName="plane.urdf", baseOrientation=[0.25882, 0, 0, 0.96593])
|
||||
p.loadURDF(fileName="cube.urdf", basePosition=[0, 0, 2])
|
||||
cubeId = p.loadURDF(fileName="cube.urdf", baseOrientation=[0, 0, 0, 1], basePosition=[0, 0, 4])
|
||||
|
@ -3,10 +3,13 @@
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
cid = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
restitutionId = p.addUserDebugParameter("restitution", 0, 1, 1)
|
||||
restitutionVelocityThresholdId = p.addUserDebugParameter("res. vel. threshold", 0, 3, 0.2)
|
||||
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
p.connect(p.GUI) #or p.SHARED_MEMORY or p.DIRECT
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0, 0, -10)
|
||||
|
@ -1,9 +1,12 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
q = p.loadURDF("quadruped/quadruped.urdf", useFixedBase=True)
|
||||
rollId = p.addUserDebugParameter("roll", -1.5, 1.5, 0)
|
||||
pitchId = p.addUserDebugParameter("pitch", -1.5, 1.5, 0)
|
||||
|
@ -3,7 +3,10 @@ import pybullet as p
|
||||
import pybullet_data as pd
|
||||
useMaximalCoordinatesA = True
|
||||
useMaximalCoordinatesB = True
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
cube=p.loadURDF("cube_rotate.urdf",useMaximalCoordinates=useMaximalCoordinatesA)
|
||||
p.loadURDF("sphere2.urdf",[0,0,2],useMaximalCoordinates=useMaximalCoordinatesB)
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setGravity(0, 0, -10)
|
||||
p.setPhysicsEngineParameter(enableSAT=1)
|
||||
p.loadURDF("cube_concave.urdf", [0, 0, -25],
|
||||
|
@ -1,6 +1,8 @@
|
||||
import pybullet as p
|
||||
import math, time
|
||||
import difflib, sys
|
||||
import pybullet_data
|
||||
|
||||
|
||||
numSteps = 500
|
||||
numSteps2 = 30
|
||||
@ -8,6 +10,7 @@ p.connect(p.GUI, options="--width=1024 --height=768")
|
||||
numObjects = 50
|
||||
verbose = 0
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "saveRestoreTimings.log")
|
||||
|
||||
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.SHARED_MEMORY)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
timestr = time.strftime("%Y%m%d-%H%M%S")
|
||||
filename = "saveWorld" + timestr + ".py"
|
||||
p.saveWorld(filename)
|
||||
|
@ -2,7 +2,10 @@ import pybullet as p
|
||||
import time
|
||||
import numpy as np
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("plane.urdf")
|
||||
p.loadURDF("sphere2.urdf",[0,0,2])
|
||||
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
r2d2 = p.loadURDF("r2d2.urdf", [0, 0, 1])
|
||||
for l in range(p.getNumJoints(r2d2)):
|
||||
print(p.getJointInfo(r2d2, l))
|
||||
|
@ -2,8 +2,11 @@ import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0, 0, -10)
|
||||
|
@ -1,7 +1,10 @@
|
||||
import pybullet as p
|
||||
import pybullet
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.loadURDF("toys/concave_box.urdf")
|
||||
p.setGravity(0, 0, -10)
|
||||
for i in range(10):
|
||||
|
@ -4,7 +4,10 @@ useMaximalCoordinates = False
|
||||
|
||||
flags = p.URDF_ENABLE_SLEEPING
|
||||
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
|
||||
|
||||
p.loadURDF("plane100.urdf", flags=flags, useMaximalCoordinates=useMaximalCoordinates)
|
||||
|
@ -4,8 +4,10 @@ import math
|
||||
|
||||
# This simple snake logic is from some 15 year old Havok C++ demo
|
||||
# Thanks to Michael Ewert!
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plane = p.createCollisionShape(p.GEOM_PLANE)
|
||||
|
||||
p.createMultiBody(0, plane)
|
||||
|
@ -1,7 +1,9 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001)
|
||||
p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_DANTZIG,
|
||||
globalCFM=0.000001)
|
||||
|
@ -1,5 +1,8 @@
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
plugin = p.loadPlugin("D:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll",
|
||||
"_testPlugin")
|
||||
print("plugin=", plugin)
|
||||
|
@ -1,8 +1,11 @@
|
||||
import pybullet as p
|
||||
from time import sleep
|
||||
import pybullet_data
|
||||
|
||||
|
||||
physicsClient = p.connect(p.GUI)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
useDeformable = True
|
||||
if useDeformable:
|
||||
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||
|
@ -11,9 +11,12 @@ img = [[1, 2, 3] * 50] * 100 #np.random.rand(200, 320)
|
||||
#img = [tandard_normal((50,100))
|
||||
image = plt.imshow(img, interpolation='none', animated=True, label="blah")
|
||||
ax = plt.gca()
|
||||
import pybullet_data
|
||||
|
||||
pybullet.connect(pybullet.DIRECT)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
#pybullet.loadPlugin("eglRendererPlugin")
|
||||
pybullet.loadURDF("plane.urdf", [0, 0, -1])
|
||||
pybullet.loadURDF("r2d2.urdf")
|
||||
|
@ -17,9 +17,13 @@ img = np.random.rand(200, 320)
|
||||
#img = [tandard_normal((50,100))
|
||||
image = plt.imshow(img, interpolation='none', animated=True, label="blah")
|
||||
ax = plt.gca()
|
||||
import pybullet_data
|
||||
|
||||
|
||||
pybullet.connect(pybullet.DIRECT)
|
||||
|
||||
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
egl = pkgutil.get_loader('eglRenderer')
|
||||
if (egl):
|
||||
pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin")
|
||||
|
@ -6,6 +6,7 @@ import numpy as np
|
||||
import matplotlib.pyplot as plt
|
||||
import pybullet
|
||||
import time
|
||||
import pybullet_data
|
||||
|
||||
plt.ion()
|
||||
|
||||
@ -16,6 +17,8 @@ ax = plt.gca()
|
||||
|
||||
#pybullet.connect(pybullet.GUI)
|
||||
pybullet.connect(pybullet.DIRECT)
|
||||
|
||||
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
pybullet.loadURDF("plane.urdf", [0, 0, -1])
|
||||
pybullet.loadURDF("r2d2.urdf")
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user