remove pose frame from SDF,
allow plane collision shape in SDF load the Roboschool stadium.sdf in humanoid_knee_position_control.py
This commit is contained in:
@@ -568,6 +568,15 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
|
||||
switch (collision->m_geometry.m_type)
|
||||
{
|
||||
case URDF_GEOM_PLANE:
|
||||
{
|
||||
btVector3 planeNormal = collision->m_geometry.m_planeNormal;
|
||||
btScalar planeConstant = 0;//not available?
|
||||
btStaticPlaneShape* plane = new btStaticPlaneShape(planeNormal,planeConstant);
|
||||
shape = plane;
|
||||
shape ->setMargin(gUrdfDefaultCollisionMargin);
|
||||
break;
|
||||
}
|
||||
case URDF_GEOM_CAPSULE:
|
||||
{
|
||||
btScalar radius = collision->m_geometry.m_capsuleRadius;
|
||||
@@ -789,7 +798,7 @@ upAxisMat.setIdentity();
|
||||
|
||||
default:
|
||||
b3Warning("Error: unknown collision geometry type %i\n", collision->m_geometry.m_type);
|
||||
// for example, URDF_GEOM_PLANE
|
||||
|
||||
}
|
||||
return shape;
|
||||
}
|
||||
|
||||
@@ -3940,38 +3940,40 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
}
|
||||
else
|
||||
{
|
||||
if (mb->getLinkCollider(linkIndex))
|
||||
if (linkIndex >= 0 && linkIndex < mb->getNumLinks())
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
if (mb->getLinkCollider(linkIndex))
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setSpinningFriction(spinningFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRollingFriction(rollingFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setSpinningFriction(spinningFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRollingFriction(rollingFriction);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setFriction(lateralFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setFriction(lateralFriction);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
mb->getLink(linkIndex).m_mass = mass;
|
||||
if (mb->getLinkCollider(linkIndex) && mb->getLinkCollider(linkIndex)->getCollisionShape())
|
||||
{
|
||||
btVector3 localInertia;
|
||||
mb->getLinkCollider(linkIndex)->getCollisionShape()->calculateLocalInertia(mass,localInertia);
|
||||
mb->getLink(linkIndex).m_inertiaLocal = localInertia;
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
mb->getLink(linkIndex).m_mass = mass;
|
||||
if (mb->getLinkCollider(linkIndex) && mb->getLinkCollider(linkIndex)->getCollisionShape())
|
||||
{
|
||||
btVector3 localInertia;
|
||||
mb->getLinkCollider(linkIndex)->getCollisionShape()->calculateLocalInertia(mass,localInertia);
|
||||
mb->getLink(linkIndex).m_inertiaLocal = localInertia;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else
|
||||
|
||||
@@ -13,7 +13,7 @@ p.setRealTimeSimulation(useRealTime)
|
||||
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
p.loadURDF("plane.urdf")
|
||||
p.loadSDF("stadium.sdf")
|
||||
|
||||
obUids = p.loadMJCF("mjcf/humanoid_fixed.xml")
|
||||
human = obUids[0]
|
||||
|
||||
@@ -1,21 +1,30 @@
|
||||
import tensorflow as tf
|
||||
import sys
|
||||
import numpy as np
|
||||
|
||||
import argparse
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI) #DIRECT is much faster, but GUI shows the running gait
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid<0):
|
||||
cid = p.connect(p.GUI) #DIRECT is much faster, but GUI shows the running gait
|
||||
|
||||
p.setGravity(0,0,-9.8)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=5, numSubSteps=2)
|
||||
#this mp4 recording requires ffmpeg installed
|
||||
#mp4log = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4,"humanoid.mp4")
|
||||
|
||||
p.loadSDF("stadium.sdf")
|
||||
#p.loadURDF("plane.urdf")
|
||||
|
||||
plane, human = p.loadMJCF("mjcf/humanoid_symmetric.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
|
||||
objs = p.loadMJCF("mjcf/humanoid_symmetric_no_ground.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
human = objs[0]
|
||||
ordered_joints = []
|
||||
ordered_joint_indices = []
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument('--profile')
|
||||
|
||||
|
||||
jdict = {}
|
||||
for j in range( p.getNumJoints(human) ):
|
||||
@@ -175,7 +184,7 @@ def demo_run():
|
||||
p.setJointMotorControlArray(human, motors,controlMode=p.TORQUE_CONTROL, forces=forces)
|
||||
|
||||
p.stepSimulation()
|
||||
#time.sleep(0.01)
|
||||
time.sleep(0.01)
|
||||
distance=5
|
||||
yaw = 0
|
||||
humanPos, humanOrn = p.getBasePositionAndOrientation(human)
|
||||
|
||||
Reference in New Issue
Block a user