Merge pull request #3339 from erwincoumans/master

add pybullet_examples, fix pybullet_envs.minitaur.envs_v2, bump up pybullet 3.1.2
This commit is contained in:
erwincoumans 2021-04-05 19:53:38 -07:00 committed by GitHub
commit 21d1b8fc71
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
94 changed files with 26551 additions and 3 deletions

View File

@ -0,0 +1 @@

View File

@ -7,7 +7,6 @@ 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()

View File

@ -0,0 +1,182 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from TwoJointRobot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="TwoJointRobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_01_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_12_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_21_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_23_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_1">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<link name="link_2">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<joint name="link_01" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_01_cyl"/>
<child link="link_1"/>
</joint>
<joint name="link_12" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_1"/>
<child link="link_12_cyl"/>
</joint>
<joint name="link_21" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_21_cyl"/>
<child link="link_2"/>
</joint>
<joint name="link_23" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_2"/>
<child link="link_23_cyl"/>
</joint>
<joint name="joint_1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3" upper="+3" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
<parent link="base_link"/>
<child link="link_01_cyl"/>
</joint>
<joint name="joint_2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3" upper="+3" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0.0 0. 0.05"/>
<parent link="link_12_cyl"/>
<child link="link_21_cyl"/>
</joint>
</robot>

View File

@ -0,0 +1,110 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from TwoJointRobot_woCyl.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="TwoJointRobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_23_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_1">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<link name="link_2">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<joint name="joint_1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3.14" upper="3.14" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
<parent link="base_link"/>
<child link="link_1"/>
</joint>
<joint name="joint_2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3.14" upper="3.14" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="1.0 0. 0.05"/>
<parent link="link_1"/>
<child link="link_2"/>
</joint>
<joint name="link_23" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_2"/>
<child link="link_23_cyl"/>
</joint>
</robot>

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

View File

@ -0,0 +1,13 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 94.117647
Ka 1.000000 1.000000 1.000000
Kd 0.640000 0.640000 0.640000
Ks 0.500000 0.500000 0.500000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Kd cube.png

View File

@ -0,0 +1,89 @@
# Blender v2.79 (sub 0) OBJ File: ''
# www.blender.org
mtllib cloth_z_up.mtl
o Plane_Plane.001
v 1.000000 -0.500000 -0.000000
v 0.500000 -1.000000 -0.000000
v 0.500000 -0.500000 -0.000000
v 0.000000 -0.500000 -0.000000
v -0.500000 -1.000000 -0.000000
v -0.500000 -0.500000 -0.000000
v -0.000000 0.500000 0.000000
v -0.500000 0.000000 -0.000000
v -0.500000 0.500000 0.000000
v 1.000000 0.500000 0.000000
v 0.500000 0.000000 0.000000
v 0.500000 0.500000 0.000000
v 0.000000 0.000000 0.000000
v 0.500000 1.000000 0.000000
v -0.000000 1.000000 0.000000
v 1.000000 1.000000 0.000000
v -1.000000 0.000000 -0.000000
v -1.000000 0.500000 0.000000
v -0.500000 1.000000 0.000000
v -1.000000 1.000000 0.000000
v -1.000000 -1.000000 -0.000000
v -1.000000 -0.500000 -0.000000
v 0.000000 -1.000000 -0.000000
v 1.000000 0.000000 0.000000
v 1.000000 -1.000000 -0.000000
vt 0.976031 1.084981
vt 0.738016 1.669965
vt 0.738016 1.084981
vt 0.499998 1.084981
vt 0.261984 1.669965
vt 0.261984 1.084981
vt 0.499998 -0.084982
vt 0.261984 0.500000
vt 0.261984 -0.084982
vt 0.976031 -0.084982
vt 0.738016 0.500000
vt 0.738016 -0.084982
vt 0.499998 0.500000
vt 0.738016 -0.669965
vt 0.499998 -0.669965
vt 0.976031 -0.669965
vt 0.023969 0.500000
vt 0.023969 -0.084982
vt 0.261984 -0.669965
vt 0.023969 -0.669965
vt 0.023969 1.669965
vt 0.023969 1.084981
vt 0.499998 1.669965
vt 0.976031 0.500000
vt 0.976031 1.669965
vn 0.0000 0.0000 -1.0000
usemtl None
s 1
f 1/1/1 2/2/1 3/3/1
f 4/4/1 5/5/1 6/6/1
f 7/7/1 8/8/1 9/9/1
f 10/10/1 11/11/1 12/12/1
f 12/12/1 13/13/1 7/7/1
f 14/14/1 7/7/1 15/15/1
f 16/16/1 12/12/1 14/14/1
f 9/9/1 17/17/1 18/18/1
f 19/19/1 18/18/1 20/20/1
f 15/15/1 9/9/1 19/19/1
f 6/6/1 21/21/1 22/22/1
f 8/8/1 22/22/1 17/17/1
f 13/13/1 6/6/1 8/8/1
f 3/3/1 23/23/1 4/4/1
f 11/11/1 4/4/1 13/13/1
f 24/24/1 3/3/1 11/11/1
f 1/1/1 25/25/1 2/2/1
f 4/4/1 23/23/1 5/5/1
f 7/7/1 13/13/1 8/8/1
f 10/10/1 24/24/1 11/11/1
f 12/12/1 11/11/1 13/13/1
f 14/14/1 12/12/1 7/7/1
f 16/16/1 10/10/1 12/12/1
f 9/9/1 8/8/1 17/17/1
f 19/19/1 9/9/1 18/18/1
f 15/15/1 7/7/1 9/9/1
f 6/6/1 5/5/1 21/21/1
f 8/8/1 6/6/1 22/22/1
f 13/13/1 4/4/1 6/6/1
f 3/3/1 2/2/1 23/23/1
f 11/11/1 3/3/1 4/4/1
f 24/24/1 1/1/1 3/3/1

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cloth_z_up.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cube.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,29 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cube.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision group="0" mask="0">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

Binary file not shown.

View File

@ -0,0 +1,22 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="base_link">
<contact>
<rolling_friction value="0.001"/>
<spinning_friction value="0.001"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.005"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="baseLink">
<contact>
<rolling_friction value="0.03"/>
<spinning_friction value="0.03"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
</geometry>
<material name="red_transparent">
<color rgba="1 0 0 0.5"/>
<specular rgb="11 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

View File

@ -0,0 +1,32 @@
# Blender v2.78 (sub 0) OBJ File: ''
# www.blender.org
mtllib stone.mtl
o Cube
v -0.246350 -0.246483 -0.000624
v -0.151407 -0.176325 0.172867
v -0.246350 0.249205 -0.000624
v -0.151407 0.129477 0.172867
v 0.249338 -0.246483 -0.000624
v 0.154395 -0.176325 0.172867
v 0.249338 0.249205 -0.000624
v 0.154395 0.129477 0.172867
vn -0.8772 0.0000 0.4801
vn 0.0000 0.8230 0.5680
vn 0.8772 0.0000 0.4801
vn 0.0000 -0.9271 0.3749
vn 0.0000 0.0000 -1.0000
vn 0.0000 0.0000 1.0000
usemtl None
s off
f 1//1 4//1 3//1
f 4//2 7//2 3//2
f 8//3 5//3 7//3
f 6//4 1//4 5//4
f 7//5 1//5 3//5
f 4//6 6//6 8//6
f 1//1 2//1 4//1
f 4//2 8//2 7//2
f 8//3 6//3 5//3
f 6//4 2//4 1//4
f 7//5 5//5 1//5
f 4//6 2//6 6//6

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<lateral_friction value="0.5"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0.07 0.05 0.03"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
</geometry>
<material name="red">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
</geometry>
</collision>
</link>
</robot>

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd ../cube.png

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot name="torus">
<deformable name="torus">
<inertial>
<mass value="3" />
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<collision_margin value="0.006"/>
<repulsion_stiffness value="800.0"/>
<friction value= "0.5"/>
<neohookean mu= "180" lambda= "600" damping= "0.01" />
<visual filename="torus.vtk"/>
</deformable>
</robot>

View File

@ -0,0 +1,14 @@
URDF created by Erwin Coumans
Bullet Continuous Collision Detection and Physics Library
http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd ../checker_grid.jpg

View File

@ -0,0 +1,949 @@
# Blender v2.78 (sub 0) OBJ File: ''
# www.blender.org
mtllib concave_box.mtl
o Cube_Cube.003
v 0.252358 -0.051546 0.073254
v 0.196823 -0.040500 0.026785
v 0.133463 -0.027897 -0.007745
v 0.064714 -0.014222 -0.029009
v 0.237323 -0.101112 0.073254
v 0.185009 -0.079443 0.026785
v 0.125326 -0.054721 -0.007745
v 0.060565 -0.027897 -0.029009
v 0.212906 -0.146792 0.073254
v 0.165826 -0.115334 0.026785
v 0.112112 -0.079443 -0.007745
v 0.053829 -0.040500 -0.029009
v 0.180047 -0.186831 0.073254
v 0.140008 -0.146792 0.026785
v 0.094329 -0.101112 -0.007745
v 0.044763 -0.051546 -0.029009
v 0.140008 -0.219690 0.073254
v 0.108550 -0.172609 0.026785
v 0.072660 -0.118895 -0.007745
v 0.033716 -0.060612 -0.029009
v -0.006783 -0.000000 -0.036189
v 0.094329 -0.244106 0.073254
v 0.072660 -0.191793 0.026785
v 0.047938 -0.132109 -0.007745
v 0.021113 -0.067349 -0.029009
v 0.044763 -0.259142 0.073254
v 0.033716 -0.203606 0.026785
v 0.021113 -0.140246 -0.007745
v 0.007438 -0.071497 -0.029009
v -0.006783 -0.264218 0.073254
v -0.006783 -0.207595 0.026785
v -0.006783 -0.142994 -0.007745
v -0.006783 -0.072898 -0.029009
v -0.058330 -0.259142 0.073254
v -0.047283 -0.203606 0.026785
v -0.034680 -0.140246 -0.007745
v -0.021005 -0.071497 -0.029009
v -0.107895 -0.244106 0.073254
v -0.086227 -0.191793 0.026785
v -0.061505 -0.132109 -0.007745
v -0.034680 -0.067349 -0.029009
v -0.153575 -0.219690 0.073254
v -0.122117 -0.172609 0.026785
v -0.086227 -0.118895 -0.007745
v -0.047283 -0.060612 -0.029009
v -0.193614 -0.186831 0.073254
v -0.153575 -0.146792 0.026785
v -0.107895 -0.101112 -0.007745
v -0.058330 -0.051546 -0.029009
v -0.226473 -0.146792 0.073254
v -0.179392 -0.115334 0.026785
v -0.125679 -0.079443 -0.007745
v -0.067396 -0.040500 -0.029009
v -0.250889 -0.101112 0.073254
v -0.198576 -0.079443 0.026785
v -0.138893 -0.054721 -0.007745
v -0.074132 -0.027897 -0.029009
v -0.265925 -0.051546 0.073254
v -0.210390 -0.040500 0.026785
v -0.147030 -0.027897 -0.007745
v -0.078280 -0.014222 -0.029009
v -0.271002 0.000000 0.073254
v -0.214378 0.000000 0.026785
v -0.149777 -0.000000 -0.007745
v -0.079681 -0.000000 -0.029009
v -0.265925 0.051546 0.073254
v -0.210390 0.040500 0.026785
v -0.147030 0.027897 -0.007745
v -0.078280 0.014222 -0.029009
v -0.250889 0.101112 0.073254
v -0.198576 0.079443 0.026785
v -0.138893 0.054721 -0.007745
v -0.074132 0.027897 -0.029009
v -0.226473 0.146792 0.073254
v -0.179392 0.115334 0.026785
v -0.125679 0.079443 -0.007745
v -0.067396 0.040500 -0.029009
v -0.193614 0.186831 0.073254
v -0.153575 0.146792 0.026785
v -0.107895 0.101112 -0.007745
v -0.058330 0.051546 -0.029009
v -0.153575 0.219690 0.073254
v -0.122117 0.172609 0.026785
v -0.086227 0.118895 -0.007745
v -0.047283 0.060612 -0.029009
v -0.107895 0.244106 0.073254
v -0.086227 0.191793 0.026785
v -0.061505 0.132109 -0.007745
v -0.034680 0.067349 -0.029009
v -0.058330 0.259141 0.073254
v -0.047283 0.203606 0.026785
v -0.034680 0.140246 -0.007745
v -0.021005 0.071497 -0.029009
v -0.006783 0.264218 0.073254
v -0.006783 0.207595 0.026785
v -0.006783 0.142994 -0.007745
v -0.006783 0.072898 -0.029009
v 0.044763 0.259141 0.073254
v 0.033716 0.203606 0.026785
v 0.021113 0.140246 -0.007745
v 0.007438 0.071497 -0.029009
v 0.094329 0.244106 0.073254
v 0.072660 0.191793 0.026785
v 0.047938 0.132109 -0.007745
v 0.021113 0.067349 -0.029009
v 0.140008 0.219689 0.073254
v 0.108550 0.172609 0.026785
v 0.072660 0.118895 -0.007745
v 0.033716 0.060612 -0.029009
v 0.180047 0.186831 0.073254
v 0.140008 0.146792 0.026785
v 0.094328 0.101112 -0.007745
v 0.044763 0.051546 -0.029009
v 0.212906 0.146792 0.073254
v 0.165825 0.115334 0.026785
v 0.112112 0.079443 -0.007745
v 0.053829 0.040500 -0.029009
v 0.237322 0.101112 0.073254
v 0.185009 0.079443 0.026785
v 0.125326 0.054721 -0.007745
v 0.060565 0.027897 -0.029009
v 0.252358 0.051546 0.073254
v 0.196823 0.040500 0.026785
v 0.133463 0.027897 -0.007745
v 0.064713 0.014222 -0.029009
v 0.257435 -0.000000 0.073254
v 0.200811 -0.000000 0.026785
v 0.136210 -0.000000 -0.007745
v 0.066114 -0.000000 -0.029009
v -1.000000 1.000000 -0.100000
v -1.000000 1.000000 0.100000
v 1.000000 1.000000 -0.100000
v 1.000000 1.000000 0.100000
v -1.000000 -1.000000 -0.100000
v -1.000000 -1.000000 0.100000
v 1.000000 -1.000000 -0.100000
v 1.000000 -1.000000 0.100000
v -0.006783 -0.286168 0.100000
v -0.062612 -0.280669 0.100000
v 0.195568 -0.202351 0.100000
v 0.231157 -0.158987 0.100000
v 0.257601 -0.109512 0.100000
v 0.195568 0.202351 0.100000
v -0.209135 0.202351 0.100000
v 0.273886 -0.055829 0.100000
v 0.273886 0.055829 0.100000
v 0.257601 0.109512 0.100000
v 0.152203 0.237940 0.100000
v -0.209135 -0.202351 0.100000
v -0.165770 -0.237940 0.100000
v -0.244724 -0.158986 0.100000
v -0.116295 -0.264385 0.100000
v -0.244723 0.158986 0.100000
v -0.165770 0.237940 0.100000
v -0.116295 0.264385 0.100000
v 0.231156 0.158986 0.100000
v -0.271168 -0.109512 0.100000
v -0.287453 0.055829 0.100000
v -0.292951 0.000000 0.100000
v 0.279384 -0.000000 0.100000
v 0.102728 -0.264385 0.100000
v 0.049045 0.280669 0.100000
v 0.049045 -0.280669 0.100000
v -0.287453 -0.055829 0.100000
v -0.062612 0.280669 0.100000
v -0.006783 0.286168 0.100000
v 0.152203 -0.237940 0.100000
v 0.102728 0.264385 0.100000
v -0.271168 0.109512 0.100000
vt 0.5258 0.8663
vt 0.5000 1.0000
vt 0.5000 0.8663
vt 0.5202 0.6339
vt 0.5000 0.6339
vt 0.5139 0.4613
vt 0.5000 0.4613
vt 0.5071 0.3550
vt 0.5000 0.3550
vt 0.5000 0.4966
vt 0.5071 0.5324
vt 0.5000 0.5331
vt 0.5139 0.5303
vt 0.5506 0.8663
vt 0.5279 1.0000
vt 0.5274 0.4613
vt 0.5139 0.3550
vt 0.5734 0.8663
vt 0.5548 1.0000
vt 0.5577 0.6339
vt 0.5397 0.6339
vt 0.5397 0.4613
vt 0.5202 0.3550
vt 0.5202 0.5269
vt 0.5258 0.5224
vt 0.6012 1.0000
vt 0.5795 1.0000
vt 0.5734 0.6339
vt 0.5506 0.4613
vt 0.5258 0.3550
vt 0.5700 0.6339
vt 0.5700 0.8663
vt 0.5900 0.8663
vt 0.5363 0.4613
vt 0.5472 0.4613
vt 0.5169 0.3550
vt 0.5224 0.3550
vt 0.5303 0.5169
vt 0.5978 1.0000
vt 0.5514 1.0000
vt 0.5761 1.0000
vt 0.5543 0.6339
vt 0.5472 0.8663
vt 0.5363 0.6339
vt 0.5240 0.4613
vt 0.5337 0.5106
vt 0.5224 0.8663
vt 0.5106 0.4613
vt 0.5106 0.3550
vt 0.5357 0.5037
vt 0.4966 1.0000
vt 0.5245 1.0000
vt 0.5169 0.6339
vt 0.4966 0.8663
vt 0.4966 0.6339
vt 0.5037 0.3550
vt 0.4966 0.4613
vt 0.5364 0.4966
vt 0.4827 0.4613
vt 0.4895 0.3550
vt 0.4966 0.3550
vt 0.5357 0.4895
vt 0.4708 0.8663
vt 0.4461 0.8663
vt 0.4687 1.0000
vt 0.4764 0.6339
vt 0.4569 0.6339
vt 0.4692 0.4613
vt 0.5337 0.4827
vt 0.4827 0.3550
vt 0.4569 0.4613
vt 0.5303 0.4764
vt 0.4232 0.8663
vt 0.4419 1.0000
vt 0.4389 0.6339
vt 0.4032 0.8663
vt 0.4171 1.0000
vt 0.4232 0.6339
vt 0.4708 0.3550
vt 0.4764 0.3550
vt 0.5258 0.4708
vt 0.5202 0.3550
vt 0.5506 0.4613
vt 0.5258 0.3550
vt 0.5202 0.4663
vt 0.5734 0.8663
vt 0.6012 1.0000
vt 0.5934 0.8663
vt 0.5734 0.6339
vt 0.5577 0.6339
vt 0.5506 0.8663
vt 0.5795 1.0000
vt 0.5274 0.4613
vt 0.5397 0.4613
vt 0.5139 0.4629
vt 0.5071 0.4609
vt 0.5279 1.0000
vt 0.5548 1.0000
vt 0.5202 0.6339
vt 0.5397 0.6339
vt 0.5139 0.4613
vt 0.5071 0.3550
vt 0.5139 0.3550
vt 0.5000 0.8663
vt 0.5258 0.8663
vt 0.5000 0.6339
vt 0.5000 0.4613
vt 0.5000 0.4602
vt 0.4929 0.4609
vt 0.4742 0.8663
vt 0.5000 1.0000
vt 0.4798 0.6339
vt 0.4861 0.4613
vt 0.4929 0.3550
vt 0.5000 0.3550
vt 0.4603 0.6339
vt 0.4726 0.4613
vt 0.4861 0.4629
vt 0.4494 0.8663
vt 0.4721 1.0000
vt 0.4266 0.8663
vt 0.4452 1.0000
vt 0.4603 0.4613
vt 0.4861 0.3550
vt 0.4798 0.4663
vt 0.4266 0.6339
vt 0.4423 0.6339
vt 0.4742 0.3550
vt 0.4798 0.3550
vt 0.4742 0.4708
vt 0.4066 0.8663
vt 0.4205 1.0000
vt 0.4232 0.8663
vt 0.3954 1.0000
vt 0.4032 0.8663
vt 0.4389 0.6339
vt 0.4232 0.6339
vt 0.4569 0.4613
vt 0.4461 0.4613
vt 0.4708 0.3550
vt 0.4697 0.4764
vt 0.4569 0.6339
vt 0.4827 0.3550
vt 0.4764 0.3550
vt 0.4663 0.4827
vt 0.4461 0.8663
vt 0.4171 1.0000
vt 0.4708 0.8663
vt 0.4419 1.0000
vt 0.4764 0.6339
vt 0.4827 0.4613
vt 0.4692 0.4613
vt 0.4895 0.3550
vt 0.4643 0.4895
vt 0.4966 0.3550
vt 0.4636 0.4966
vt 0.4966 0.8663
vt 0.4687 1.0000
vt 0.4966 0.6339
vt 0.5224 0.8663
vt 0.4966 1.0000
vt 0.5169 0.6339
vt 0.4966 0.4613
vt 0.5037 0.3550
vt 0.4643 0.5037
vt 0.5106 0.3550
vt 0.5106 0.4613
vt 0.4663 0.5106
vt 0.5472 0.8663
vt 0.5245 1.0000
vt 0.5363 0.6339
vt 0.5240 0.4613
vt 0.5700 0.8663
vt 0.5514 1.0000
vt 0.5363 0.4613
vt 0.5169 0.3550
vt 0.4697 0.5169
vt 0.4742 0.5224
vt 0.5900 0.8663
vt 0.5761 1.0000
vt 0.5700 0.6339
vt 0.5543 0.6339
vt 0.5224 0.3550
vt 0.4423 0.6339
vt 0.4066 0.8663
vt 0.4266 0.6339
vt 0.4603 0.4613
vt 0.4494 0.4613
vt 0.4798 0.3550
vt 0.4742 0.3550
vt 0.4798 0.5269
vt 0.4266 0.8663
vt 0.3988 1.0000
vt 0.4494 0.8663
vt 0.4205 1.0000
vt 0.4603 0.6339
vt 0.4861 0.3550
vt 0.4861 0.5303
vt 0.4798 0.6339
vt 0.4861 0.4613
vt 0.4726 0.4613
vt 0.4929 0.3550
vt 0.4929 0.5324
vt 0.4742 0.8663
vt 0.4452 1.0000
vt 0.4721 1.0000
vt 0.0000 1.0000
vt 1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt 1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt -1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt -1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 -1.0000
vt -1.0000 0.0000
vt -0.5279 -0.3631
vt -0.5000 -0.3603
vt -0.5000 0.3535
vt -0.5279 0.3563
vt -1.0000 0.0000
vt 0.5934 0.8663
vt 0.3954 1.0000
vt 0.4461 0.4613
vt 0.4494 0.4613
vt 0.3988 1.0000
vt 0.5978 1.0000
vt 0.5472 0.4613
vt 1.0000 1.0000
vt 1.0000 1.0000
vt -1.0000 1.0000
vt -1.0000 1.0000
vt 1.0000 -1.0000
vt -1.0000 -1.0000
vt -0.6431 -0.5034
vt -0.6403 -0.4755
vt -0.3569 -0.5034
vt 0.0000 -1.0000
vt 0.0000 0.0000
vt -0.3597 -0.4755
vt -0.6322 -0.4486
vt -0.6190 -0.4239
vt -0.3678 -0.4486
vt -0.3810 -0.4239
vt -0.6012 -0.4022
vt -0.5795 -0.3844
vt -0.3988 -0.4022
vt -0.4205 -0.3844
vt -0.5548 -0.3712
vt -0.4452 -0.3712
vt -0.4721 -0.3631
vt 0.0000 0.0000
vt -0.3569 0.4966
vt -0.3597 0.4687
vt -0.3678 0.4419
vt -0.6403 0.4687
vt -0.6431 0.4966
vt -0.6322 0.4419
vt -0.3810 0.4171
vt -0.3988 0.3954
vt -0.6190 0.4171
vt -0.6012 0.3954
vt -0.4205 0.3776
vt -0.4452 0.3644
vt -0.5795 0.3776
vt -0.5548 0.3644
vt -0.4721 0.3563
vn -0.7708 0.0759 0.6326
vn -0.6332 0.0624 0.7715
vn -0.4709 0.0464 0.8810
vn -0.2902 0.0286 0.9565
vn -0.0980 0.0097 0.9951
vn -0.0942 0.0286 0.9951
vn -0.7412 0.2248 0.6326
vn -0.6088 0.1847 0.7715
vn -0.4528 0.1374 0.8810
vn -0.2790 0.0846 0.9565
vn -0.6831 0.3651 0.6326
vn -0.5611 0.2999 0.7715
vn -0.4173 0.2230 0.8810
vn -0.2571 0.1374 0.9565
vn -0.0869 0.0464 0.9951
vn -0.0761 0.0625 0.9951
vn -0.5987 0.4913 0.6326
vn -0.4918 0.4036 0.7715
vn -0.3658 0.3002 0.8810
vn -0.2254 0.1850 0.9565
vn -0.4036 0.4918 0.7715
vn -0.3002 0.3658 0.8810
vn -0.1850 0.2254 0.9565
vn -0.0625 0.0761 0.9951
vn -0.4913 0.5987 0.6326
vn -0.3651 0.6831 0.6326
vn -0.2999 0.5611 0.7715
vn -0.2230 0.4173 0.8810
vn -0.1374 0.2571 0.9565
vn -0.0464 0.0869 0.9951
vn -0.1847 0.6088 0.7715
vn -0.1374 0.4528 0.8810
vn -0.0846 0.2790 0.9565
vn -0.0286 0.0942 0.9951
vn -0.2248 0.7412 0.6326
vn -0.0759 0.7708 0.6326
vn -0.0624 0.6332 0.7715
vn -0.0464 0.4709 0.8810
vn -0.0286 0.2902 0.9565
vn -0.0097 0.0980 0.9951
vn 0.0464 0.4709 0.8810
vn 0.0286 0.2902 0.9565
vn 0.0097 0.0980 0.9951
vn 0.0759 0.7708 0.6326
vn 0.0624 0.6332 0.7715
vn 0.2248 0.7412 0.6326
vn 0.1847 0.6088 0.7715
vn 0.1374 0.4528 0.8810
vn 0.0846 0.2790 0.9565
vn 0.0286 0.0942 0.9951
vn 0.1374 0.2571 0.9565
vn 0.0464 0.0869 0.9951
vn 0.3651 0.6831 0.6326
vn 0.2999 0.5611 0.7715
vn 0.2230 0.4173 0.8810
vn 0.4913 0.5987 0.6326
vn 0.4036 0.4918 0.7715
vn 0.3002 0.3658 0.8810
vn 0.1850 0.2254 0.9565
vn 0.0625 0.0761 0.9951
vn 0.2254 0.1850 0.9565
vn 0.0761 0.0625 0.9951
vn 0.5987 0.4913 0.6326
vn 0.4918 0.4036 0.7715
vn 0.3658 0.3002 0.8810
vn 0.6831 0.3651 0.6326
vn 0.5611 0.2999 0.7715
vn 0.4173 0.2230 0.8810
vn 0.2571 0.1374 0.9565
vn 0.0869 0.0464 0.9951
vn 0.0942 0.0286 0.9951
vn 0.7412 0.2248 0.6326
vn 0.6088 0.1847 0.7715
vn 0.4528 0.1374 0.8810
vn 0.2790 0.0846 0.9565
vn 0.7708 0.0759 0.6326
vn 0.6332 0.0624 0.7715
vn 0.4709 0.0464 0.8810
vn 0.2902 0.0286 0.9565
vn 0.0980 0.0097 0.9951
vn 0.0980 -0.0097 0.9951
vn 0.7708 -0.0759 0.6326
vn 0.6332 -0.0624 0.7715
vn 0.4709 -0.0464 0.8810
vn 0.2902 -0.0286 0.9565
vn 0.6088 -0.1847 0.7715
vn 0.4528 -0.1374 0.8810
vn 0.2790 -0.0846 0.9565
vn 0.0942 -0.0286 0.9951
vn 0.7412 -0.2248 0.6326
vn 0.6831 -0.3651 0.6326
vn 0.5611 -0.2999 0.7715
vn 0.4173 -0.2230 0.8810
vn 0.2571 -0.1374 0.9565
vn 0.0869 -0.0464 0.9951
vn 0.3658 -0.3002 0.8810
vn 0.2254 -0.1850 0.9565
vn 0.0761 -0.0625 0.9951
vn 0.5987 -0.4913 0.6326
vn 0.4918 -0.4036 0.7715
vn 0.4913 -0.5987 0.6326
vn 0.4036 -0.4918 0.7715
vn 0.3002 -0.3658 0.8810
vn 0.1850 -0.2254 0.9565
vn 0.0625 -0.0761 0.9951
vn 0.2230 -0.4173 0.8810
vn 0.1374 -0.2571 0.9565
vn 0.0464 -0.0869 0.9951
vn 0.3651 -0.6831 0.6326
vn 0.2999 -0.5611 0.7715
vn 0.2248 -0.7412 0.6326
vn 0.1847 -0.6088 0.7715
vn 0.1374 -0.4528 0.8810
vn 0.0846 -0.2790 0.9565
vn 0.0286 -0.0942 0.9951
vn 0.0286 -0.2902 0.9565
vn 0.0097 -0.0980 0.9951
vn 0.0759 -0.7708 0.6326
vn 0.0624 -0.6332 0.7715
vn 0.0464 -0.4709 0.8810
vn -0.0759 -0.7708 0.6326
vn -0.0624 -0.6332 0.7715
vn -0.0464 -0.4709 0.8810
vn -0.0286 -0.2902 0.9565
vn -0.0097 -0.0980 0.9951
vn -0.0846 -0.2790 0.9565
vn -0.0286 -0.0942 0.9951
vn -0.2248 -0.7412 0.6326
vn -0.1847 -0.6088 0.7715
vn -0.1374 -0.4528 0.8810
vn -0.3651 -0.6831 0.6326
vn -0.2999 -0.5611 0.7715
vn -0.2231 -0.4173 0.8810
vn -0.1374 -0.2571 0.9565
vn -0.0464 -0.0869 0.9951
vn -0.0625 -0.0761 0.9951
vn -0.4913 -0.5987 0.6326
vn -0.4036 -0.4918 0.7715
vn -0.3002 -0.3658 0.8810
vn -0.1850 -0.2254 0.9565
vn -0.4918 -0.4036 0.7715
vn -0.3658 -0.3002 0.8810
vn -0.2254 -0.1850 0.9565
vn -0.0761 -0.0625 0.9951
vn -0.5987 -0.4913 0.6326
vn -0.6831 -0.3651 0.6326
vn -0.5611 -0.2999 0.7715
vn -0.4173 -0.2231 0.8810
vn -0.2571 -0.1374 0.9565
vn -0.0869 -0.0464 0.9951
vn -0.6088 -0.1847 0.7715
vn -0.4528 -0.1374 0.8810
vn -0.2790 -0.0846 0.9565
vn -0.0942 -0.0286 0.9951
vn -0.7412 -0.2248 0.6326
vn -0.7708 -0.0759 0.6326
vn -0.6332 -0.0624 0.7715
vn -0.4709 -0.0464 0.8810
vn -0.2902 -0.0286 0.9565
vn -0.0980 -0.0097 0.9951
vn 0.0000 1.0000 0.0000
vn 1.0000 0.0000 0.0000
vn 0.0000 -1.0000 0.0000
vn -1.0000 0.0000 0.0000
vn 0.0000 0.0000 -1.0000
vn -0.0000 0.0000 1.0000
vn 0.2231 0.4173 0.8810
vn 0.4173 -0.2231 0.8810
vn -0.4173 -0.2230 0.8810
usemtl None
s off
f 1/1/1 160/2/1 126/3/1
f 2/4/2 126/3/2 127/5/2
f 3/6/3 127/5/3 128/7/3
f 4/8/4 128/7/4 129/9/4
f 21/10/5 4/11/5 129/12/5
f 21/10/6 8/13/6 4/11/6
f 5/14/7 145/15/7 1/1/7
f 2/4/8 5/14/8 1/1/8
f 7/16/9 2/4/9 3/6/9
f 8/17/10 3/6/10 4/8/10
f 9/18/11 142/19/11 5/14/11
f 10/20/12 5/14/12 6/21/12
f 11/22/13 6/21/13 7/16/13
f 12/23/14 7/16/14 8/17/14
f 21/10/15 12/24/15 8/13/15
f 21/10/16 16/25/16 12/24/16
f 9/18/17 140/26/17 141/27/17
f 14/28/18 9/18/18 10/20/18
f 15/29/19 10/20/19 11/22/19
f 16/30/20 11/22/20 12/23/20
f 14/31/21 17/32/21 13/33/21
f 19/34/22 14/31/22 15/35/22
f 20/36/23 15/35/23 16/37/23
f 21/10/24 20/38/24 16/25/24
f 17/32/25 140/39/25 13/33/25
f 17/32/26 161/40/26 167/41/26
f 18/42/27 22/43/27 17/32/27
f 19/34/28 23/44/28 18/42/28
f 20/36/29 24/45/29 19/34/29
f 21/10/30 25/46/30 20/38/30
f 23/44/31 26/47/31 22/43/31
f 28/48/32 23/44/32 24/45/32
f 25/49/33 28/48/33 24/45/33
f 21/10/34 29/50/34 25/46/34
f 26/47/35 161/40/35 22/43/35
f 26/47/36 138/51/36 163/52/36
f 27/53/37 30/54/37 26/47/37
f 28/48/38 31/55/38 27/53/38
f 29/56/39 32/57/39 28/48/39
f 21/10/40 33/58/40 29/50/40
f 36/59/41 31/55/41 32/57/41
f 37/60/42 32/57/42 33/61/42
f 21/10/43 37/62/43 33/58/43
f 34/63/44 138/51/44 30/54/44
f 31/55/45 34/63/45 30/54/45
f 38/64/46 139/65/46 34/63/46
f 35/66/47 38/64/47 34/63/47
f 36/59/48 39/67/48 35/66/48
f 37/60/49 40/68/49 36/59/49
f 21/10/50 41/69/50 37/62/50
f 41/70/51 44/71/51 40/68/51
f 21/10/52 45/72/52 41/69/52
f 42/73/53 152/74/53 38/64/53
f 43/75/54 38/64/54 39/67/54
f 44/71/55 39/67/55 40/68/55
f 46/76/56 150/77/56 42/73/56
f 43/75/57 46/76/57 42/73/57
f 44/71/58 47/78/58 43/75/58
f 49/79/59 44/71/59 45/80/59
f 21/10/60 49/81/60 45/72/60
f 53/82/61 48/83/61 49/84/61
f 21/10/62 53/85/62 49/81/62
f 50/86/63 149/87/63 46/88/63
f 47/89/64 50/86/64 46/88/64
f 48/83/65 51/90/65 47/89/65
f 54/91/66 151/92/66 50/86/66
f 51/90/67 54/91/67 50/86/67
f 56/93/68 51/90/68 52/94/68
f 53/82/69 56/93/69 52/94/69
f 21/10/70 57/95/70 53/85/70
f 21/10/71 61/96/71 57/95/71
f 54/91/72 164/97/72 157/98/72
f 59/99/73 54/91/73 55/100/73
f 60/101/74 55/100/74 56/93/74
f 61/102/75 56/93/75 57/103/75
f 62/104/76 164/97/76 58/105/76
f 63/106/77 58/105/77 59/99/77
f 64/107/78 59/99/78 60/101/78
f 61/102/79 64/107/79 60/101/79
f 21/10/80 65/108/80 61/96/80
f 21/10/81 69/109/81 65/108/81
f 66/110/82 159/111/82 62/104/82
f 67/112/83 62/104/83 63/106/83
f 68/113/84 63/106/84 64/107/84
f 69/114/85 64/107/85 65/115/85
f 71/116/86 66/110/86 67/112/86
f 72/117/87 67/112/87 68/113/87
f 69/114/88 72/117/88 68/113/88
f 21/10/89 73/118/89 69/109/89
f 70/119/90 158/120/90 66/110/90
f 74/121/91 169/122/91 70/119/91
f 71/116/92 74/121/92 70/119/92
f 76/123/93 71/116/93 72/117/93
f 73/124/94 76/123/94 72/117/94
f 21/10/95 77/125/95 73/118/95
f 76/123/96 79/126/96 75/127/96
f 81/128/97 76/123/97 77/129/97
f 21/10/98 81/130/98 77/125/98
f 78/131/99 153/132/99 74/121/99
f 79/126/100 74/121/100 75/127/100
f 82/133/101 144/134/101 78/135/101
f 83/136/102 78/135/102 79/137/102
f 84/138/103 79/137/103 80/139/103
f 81/140/104 84/138/104 80/139/104
f 21/10/105 85/141/105 81/130/105
f 84/138/106 87/142/106 83/136/106
f 89/143/107 84/138/107 85/144/107
f 21/10/108 89/145/108 85/141/108
f 86/146/109 154/147/109 82/133/109
f 87/142/110 82/133/110 83/136/110
f 90/148/111 155/149/111 86/146/111
f 91/150/112 86/146/112 87/142/112
f 92/151/113 87/142/113 88/152/113
f 93/153/114 88/152/114 89/143/114
f 21/10/115 93/154/115 89/145/115
f 97/155/116 92/151/116 93/153/116
f 21/10/117 97/156/117 93/154/117
f 94/157/118 165/158/118 90/148/118
f 95/159/119 90/148/119 91/150/119
f 92/151/120 95/159/120 91/150/120
f 98/160/121 166/161/121 94/157/121
f 99/162/122 94/157/122 95/159/122
f 96/163/123 99/162/123 95/159/123
f 101/164/124 96/163/124 97/155/124
f 21/10/125 101/165/125 97/156/125
f 105/166/126 100/167/126 101/164/126
f 21/10/127 105/168/127 101/165/127
f 102/169/128 162/170/128 98/160/128
f 103/171/129 98/160/129 99/162/129
f 104/172/130 99/162/130 100/167/130
f 106/173/131 168/174/131 102/169/131
f 103/171/132 106/173/132 102/169/132
f 108/175/133 103/171/133 104/172/133
f 109/176/134 104/172/134 105/166/134
f 21/10/135 109/177/135 105/168/135
f 21/10/136 113/178/136 109/177/136
f 110/179/137 148/180/137 106/173/137
f 111/181/138 106/173/138 107/182/138
f 108/175/139 111/181/139 107/182/139
f 113/183/140 108/175/140 109/176/140
f 115/184/141 110/185/141 111/186/141
f 116/187/142 111/186/142 112/188/142
f 117/189/143 112/188/143 113/190/143
f 21/10/144 117/191/144 113/178/144
f 114/192/145 143/193/145 110/185/145
f 118/194/146 156/195/146 114/192/146
f 119/196/147 114/192/147 115/184/147
f 116/187/148 119/196/148 115/184/148
f 121/197/149 116/187/149 117/189/149
f 21/10/150 121/198/150 117/191/150
f 123/199/151 118/194/151 119/196/151
f 124/200/152 119/196/152 120/201/152
f 125/202/153 120/201/153 121/197/153
f 21/10/154 125/203/154 121/198/154
f 122/204/155 147/205/155 118/194/155
f 126/3/156 146/206/156 122/204/156
f 127/5/157 122/204/157 123/199/157
f 128/7/158 123/199/158 124/200/158
f 129/9/159 124/200/159 125/202/159
f 21/10/160 129/12/160 125/203/160
f 131/207/161 132/208/161 130/209/161
f 133/210/162 136/211/162 132/212/162
f 137/213/163 134/214/163 136/215/163
f 135/216/164 130/217/164 134/218/164
f 136/211/165 130/219/165 132/212/165
f 133/220/166 146/221/166 160/222/166
f 159/223/166 158/224/166 131/225/166
f 1/1/1 145/15/1 160/2/1
f 2/4/2 1/1/2 126/3/2
f 3/6/3 2/4/3 127/5/3
f 4/8/4 3/6/4 128/7/4
f 5/14/7 142/19/7 145/15/7
f 2/4/8 6/21/8 5/14/8
f 7/16/9 6/21/9 2/4/9
f 8/17/10 7/16/10 3/6/10
f 9/18/11 141/27/11 142/19/11
f 10/20/12 9/18/12 5/14/12
f 11/22/13 10/20/13 6/21/13
f 12/23/14 11/22/14 7/16/14
f 9/18/17 13/226/17 140/26/17
f 14/28/18 13/226/18 9/18/18
f 15/29/19 14/28/19 10/20/19
f 16/30/20 15/29/20 11/22/20
f 14/31/21 18/42/21 17/32/21
f 19/34/22 18/42/22 14/31/22
f 20/36/23 19/34/23 15/35/23
f 17/32/25 167/41/25 140/39/25
f 17/32/26 22/43/26 161/40/26
f 18/42/27 23/44/27 22/43/27
f 19/34/28 24/45/28 23/44/28
f 20/36/29 25/49/29 24/45/29
f 23/44/31 27/53/31 26/47/31
f 28/48/32 27/53/32 23/44/32
f 25/49/33 29/56/33 28/48/33
f 26/47/35 163/52/35 161/40/35
f 26/47/36 30/54/36 138/51/36
f 27/53/37 31/55/37 30/54/37
f 28/48/38 32/57/38 31/55/38
f 29/56/39 33/61/39 32/57/39
f 36/59/41 35/66/41 31/55/41
f 37/60/42 36/59/42 32/57/42
f 34/63/44 139/65/44 138/51/44
f 31/55/45 35/66/45 34/63/45
f 38/64/46 152/74/46 139/65/46
f 35/66/47 39/67/47 38/64/47
f 36/59/48 40/68/48 39/67/48
f 37/60/49 41/70/49 40/68/49
f 41/70/51 45/80/51 44/71/51
f 42/73/53 150/77/53 152/74/53
f 43/75/54 42/73/54 38/64/54
f 44/71/167 43/75/167 39/67/167
f 46/76/56 149/227/56 150/77/56
f 43/75/57 47/78/57 46/76/57
f 44/71/58 48/228/58 47/78/58
f 49/79/59 48/228/59 44/71/59
f 53/82/61 52/94/61 48/83/61
f 50/86/63 151/92/63 149/87/63
f 47/89/64 51/90/64 50/86/64
f 48/83/65 52/94/65 51/90/65
f 54/91/66 157/98/66 151/92/66
f 51/90/67 55/100/67 54/91/67
f 56/93/68 55/100/68 51/90/68
f 53/82/69 57/103/69 56/93/69
f 54/91/72 58/105/72 164/97/72
f 59/99/73 58/105/73 54/91/73
f 60/101/74 59/99/74 55/100/74
f 61/102/75 60/101/75 56/93/75
f 62/104/76 159/111/76 164/97/76
f 63/106/77 62/104/77 58/105/77
f 64/107/78 63/106/78 59/99/78
f 61/102/79 65/115/79 64/107/79
f 66/110/82 158/120/82 159/111/82
f 67/112/83 66/110/83 62/104/83
f 68/113/84 67/112/84 63/106/84
f 69/114/85 68/113/85 64/107/85
f 71/116/86 70/119/86 66/110/86
f 72/117/87 71/116/87 67/112/87
f 69/114/88 73/124/88 72/117/88
f 70/119/90 169/122/90 158/120/90
f 74/121/91 153/132/91 169/122/91
f 71/116/92 75/127/92 74/121/92
f 76/123/168 75/127/168 71/116/168
f 73/124/94 77/129/94 76/123/94
f 76/123/96 80/229/96 79/126/96
f 81/128/97 80/229/97 76/123/97
f 78/131/99 144/230/99 153/132/99
f 79/126/100 78/131/100 74/121/100
f 82/133/101 154/147/101 144/134/101
f 83/136/102 82/133/102 78/135/102
f 84/138/103 83/136/103 79/137/103
f 81/140/104 85/144/104 84/138/104
f 84/138/106 88/152/106 87/142/106
f 89/143/107 88/152/107 84/138/107
f 86/146/109 155/149/109 154/147/109
f 87/142/110 86/146/110 82/133/110
f 90/148/111 165/158/111 155/149/111
f 91/150/112 90/148/112 86/146/112
f 92/151/113 91/150/113 87/142/113
f 93/153/114 92/151/114 88/152/114
f 97/155/116 96/163/116 92/151/116
f 94/157/118 166/161/118 165/158/118
f 95/159/119 94/157/119 90/148/119
f 92/151/120 96/163/120 95/159/120
f 98/160/121 162/170/121 166/161/121
f 99/162/122 98/160/122 94/157/122
f 96/163/123 100/167/123 99/162/123
f 101/164/124 100/167/124 96/163/124
f 105/166/126 104/172/126 100/167/126
f 102/169/128 168/174/128 162/170/128
f 103/171/129 102/169/129 98/160/129
f 104/172/130 103/171/130 99/162/130
f 106/173/131 148/180/131 168/174/131
f 103/171/132 107/182/132 106/173/132
f 108/175/133 107/182/133 103/171/133
f 109/176/134 108/175/134 104/172/134
f 110/179/137 143/231/137 148/180/137
f 111/181/138 110/179/138 106/173/138
f 108/175/139 112/232/139 111/181/139
f 113/183/140 112/232/140 108/175/140
f 115/184/141 114/192/141 110/185/141
f 116/187/142 115/184/142 111/186/142
f 117/189/143 116/187/143 112/188/143
f 114/192/145 156/195/145 143/193/145
f 118/194/146 147/205/146 156/195/146
f 119/196/147 118/194/147 114/192/147
f 116/187/169 120/201/169 119/196/169
f 121/197/149 120/201/149 116/187/149
f 123/199/151 122/204/151 118/194/151
f 124/200/152 123/199/152 119/196/152
f 125/202/153 124/200/153 120/201/153
f 122/204/155 146/206/155 147/205/155
f 126/3/156 160/2/156 146/206/156
f 127/5/157 126/3/157 122/204/157
f 128/7/158 127/5/158 123/199/158
f 129/9/159 128/7/159 124/200/159
f 131/207/161 133/233/161 132/208/161
f 133/210/162 137/234/162 136/211/162
f 137/213/163 135/235/163 134/214/163
f 135/216/164 131/236/164 130/217/164
f 136/211/165 134/237/165 130/219/165
f 133/220/166 131/238/166 166/239/166
f 133/220/166 166/239/166 162/240/166
f 138/241/166 135/242/166 137/243/166
f 163/244/166 138/241/166 137/243/166
f 133/220/166 162/240/166 168/245/166
f 133/220/166 168/245/166 148/246/166
f 161/247/166 163/244/166 137/243/166
f 167/248/166 161/247/166 137/243/166
f 133/220/166 148/246/166 143/249/166
f 133/220/166 143/249/166 156/250/166
f 140/251/166 167/248/166 137/243/166
f 141/252/166 140/251/166 137/243/166
f 137/243/166 133/220/166 160/222/166
f 133/220/166 156/250/166 147/253/166
f 142/254/166 141/252/166 137/243/166
f 145/255/166 142/254/166 137/243/166
f 133/220/166 147/253/166 146/221/166
f 160/222/166 145/255/166 137/243/166
f 135/256/166 138/257/166 139/258/166
f 135/256/166 139/258/166 152/259/166
f 165/260/166 166/261/166 131/225/166
f 155/262/166 165/260/166 131/225/166
f 135/256/166 152/259/166 150/263/166
f 135/256/166 150/263/166 149/264/166
f 154/265/166 155/262/166 131/225/166
f 144/266/166 154/265/166 131/225/166
f 135/256/166 149/264/166 151/267/166
f 135/256/166 151/267/166 157/268/166
f 153/269/166 144/266/166 131/225/166
f 169/270/166 153/269/166 131/225/166
f 131/225/166 135/256/166 159/223/166
f 135/256/166 157/268/166 164/271/166
f 158/224/166 169/270/166 131/225/166
f 135/256/166 164/271/166 159/223/166

View File

@ -0,0 +1,30 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="base_link">
<contact>
<rolling_friction value="0.001"/>
<spinning_friction value="0.001"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="concave_box.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cdf filename="concave_box.cdf" scale="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 1
newmtl Material.002
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.017444 0.640000 0.032216
Ks 0.034126 0.500000 0.031333
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,64 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib cube.mtl
o Cube.001_Cube.002
v -0.231854 0.040516 -0.056463
v -0.231854 0.040516 -0.121937
v -0.144556 0.040516 -0.121937
v -0.144556 0.040516 -0.056463
v -0.231854 0.127815 -0.056463
v -0.231854 0.127815 -0.121937
v -0.144556 0.127815 -0.121937
v -0.144556 0.127815 -0.056463
v -0.231854 0.040516 -0.056463
v -0.231854 0.040516 -0.121937
v -0.144556 0.040516 -0.121937
v -0.144556 0.040516 -0.056463
v -0.231854 0.127815 -0.056463
v -0.231854 0.127815 -0.121937
v -0.144556 0.127815 -0.121937
v -0.144556 0.127815 -0.056463
vt 1.044600 0.042083
vt 1.044600 -0.957917
vt 0.044600 -0.957917
vt 1.905897 0.042083
vt 1.905897 -0.957917
vt 0.905898 -0.957917
vt -0.955400 0.042083
vt -0.955400 -0.957917
vt -0.094102 0.042083
vt -0.094102 -0.957917
vt 0.905898 1.044600
vt 1.905897 1.044600
vt 1.905897 0.044600
vt -0.094102 1.044600
vt -0.094102 0.044600
vt 0.044600 0.042083
vt 0.905898 0.042083
vt 0.905898 0.044600
usemtl Material.002
s off
f 6/1 2/2 1/3
f 7/4 3/5 2/6
f 8/7 4/8 3/3
f 5/9 1/10 4/6
f 2/11 3/12 4/13
f 7/11 6/14 5/15
f 14/1 10/2 9/3
f 15/4 11/5 10/6
f 16/7 12/8 11/3
f 13/9 9/10 12/6
f 10/11 11/12 12/13
f 15/11 14/14 13/15
f 5/16 6/1 1/3
f 6/17 7/4 2/6
f 7/16 8/7 3/3
f 8/17 5/9 4/6
f 1/18 2/11 4/13
f 8/18 7/11 5/15
f 13/16 14/1 9/3
f 14/17 15/4 10/6
f 15/16 16/7 11/3
f 16/17 13/9 12/6
f 9/18 10/11 12/13
f 16/18 15/11 13/15

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 1
newmtl Material.001
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.013473 0.018536 0.640000
Ks 0.500000 0.500000 0.500000
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,282 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib cylinder.mtl
o Cylinder.001
v -0.291246 0.045696 0.165546
v -0.214241 0.045696 0.165546
v -0.291246 0.034429 0.166100
v -0.214241 0.034429 0.166100
v -0.291246 0.023595 0.167744
v -0.214241 0.023595 0.167744
v -0.291246 0.013610 0.170412
v -0.214241 0.013610 0.170412
v -0.291246 0.004859 0.174003
v -0.214241 0.004858 0.174003
v -0.291246 -0.002324 0.178379
v -0.214241 -0.002324 0.178379
v -0.291246 -0.007661 0.183372
v -0.214241 -0.007661 0.183372
v -0.291246 -0.010947 0.188789
v -0.214241 -0.010947 0.188789
v -0.291246 -0.012057 0.194422
v -0.214241 -0.012057 0.194422
v -0.291246 -0.010947 0.200056
v -0.214241 -0.010947 0.200056
v -0.291246 -0.007661 0.205473
v -0.214241 -0.007661 0.205473
v -0.291246 -0.002324 0.210465
v -0.214241 -0.002324 0.210465
v -0.291246 0.004859 0.214841
v -0.214241 0.004858 0.214841
v -0.291246 0.013610 0.218432
v -0.214241 0.013610 0.218432
v -0.291246 0.023595 0.221101
v -0.214241 0.023595 0.221101
v -0.291246 0.034429 0.222744
v -0.214241 0.034429 0.222744
v -0.291246 0.045696 0.223299
v -0.214241 0.045696 0.223299
v -0.291246 0.056963 0.222744
v -0.214241 0.056963 0.222744
v -0.291246 0.067797 0.221101
v -0.214241 0.067797 0.221101
v -0.291246 0.077782 0.218432
v -0.214241 0.077782 0.218432
v -0.291246 0.086534 0.214841
v -0.214241 0.086534 0.214841
v -0.291246 0.093716 0.210465
v -0.214241 0.093716 0.210465
v -0.291246 0.099053 0.205473
v -0.214241 0.099053 0.205473
v -0.291246 0.102340 0.200056
v -0.214241 0.102340 0.200056
v -0.291246 0.103449 0.194422
v -0.214241 0.103449 0.194422
v -0.291246 0.102340 0.188789
v -0.214241 0.102340 0.188789
v -0.291246 0.099053 0.183371
v -0.214241 0.099053 0.183371
v -0.291246 0.093716 0.178379
v -0.214241 0.093716 0.178379
v -0.291246 0.086534 0.174003
v -0.214241 0.086534 0.174003
v -0.291246 0.077782 0.170412
v -0.214241 0.077782 0.170412
v -0.291246 0.067797 0.167744
v -0.214241 0.067797 0.167744
v -0.291246 0.056963 0.166100
v -0.214241 0.056963 0.166100
vt 0.306049 0.488177
vt 0.092448 0.519423
vt 0.067655 0.516411
vt 0.270128 0.485165
vt 0.049219 0.513369
vt 0.232794 0.482123
vt 0.034123 0.510414
vt 0.020864 0.507658
vt 0.163092 0.476412
vt 0.008587 0.505209
vt 0.133302 0.473963
vt 1.008587 0.505209
vt 0.996728 0.503160
vt 1.106812 0.471914
vt 0.984865 0.501590
vt 1.082707 0.470344
vt 0.972628 0.500559
vt 0.959652 0.500107
vt 1.036012 0.468861
vt 0.945535 0.500252
vt 1.008811 0.469006
vt 0.929810 0.500987
vt 0.972352 0.469741
vt 0.911918 0.502285
vt 0.913273 0.471038
vt 0.891203 0.504095
vt 0.866959 0.506348
vt 0.698338 0.475102
vt 0.838607 0.508958
vt 0.630535 0.477711
vt 0.806049 0.511823
vt 0.592448 0.480577
vt 0.770128 0.514835
vt 0.732794 0.517877
vt 0.549219 0.486631
vt 0.696491 0.520833
vt 0.534123 0.489586
vt 0.663092 0.523588
vt 0.520864 0.492342
vt 0.633302 0.526037
vt 0.508586 0.494791
vt 0.606812 0.528086
vt 0.496728 0.496840
vt 0.582707 0.529656
vt 0.559695 0.530687
vt 0.472628 0.499441
vt 0.536012 0.531139
vt 0.459652 0.499893
vt 0.508810 0.530994
vt 0.445535 0.499748
vt 0.472352 0.530259
vt 0.413273 0.528962
vt 0.411918 0.497715
vt 0.310810 0.527152
vt 0.391202 0.495905
vt 0.198337 0.524898
vt 1.020864 0.507658
vt 1.034123 0.510414
vt 0.130535 0.522289
vt 0.366959 0.493652
vt 1.391202 0.495905
vt 0.196491 0.479167
vt 1.133302 0.473963
vt 1.059695 0.469313
vt 0.810811 0.472848
vt 0.567655 0.483589
vt 0.484865 0.498410
vt 0.429810 0.499013
vt 1.092448 0.519423
vt 1.067655 0.516411
vt 1.198337 0.524898
vt 1.413273 0.528962
vt 1.310810 0.527152
vt 1.472352 0.530259
vt 1.130535 0.522289
vt 1.049219 0.513369
vt 0.338607 0.491042
vt 1.270128 0.485165
vt 1.306049 0.488177
vt 1.196491 0.479167
vt 1.232794 0.482123
vt 1.163092 0.476412
vt 1.366959 0.493652
vt 1.338607 0.491042
vt 1.429810 0.499013
vt 1.411918 0.497715
vt 1.445535 0.499748
vt 1.459652 0.499893
usemtl Material.001
s off
f 1/1 2/2 4/3
f 3/4 4/3 6/5
f 5/6 6/5 8/7
f 8/7 10/8 9/9
f 10/8 12/10 11/11
f 12/12 14/13 13/14
f 14/13 16/15 15/16
f 15/16 16/15 18/17
f 18/17 20/18 19/19
f 20/18 22/20 21/21
f 22/20 24/22 23/23
f 24/22 26/24 25/25
f 25/25 26/24 28/26
f 28/26 30/27 29/28
f 30/27 32/29 31/30
f 32/29 34/31 33/32
f 33/32 34/31 36/33
f 36/33 38/34 37/35
f 38/34 40/36 39/37
f 40/36 42/38 41/39
f 42/38 44/40 43/41
f 44/40 46/42 45/43
f 45/43 46/42 48/44
f 48/44 50/45 49/46
f 50/45 52/47 51/48
f 52/47 54/49 53/50
f 53/50 54/49 56/51
f 56/51 58/52 57/53
f 58/52 60/54 59/55
f 59/55 60/54 62/56
f 26/24 10/57 8/58
f 64/59 2/2 1/1
f 61/60 62/56 64/59
f 37/35 39/37 59/61
f 3/4 1/1 4/3
f 5/6 3/4 6/5
f 7/62 5/6 8/7
f 7/62 8/7 9/9
f 9/9 10/8 11/11
f 11/63 12/12 13/14
f 13/14 14/13 15/16
f 17/64 15/16 18/17
f 17/64 18/17 19/19
f 19/19 20/18 21/21
f 21/21 22/20 23/23
f 23/23 24/22 25/25
f 27/65 25/25 28/26
f 27/65 28/26 29/28
f 29/28 30/27 31/30
f 31/30 32/29 33/32
f 35/66 33/32 36/33
f 35/66 36/33 37/35
f 37/35 38/34 39/37
f 39/37 40/36 41/39
f 41/39 42/38 43/41
f 43/41 44/40 45/43
f 47/67 45/43 48/44
f 47/67 48/44 49/46
f 49/46 50/45 51/48
f 51/48 52/47 53/50
f 55/68 53/50 56/51
f 55/68 56/51 57/53
f 57/53 58/52 59/55
f 61/60 59/55 62/56
f 2/69 34/31 4/70
f 38/34 36/33 62/71
f 58/72 40/36 60/73
f 54/49 44/40 56/74
f 50/45 48/44 52/47
f 46/42 54/49 48/44
f 14/13 22/20 20/18
f 12/12 10/57 24/22
f 2/69 64/75 34/31
f 30/27 6/76 32/29
f 26/24 8/58 28/26
f 63/77 61/60 64/59
f 64/75 36/33 34/31
f 14/13 20/18 16/15
f 44/40 42/38 56/74
f 40/36 38/34 60/73
f 38/34 62/71 60/73
f 10/57 26/24 24/22
f 48/44 54/49 52/47
f 34/31 32/29 4/70
f 8/58 6/76 28/26
f 54/49 46/42 44/40
f 20/18 18/17 16/15
f 42/38 58/72 56/74
f 63/77 64/59 1/1
f 32/29 6/76 4/70
f 12/12 24/22 14/13
f 58/72 42/38 40/36
f 36/33 64/75 62/71
f 24/22 22/20 14/13
f 6/76 30/27 28/26
f 3/78 31/30 1/79
f 7/80 29/28 5/81
f 11/63 23/23 9/82
f 15/16 21/21 13/14
f 15/16 17/64 19/19
f 61/83 63/84 35/66
f 27/65 7/80 25/25
f 41/39 55/85 57/86
f 35/66 63/84 33/32
f 53/87 55/85 43/41
f 43/41 55/85 41/39
f 47/67 53/87 45/43
f 47/67 49/46 51/88
f 59/61 39/37 57/86
f 29/28 31/30 5/81
f 7/80 27/65 29/28
f 45/43 53/87 43/41
f 47/67 51/88 53/87
f 61/83 37/35 59/61
f 31/30 3/78 5/81
f 15/16 19/19 21/21
f 21/21 23/23 13/14
f 39/37 41/39 57/86
f 7/80 9/82 25/25
f 1/79 31/30 33/32
f 23/23 11/63 13/14
f 9/82 23/23 25/25
f 37/35 61/83 35/66
f 63/84 1/79 33/32

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 1
newmtl Material.003
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.640000 0.007339 0.006282
Ks 0.500000 0.500000 0.500000
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,45 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib prism.mtl
o Cube.002_Cube.005
v -0.233641 -0.103557 0.060897
v -0.233641 -0.103557 -0.057063
v -0.149383 -0.103557 -0.057063
v -0.149383 -0.103557 0.060897
v -0.233013 -0.039217 0.035115
v -0.233013 -0.039217 -0.031280
v -0.150011 -0.039217 -0.031280
v -0.150011 -0.039217 0.035115
vt 0.780473 0.523151
vt 0.999041 -0.022288
vt -0.000959 -0.022288
vt 1.896793 0.523151
vt 1.904244 -0.022288
vt 0.904244 -0.022288
vt 0.217610 0.523151
vt -0.088305 0.523151
vt -0.095756 -0.022288
vt 0.904244 1.999041
vt 1.904244 1.999041
vt 1.904244 0.999041
vt 0.896793 0.780473
vt -0.088305 0.780473
vt -0.088305 0.217610
vt 0.911695 0.523151
vt 0.896793 0.523151
vt 0.904244 0.999041
vt 0.896793 0.217610
usemtl Material.003
s off
f 6/1 2/2 1/3
f 7/4 3/5 2/6
f 8/7 4/3 3/2
f 5/8 1/9 4/6
f 2/10 3/11 4/12
f 7/13 6/14 5/15
f 5/7 6/1 1/3
f 6/16 7/4 2/6
f 7/1 8/7 3/2
f 8/17 5/8 4/6
f 1/18 2/10 4/12
f 8/19 7/13 5/15

View File

@ -0,0 +1,21 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 2
newmtl Material.004
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.640000 0.640000 0.640000
Ks 0.500000 0.500000 0.500000
Ni 1.000000
d 1.000000
illum 2
map_Kd E:\develop\bullet3\data\table\table.png
newmtl Material.004_NONE
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.640000 0.640000 0.640000
Ks 0.500000 0.500000 0.500000
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,400 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib shape_sorter.mtl
o Cube
v -0.200000 0.200000 -0.200000
v -0.200000 -0.200000 -0.200000
v -0.200000 0.037707 -0.055248
v -0.200000 0.037707 -0.124929
v -0.200000 0.130615 -0.124929
v -0.200000 0.130615 -0.055248
v -0.200000 -0.200000 0.200000
v -0.200000 0.014752 0.076444
v -0.200000 -0.109627 0.071917
v -0.200000 -0.109627 -0.068083
v -0.200000 -0.033266 -0.037483
v -0.200000 -0.033266 0.041318
v -0.200000 0.015905 0.070592
v -0.200000 0.019320 0.064964
v -0.200000 0.024864 0.059777
v -0.200000 0.032326 0.055231
v -0.200000 0.041418 0.051500
v -0.200000 0.051791 0.048728
v -0.200000 0.063047 0.047021
v -0.200000 0.074753 0.046444
v -0.200000 0.086458 0.047021
v -0.200000 0.097713 0.048728
v -0.200000 0.108087 0.051500
v -0.200000 0.117179 0.055231
v -0.200000 0.124641 0.059777
v -0.200000 0.130185 0.064964
v -0.200000 0.133600 0.070592
v -0.200000 0.200000 0.200000
v 0.200000 0.200000 -0.200000
v 0.200000 -0.200000 -0.200000
v -0.179938 0.037707 -0.055248
v -0.179938 0.037707 -0.124929
v -0.179938 0.130615 -0.124929
v -0.179938 0.130615 -0.055248
v -0.179938 0.200000 0.179938
v -0.179938 0.200000 -0.179938
v 0.179938 0.200000 -0.179938
v 0.200000 -0.200000 0.200000
v -0.200000 0.134752 0.076444
v -0.200000 0.133600 0.082297
v -0.200000 0.130185 0.087925
v -0.200000 0.124641 0.093111
v -0.200000 0.117179 0.097657
v -0.200000 0.108087 0.101388
v -0.200000 0.097714 0.104161
v -0.200000 0.086458 0.105868
v -0.200000 0.074753 0.106444
v -0.200000 0.063047 0.105868
v -0.200000 0.051792 0.104161
v -0.200000 0.041418 0.101388
v -0.200000 0.032326 0.097657
v -0.200000 0.024864 0.093111
v -0.200000 0.019320 0.087925
v -0.200000 0.015905 0.082297
v -0.179938 0.014752 0.076444
v -0.179938 0.015905 0.070592
v -0.179938 0.019320 0.064964
v -0.179938 0.024864 0.059777
v -0.179938 0.032326 0.055231
v -0.179938 0.041418 0.051500
v -0.179938 0.051791 0.048728
v -0.179938 0.063047 0.047021
v -0.179938 0.074752 0.046444
v -0.179938 0.086458 0.047021
v -0.179938 0.097713 0.048728
v -0.179938 0.108087 0.051500
v -0.179938 0.117179 0.055231
v -0.179938 0.124641 0.059777
v -0.179938 0.130185 0.064964
v -0.179938 0.133600 0.070592
v 0.200000 0.200000 0.200000
v -0.179938 -0.185168 -0.179938
v 0.179938 0.200000 0.179938
v -0.179938 -0.185168 0.179938
v -0.179938 0.015905 0.082297
v -0.179938 0.019320 0.087925
v -0.179938 0.024864 0.093111
v -0.179938 0.032326 0.097657
v -0.179938 0.041418 0.101388
v -0.179938 0.051791 0.104161
v -0.179938 0.063047 0.105868
v -0.179938 0.074753 0.106444
v -0.179938 0.086458 0.105868
v -0.179938 0.097714 0.104161
v -0.179938 0.108087 0.101388
v -0.179938 0.117179 0.097657
v -0.179938 0.124641 0.093111
v -0.179938 0.130185 0.087925
v -0.179938 0.133600 0.082297
v -0.179938 0.134752 0.076444
v 0.179938 -0.185168 -0.179938
v -0.179938 -0.109627 0.071917
v -0.179938 -0.033266 0.041318
v -0.179938 -0.033266 -0.037483
v -0.179938 -0.109627 -0.068083
v 0.179938 -0.185168 0.179938
vt 0.337529 0.596545
vt 0.387821 0.596545
vt 0.283346 0.663317
vt 0.379674 0.386434
vt 0.283346 0.278382
vt 0.572047 0.278383
vt 0.387821 0.507137
vt 0.461218 0.542787
vt 0.461634 0.554051
vt 0.372847 0.595850
vt 0.372847 0.369934
vt 0.391646 0.506894
vt 0.343069 0.506894
vt 0.337529 0.507137
vt 0.343069 0.593253
vt 0.391646 0.593253
vt 0.304720 0.657748
vt 0.378834 0.597878
vt 0.542284 0.369934
vt 0.572047 0.663317
vt 0.504523 0.542787
vt 0.504107 0.531523
vt 0.482871 0.485047
vt 0.483455 0.485557
vt 0.479374 0.486628
vt 0.478646 0.486156
vt 0.475451 0.489802
vt 0.474584 0.489442
vt 0.471835 0.494956
vt 0.467560 0.501959
vt 0.470841 0.494778
vt 0.468666 0.501892
vt 0.466065 0.510343
vt 0.462866 0.520691
vt 0.464867 0.510708
vt 0.461634 0.531522
vt 0.464132 0.519985
vt 0.462942 0.530448
vt 0.462540 0.541328
vt 0.462942 0.552208
vt 0.462866 0.564883
vt 0.464132 0.562671
vt 0.466065 0.572313
vt 0.467560 0.583615
vt 0.464867 0.574866
vt 0.468666 0.580764
vt 0.471835 0.587700
vt 0.474584 0.596132
vt 0.470841 0.590796
vt 0.475451 0.592854
vt 0.479374 0.596028
vt 0.542284 0.595850
vt 0.304720 0.299726
vt 0.555605 0.657748
vt 0.504369 0.541328
vt 0.503967 0.552209
vt 0.378834 0.375736
vt 0.383150 0.371876
vt 0.555605 0.299726
vt 0.478646 0.599418
vt 0.483455 0.597099
vt 0.482870 0.600527
vt 0.487535 0.596028
vt 0.487095 0.599418
vt 0.491458 0.592854
vt 0.491157 0.596132
vt 0.495074 0.587700
vt 0.494900 0.590796
vt 0.498243 0.580764
vt 0.498181 0.583615
vt 0.500844 0.572313
vt 0.502875 0.564883
vt 0.500874 0.574866
vt 0.502777 0.562671
vt 0.504107 0.554052
vt 0.503967 0.530448
vt 0.502777 0.519985
vt 0.502875 0.520691
vt 0.500844 0.510343
vt 0.500874 0.510708
vt 0.498243 0.501892
vt 0.498181 0.501959
vt 0.495074 0.494956
vt 0.494900 0.494778
vt 0.491458 0.489802
vt 0.491157 0.489442
vt 0.487535 0.486628
vt 0.487095 0.486156
vt 0.534501 0.375736
vt 0.534501 0.597878
vt 0.478009 0.388189
vt 0.400119 0.458779
vt 0.457642 0.460616
vt 0.480077 0.374691
vt 0.459415 0.445604
vt 0.404578 0.442049
vt 0.000000 0.000000
usemtl Material.004
s off
f 5/1 6/2 1/3
f 10/4 2/5 7/6
f 3/7 20/8 21/9
f 29/10 30/11 2/5
f 3/7 31/12 32/13
f 4/14 32/13 33/15
f 34/16 6/2 5/1
f 36/17 37/18 29/10
f 31/12 3/7 6/2
f 2/5 30/11 38/19
f 28/20 47/21 48/22
f 8/23 55/24 56/25
f 13/26 56/25 57/27
f 14/28 57/27 58/29
f 16/30 15/31 58/29
f 16/30 59/32 60/33
f 18/34 17/35 60/33
f 19/36 18/34 61/37
f 20/8 19/36 62/38
f 20/8 63/39 64/40
f 22/41 21/9 64/40
f 22/41 65/42 66/43
f 24/44 23/45 66/43
f 24/44 67/46 68/47
f 26/48 25/49 68/47
f 26/48 69/50 70/51
f 71/52 38/19 30/11
f 32/13 31/12 72/53
f 71/52 29/10 37/18
f 35/54 82/55 83/56
f 36/17 72/53 91/57
f 62/38 61/37 31/12
f 95/58 74/59 72/53
f 28/20 7/6 38/19
f 27/60 70/51 90/61
f 39/62 90/61 89/63
f 40/64 89/63 88/65
f 41/66 88/65 87/67
f 42/68 87/67 86/69
f 43/70 86/69 85/71
f 45/72 44/73 85/71
f 45/72 84/74 83/56
f 46/75 83/56 82/55
f 47/21 82/55 81/76
f 48/22 81/76 80/77
f 49/78 80/77 79/79
f 50/80 79/79 78/81
f 51/82 78/81 77/83
f 52/84 77/83 76/85
f 53/86 76/85 75/87
f 54/88 75/87 55/24
f 37/18 91/57 96/89
f 73/90 96/89 74/59
f 74/59 96/89 91/57
f 2/5 3/7 4/14
f 7/6 8/23 9/91
f 1/3 2/5 4/14
f 1/3 4/14 5/1
f 10/4 11/92 3/7
f 9/91 10/4 7/6
f 10/4 3/7 2/5
f 12/93 16/30 11/92
f 28/20 1/3 6/2
f 12/93 9/91 8/23
f 27/60 28/20 6/2
f 14/28 15/31 12/93
f 12/93 8/23 13/26
f 26/48 27/60 6/2
f 12/93 13/26 14/28
f 25/49 26/48 6/2
f 1/3 29/10 2/5
f 24/44 25/49 6/2
f 3/7 16/30 17/35
f 23/45 24/44 6/2
f 3/7 17/35 18/34
f 22/41 23/45 6/2
f 3/7 18/34 19/36
f 21/9 22/41 6/2
f 16/30 3/7 11/92
f 6/2 3/7 21/9
f 12/93 15/31 16/30
f 4/14 3/7 32/13
f 3/7 19/36 20/8
f 5/1 4/14 33/15
f 33/15 34/16 5/1
f 1/3 28/20 35/54
f 34/16 31/12 6/2
f 1/3 35/54 36/17
f 36/17 29/10 1/3
f 7/6 2/5 38/19
f 28/20 27/60 39/62
f 54/88 8/23 7/6
f 28/20 39/62 40/64
f 53/86 54/88 7/6
f 28/20 40/64 41/66
f 52/84 53/86 7/6
f 28/20 41/66 42/68
f 51/82 52/84 7/6
f 28/20 42/68 43/70
f 50/80 51/82 7/6
f 28/20 43/70 44/73
f 49/78 50/80 7/6
f 44/73 45/72 28/20
f 7/6 28/20 49/78
f 28/20 45/72 46/75
f 14/28 13/26 57/27
f 13/26 8/23 56/25
f 28/20 48/22 49/78
f 28/20 46/75 47/21
f 15/31 14/28 58/29
f 59/32 16/30 58/29
f 17/35 16/30 60/33
f 61/37 18/34 60/33
f 62/38 19/36 61/37
f 63/39 20/8 62/38
f 21/9 20/8 64/40
f 65/42 22/41 64/40
f 23/45 22/41 66/43
f 67/46 24/44 66/43
f 25/49 24/44 68/47
f 69/50 26/48 68/47
f 27/60 26/48 70/51
f 29/10 71/52 30/11
f 36/17 34/16 33/15
f 35/54 28/20 71/52
f 33/15 32/13 36/17
f 74/59 55/24 75/87
f 32/13 72/53 36/17
f 73/90 35/54 71/52
f 71/52 37/18 73/90
f 36/17 35/54 34/16
f 74/59 75/87 76/85
f 31/12 63/39 62/38
f 74/59 76/85 77/83
f 35/54 90/61 34/16
f 74/59 77/83 78/81
f 88/65 89/63 35/54
f 78/81 79/79 74/59
f 87/67 88/65 35/54
f 74/59 79/79 80/77
f 86/69 87/67 35/54
f 35/54 74/59 80/77
f 85/71 86/69 35/54
f 35/54 80/77 81/76
f 84/74 85/71 35/54
f 35/54 81/76 82/55
f 83/56 84/74 35/54
f 37/18 36/17 91/57
f 35/54 89/63 90/61
f 34/16 90/61 70/51
f 92/94 93/95 55/24
f 92/94 55/24 74/59
f 34/16 70/51 69/50
f 59/32 94/96 31/12
f 34/16 69/50 68/47
f 31/12 34/16 64/40
f 34/16 68/47 67/46
f 93/95 57/27 56/25
f 34/16 67/46 66/43
f 93/95 58/29 57/27
f 34/16 66/43 65/42
f 93/95 59/32 58/29
f 34/16 65/42 64/40
f 93/95 94/96 59/32
f 63/39 31/12 64/40
f 61/37 60/33 31/12
f 93/95 56/25 55/24
f 94/96 95/58 31/12
f 60/33 59/32 31/12
f 39/62 27/60 90/61
f 95/58 92/94 74/59
f 71/52 28/20 38/19
f 95/58 72/53 31/12
f 40/64 39/62 89/63
f 41/66 40/64 88/65
f 42/68 41/66 87/67
f 43/70 42/68 86/69
f 44/73 43/70 85/71
f 84/74 45/72 85/71
f 46/75 45/72 83/56
f 47/21 46/75 82/55
f 48/22 47/21 81/76
f 49/78 48/22 80/77
f 50/80 49/78 79/79
f 51/82 50/80 78/81
f 52/84 51/82 77/83
f 53/86 52/84 76/85
f 54/88 53/86 75/87
f 8/23 54/88 55/24
f 73/90 37/18 96/89
f 35/54 73/90 74/59
f 72/53 74/59 91/57
usemtl Material.004_NONE
f 10/97 95/97 94/97
f 93/97 12/97 11/97
f 10/97 9/97 92/97
f 92/97 9/97 12/97
f 11/97 10/97 94/97
f 94/97 93/97 11/97
f 95/97 10/97 92/97
f 93/97 92/97 12/97

Binary file not shown.

After

Width:  |  Height:  |  Size: 40 KiB

View File

@ -0,0 +1 @@

View File

@ -0,0 +1,39 @@
import pybullet as p
import pybullet_data
import os
import time
GRAVITY = -9.8
dt = 1e-3
iters = 2000
import pybullet_data
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
#p.setRealTimeSimulation(True)
p.setGravity(0, 0, GRAVITY)
p.setTimeStep(dt)
planeId = p.loadURDF("plane.urdf")
cubeStartPos = [0, 0, 1.13]
cubeStartOrientation = p.getQuaternionFromEuler([0., 0, 0])
botId = p.loadURDF("biped/biped2d_pybullet.urdf", cubeStartPos, cubeStartOrientation)
#disable the default velocity motors
#and set some position control with small force to emulate joint friction/return to a rest pose
jointFrictionForce = 1
for joint in range(p.getNumJoints(botId)):
p.setJointMotorControl2(botId, joint, p.POSITION_CONTROL, force=jointFrictionForce)
#for i in range(10000):
# p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
# p.stepSimulation()
#import ipdb
#ipdb.set_trace()
import time
p.setRealTimeSimulation(1)
while (1):
#p.stepSimulation()
#p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
p.setGravity(0, 0, GRAVITY)
time.sleep(1 / 240.)
time.sleep(1000)

View File

@ -0,0 +1,21 @@
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)
collisionFilterGroup = 0
collisionFilterMask = 0
p.setCollisionFilterGroupMask(cubeId, -1, collisionFilterGroup, collisionFilterMask)
enableCollision = 1
p.setCollisionFilterPair(planeId, cubeId, -1, -1, enableCollision)
p.setRealTimeSimulation(1)
p.setGravity(0, 0, -10)
while (p.isConnected()):
time.sleep(1. / 240.)
p.setGravity(0, 0, -10)

View File

@ -0,0 +1,27 @@
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)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
cid = p.createConstraint(cubeId, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0, 0, 1])
print(cid)
print(p.getConstraintUniqueId(0))
a = -math.pi
while 1:
a = a + 0.01
if (a > math.pi):
a = -math.pi
time.sleep(.01)
p.setGravity(0, 0, -10)
pivot = [a, 0, 1]
orn = p.getQuaternionFromEuler([a, 0, 0])
p.changeConstraint(cid, pivot, jointChildFrameOrientation=orn, maxForce=50)
p.removeConstraint(cid)

View File

@ -0,0 +1,143 @@
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.)
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "createMultiBodyBatch.json")
#useMaximalCoordinates is much faster then the default reduced coordinates (Featherstone)
p.loadURDF("plane100.urdf", useMaximalCoordinates=True)
#disable rendering during creation.
p.setPhysicsEngineParameter(contactBreakingThreshold=0.04)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
#disable tinyrenderer, software (CPU) renderer, we don't use it here
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
shift = [0, -0.02, 0]
meshScale = [0.1, 0.1, 0.1]
vertices = [[-1.000000, -1.000000, 1.000000], [1.000000, -1.000000, 1.000000],
[1.000000, 1.000000, 1.000000], [-1.000000, 1.000000, 1.000000],
[-1.000000, -1.000000, -1.000000], [1.000000, -1.000000, -1.000000],
[1.000000, 1.000000, -1.000000], [-1.000000, 1.000000, -1.000000],
[-1.000000, -1.000000, -1.000000], [-1.000000, 1.000000, -1.000000],
[-1.000000, 1.000000, 1.000000], [-1.000000, -1.000000, 1.000000],
[1.000000, -1.000000, -1.000000], [1.000000, 1.000000, -1.000000],
[1.000000, 1.000000, 1.000000], [1.000000, -1.000000, 1.000000],
[-1.000000, -1.000000, -1.000000], [-1.000000, -1.000000, 1.000000],
[1.000000, -1.000000, 1.000000], [1.000000, -1.000000, -1.000000],
[-1.000000, 1.000000, -1.000000], [-1.000000, 1.000000, 1.000000],
[1.000000, 1.000000, 1.000000], [1.000000, 1.000000, -1.000000]]
normals = [[0.000000, 0.000000, 1.000000], [0.000000, 0.000000, 1.000000],
[0.000000, 0.000000, 1.000000], [0.000000, 0.000000, 1.000000],
[0.000000, 0.000000, -1.000000], [0.000000, 0.000000, -1.000000],
[0.000000, 0.000000, -1.000000], [0.000000, 0.000000, -1.000000],
[-1.000000, 0.000000, 0.000000], [-1.000000, 0.000000, 0.000000],
[-1.000000, 0.000000, 0.000000], [-1.000000, 0.000000, 0.000000],
[1.000000, 0.000000, 0.000000], [1.000000, 0.000000, 0.000000],
[1.000000, 0.000000, 0.000000], [1.000000, 0.000000, 0.000000],
[0.000000, -1.000000, 0.000000], [0.000000, -1.000000, 0.000000],
[0.000000, -1.000000, 0.000000], [0.000000, -1.000000, 0.000000],
[0.000000, 1.000000, 0.000000], [0.000000, 1.000000, 0.000000],
[0.000000, 1.000000, 0.000000], [0.000000, 1.000000, 0.000000]]
uvs = [[0.750000, 0.250000], [1.000000, 0.250000], [1.000000, 0.000000], [0.750000, 0.000000],
[0.500000, 0.250000], [0.250000, 0.250000], [0.250000, 0.000000], [0.500000, 0.000000],
[0.500000, 0.000000], [0.750000, 0.000000], [0.750000, 0.250000], [0.500000, 0.250000],
[0.250000, 0.500000], [0.250000, 0.250000], [0.000000, 0.250000], [0.000000, 0.500000],
[0.250000, 0.500000], [0.250000, 0.250000], [0.500000, 0.250000], [0.500000, 0.500000],
[0.000000, 0.000000], [0.000000, 0.250000], [0.250000, 0.250000], [0.250000, 0.000000]]
indices = [
0,
1,
2,
0,
2,
3, #//ground face
6,
5,
4,
7,
6,
4, #//top face
10,
9,
8,
11,
10,
8,
12,
13,
14,
12,
14,
15,
18,
17,
16,
19,
18,
16,
20,
21,
22,
20,
22,
23
]
#p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0)
#the visual shape and collision shape can be re-used by all createMultiBody instances (instancing)
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,
rgbaColor=[1, 1, 1, 1],
specularColor=[0.4, .4, 0],
visualFramePosition=shift,
meshScale=meshScale,
vertices=vertices,
indices=indices,
uvs=uvs,
normals=normals)
collisionShapeId = p.createCollisionShape(
shapeType=p.GEOM_BOX, halfExtents=meshScale
) #MESH, vertices=vertices, collisionFramePosition=shift,meshScale=meshScale)
texUid = p.loadTexture("tex256.png")
batchPositions = []
for x in range(32):
for y in range(32):
for z in range(10):
batchPositions.append(
[x * meshScale[0] * 5.5, y * meshScale[1] * 5.5, (0.5 + z) * meshScale[2] * 2.5])
bodyUids = p.createMultiBody(baseMass=0,
baseInertialFramePosition=[0, 0, 0],
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=[0, 0, 2],
batchPositions=batchPositions,
useMaximalCoordinates=True)
p.changeVisualShape(bodyUids[0], -1, textureUniqueId=texUid)
p.syncBodyInfo()
print("numBodies=", p.getNumBodies())
p.stopStateLogging(logId)
p.setGravity(0, 0, -10)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]]
currentColor = 0
while (1):
p.stepSimulation()
#time.sleep(1./120.)
#p.getCameraImage(320,200)

View File

@ -0,0 +1,130 @@
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)
#p.createMultiBody(0,0)
#p.resetDebugVisualizerCamera(5,75,-26,[0,0,1]);
p.resetDebugVisualizerCamera(15, -346, -16, [-15, 0, 1])
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
sphereRadius = 0.05
colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius)
#a few different ways to create a mesh:
#convex mesh from obj
stoneId = p.createCollisionShape(p.GEOM_MESH, fileName="stone.obj")
boxHalfLength = 0.5
boxHalfWidth = 2.5
boxHalfHeight = 0.1
segmentLength = 5
colBoxId = p.createCollisionShape(p.GEOM_BOX,
halfExtents=[boxHalfLength, boxHalfWidth, boxHalfHeight])
mass = 1
visualShapeId = -1
segmentStart = 0
for i in range(segmentLength):
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=colBoxId,
basePosition=[segmentStart, 0, -0.1])
segmentStart = segmentStart - 1
for i in range(segmentLength):
height = 0
if (i % 2):
height = 1
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=colBoxId,
basePosition=[segmentStart, 0, -0.1 + height])
segmentStart = segmentStart - 1
baseOrientation = p.getQuaternionFromEuler([math.pi / 2., 0, math.pi / 2.])
for i in range(segmentLength):
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=colBoxId,
basePosition=[segmentStart, 0, -0.1])
segmentStart = segmentStart - 1
if (i % 2):
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=colBoxId,
basePosition=[segmentStart, i % 3, -0.1 + height + boxHalfWidth],
baseOrientation=baseOrientation)
for i in range(segmentLength):
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=colBoxId,
basePosition=[segmentStart, 0, -0.1])
width = 4
for j in range(width):
p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=stoneId,
basePosition=[segmentStart, 0.5 * (i % 2) + j - width / 2., 0])
segmentStart = segmentStart - 1
link_Masses = [1]
linkCollisionShapeIndices = [colBoxId]
linkVisualShapeIndices = [-1]
linkPositions = [[0, 0, 0]]
linkOrientations = [[0, 0, 0, 1]]
linkInertialFramePositions = [[0, 0, 0]]
linkInertialFrameOrientations = [[0, 0, 0, 1]]
indices = [0]
jointTypes = [p.JOINT_REVOLUTE]
axis = [[1, 0, 0]]
baseOrientation = [0, 0, 0, 1]
for i in range(segmentLength):
boxId = p.createMultiBody(0,
colSphereId,
-1, [segmentStart, 0, -0.1],
baseOrientation,
linkMasses=link_Masses,
linkCollisionShapeIndices=linkCollisionShapeIndices,
linkVisualShapeIndices=linkVisualShapeIndices,
linkPositions=linkPositions,
linkOrientations=linkOrientations,
linkInertialFramePositions=linkInertialFramePositions,
linkInertialFrameOrientations=linkInertialFrameOrientations,
linkParentIndices=indices,
linkJointTypes=jointTypes,
linkJointAxis=axis)
p.changeDynamics(boxId, -1, spinningFriction=0.001, rollingFriction=0.001, linearDamping=0.0)
print(p.getNumJoints(boxId))
for joint in range(p.getNumJoints(boxId)):
targetVelocity = 10
if (i % 2):
targetVelocity = -10
p.setJointMotorControl2(boxId,
joint,
p.VELOCITY_CONTROL,
targetVelocity=targetVelocity,
force=100)
segmentStart = segmentStart - 1.1
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
while (1):
camData = p.getDebugVisualizerCamera()
viewMat = camData[2]
projMat = camData[3]
p.getCameraImage(256,
256,
viewMatrix=viewMat,
projectionMatrix=projMat,
renderer=p.ER_BULLET_HARDWARE_OPENGL)
keys = p.getKeyboardEvents()
p.stepSimulation()
#print(keys)
time.sleep(0.01)

View File

@ -0,0 +1,115 @@
import pybullet as p
import time
import math
import pybullet_data
def getRayFromTo(mouseX, mouseY):
width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera(
)
camPos = [
camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1],
camTarget[2] - dist * camForward[2]
]
farPlane = 10000
rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])]
invLen = farPlane * 1. / (math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] *
rayForward[1] + rayForward[2] * rayForward[2]))
rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]]
rayFrom = camPos
oneOverWidth = float(1) / float(width)
oneOverHeight = float(1) / float(height)
dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight]
rayToCenter = [
rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2]
]
rayTo = [
rayFrom[0] + rayForward[0] - 0.5 * horizon[0] + 0.5 * vertical[0] + float(mouseX) * dHor[0] -
float(mouseY) * dVer[0], rayFrom[1] + rayForward[1] - 0.5 * horizon[1] + 0.5 * vertical[1] +
float(mouseX) * dHor[1] - float(mouseY) * dVer[1], rayFrom[2] + rayForward[2] -
0.5 * horizon[2] + 0.5 * vertical[2] + float(mouseX) * dHor[2] - float(mouseY) * dVer[2]
]
return rayFrom, rayTo
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")
#useMaximalCoordinates is much faster then the default reduced coordinates (Featherstone)
p.loadURDF("plane100.urdf", useMaximalCoordinates=True)
#disable rendering during creation.
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
#disable tinyrenderer, software (CPU) renderer, we don't use it here
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
shift = [0, -0.02, 0]
shift1 = [0, 0.1, 0]
shift2 = [0, 0, 0]
meshScale = [0.1, 0.1, 0.1]
#the visual shape and collision shape can be re-used by all createMultiBody instances (instancing)
visualShapeId = p.createVisualShapeArray(shapeTypes=[p.GEOM_MESH, p.GEOM_BOX],
halfExtents=[[0, 0, 0], [0.1, 0.1, 0.1]],
fileNames=["duck.obj", ""],
visualFramePositions=[
shift1,
shift2,
],
meshScales=[meshScale, meshScale])
collisionShapeId = p.createCollisionShapeArray(shapeTypes=[p.GEOM_MESH, p.GEOM_BOX],
halfExtents=[[0, 0, 0], [0.1, 0.1, 0.1]],
fileNames=["duck_vhacd.obj", ""],
collisionFramePositions=[
shift1,
shift2,
],
meshScales=[meshScale, meshScale])
rangex = 2
rangey = 2
for i in range(rangex):
for j in range(rangey):
mb = p.createMultiBody(baseMass=1,
baseInertialFramePosition=[0, 0, 0],
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=[((-rangex / 2) + i * 2) * meshScale[0] * 2,
(-rangey / 2 + j) * meshScale[1] * 4, 1],
useMaximalCoordinates=False)
p.changeVisualShape(mb, -1, rgbaColor=[1, 1, 1, 1])
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.stopStateLogging(logId)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]]
currentColor = 0
p.getCameraImage(64, 64, renderer=p.ER_BULLET_HARDWARE_OPENGL)
while (1):
mouseEvents = p.getMouseEvents()
for e in mouseEvents:
if ((e[0] == 2) and (e[3] == 0) and (e[4] & p.KEY_WAS_TRIGGERED)):
mouseX = e[1]
mouseY = e[2]
rayFrom, rayTo = getRayFromTo(mouseX, mouseY)
rayInfo = p.rayTest(rayFrom, rayTo)
#p.addUserDebugLine(rayFrom,rayTo,[1,0,0],3)
for l in range(len(rayInfo)):
hit = rayInfo[l]
objectUid = hit[0]
if (objectUid >= 0):
#p.removeBody(objectUid)
p.changeVisualShape(objectUid, -1, rgbaColor=colors[currentColor])
currentColor += 1
if (currentColor >= len(colors)):
currentColor = 0

View File

@ -0,0 +1,55 @@
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
p.setGravity(0, 0, gravZ)
planeOrn = [0,0,0,1]#p.getQuaternionFromEuler([0.3,0,0])
#planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
boxId = p.loadURDF("cube.urdf", [0,1,2],useMaximalCoordinates = True)
clothId = p.loadSoftBody("cloth_z_up.obj", basePosition = [0,0,2], scale = 0.5, mass = 1., useNeoHookean = 0, useBendingSprings=1,useMassSpring=1, springElasticStiffness=40, springDampingStiffness=.1, springDampingAllDirections = 1, useSelfCollision = 0, frictionCoeff = .5, useFaceContact=1)
p.changeVisualShape(clothId, -1, flags=p.VISUAL_SHAPE_DOUBLE_SIDED)
p.createSoftBodyAnchor(clothId ,24,-1,-1)
p.createSoftBodyAnchor(clothId ,20,-1,-1)
p.createSoftBodyAnchor(clothId ,15,boxId,-1, [0.5,-0.5,0])
p.createSoftBodyAnchor(clothId ,19,boxId,-1, [-0.5,-0.5,0])
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
debug = True
if debug:
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
print("--------------")
print("data=",data)
print(data[0])
print(data[1])
text_uid = []
for i in range(data[0]):
pos = data[1][i]
uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1])
text_uid.append(uid)
while p.isConnected():
p.getCameraImage(320,200)
if debug:
data = p.getMeshData(clothId, -1, flags=p.MESH_DATA_SIMULATION_MESH)
for i in range(data[0]):
pos = data[1][i]
uid = p.addUserDebugText(str(i), pos, textColorRGB=[1,1,1], replaceItemUniqueId=text_uid[i])
p.setGravity(0,0,gravZ)
p.stepSimulation()
#p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
#sleep(1./240.)

View File

@ -0,0 +1,31 @@
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.resetDebugVisualizerCamera(3,-420,-30,[0.3,0.9,-2])
p.setGravity(0, 0, -10)
tex = p.loadTexture("uvmap.png")
planeId = p.loadURDF("plane.urdf", [0,0,-2])
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("torus/torus_textured.obj", simFileName="torus.vtk", mass = 3, useNeoHookean = 1, NeoHookeanMu = 180, NeoHookeanLambda = 600, NeoHookeanDamping = 0.01, collisionMargin = 0.006, useSelfCollision = 1, frictionCoeff = 0.5, repulsionStiffness = 800)
p.changeVisualShape(bunnyId, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0)
bunny2 = p.loadURDF("torus_deform.urdf", [0,1,0.2], flags=p.URDF_USE_SELF_COLLISION)
p.changeVisualShape(bunny2, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(0)
while p.isConnected():
p.stepSimulation()
p.getCameraImage(320,200)
p.setGravity(0,0,-10)

View File

@ -0,0 +1,55 @@
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
terrain_visual_shape_id = -1
terrain_position = [0, 0, 0]
terrain_orientation = [0, 0, 0, 1]
terrain_collision_shape_id = p.createCollisionShape(shapeType=p.GEOM_MESH,
fileName="terrain.obj",
flags=p.GEOM_FORCE_CONCAVE_TRIMESH |
p.GEOM_CONCAVE_INTERNAL_EDGE,
meshScale=[0.5, 0.5, 0.5])
p.createMultiBody(terrain_mass, terrain_collision_shape_id, terrain_visual_shape_id,
terrain_position, terrain_orientation)
useMaximalCoordinates = True
sphereRadius = 0.005
colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius)
colBoxId = p.createCollisionShape(p.GEOM_BOX,
halfExtents=[sphereRadius, sphereRadius, sphereRadius])
mass = 1
visualShapeId = -1
for i in range(5):
for j in range(5):
for k in range(5):
#if (k&2):
sphereUid = p.createMultiBody(
mass,
colSphereId,
visualShapeId, [-i * 5 * sphereRadius, j * 5 * sphereRadius, k * 2 * sphereRadius + 1],
useMaximalCoordinates=useMaximalCoordinates)
#else:
# sphereUid = p.createMultiBody(mass,colBoxId,visualShapeId,[-i*2*sphereRadius,j*2*sphereRadius,k*2*sphereRadius+1], useMaximalCoordinates=useMaximalCoordinates)
p.changeDynamics(sphereUid,
-1,
spinningFriction=0.001,
rollingFriction=0.001,
linearDamping=0.0)
p.changeDynamics(sphereUid, -1, ccdSweptSphereRadius=0.002)
p.setGravity(0, 0, -10)
pts = p.getContactPoints()
print("num points=", len(pts))
print(pts)
while (p.isConnected()):
time.sleep(1. / 240.)
p.stepSimulation()

View File

@ -0,0 +1,23 @@
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)
p.executePluginCommand(fileIO, pybullet_data.getDataPath()+"/pickup2.zip", [p.AddFileIOAction, p.ZipFileIO])
p.executePluginCommand(fileIO, "pickup.zip", [p.AddFileIOAction, p.ZipFileIO])
objs = p.loadSDF("pickup/model.sdf")
dobot = objs[0]
p.changeVisualShape(dobot, -1, rgbaColor=[1, 1, 1, 1])
else:
print("fileIOPlugin is disabled.")
p.setPhysicsEngineParameter(enableFileCaching=False)
while (1):
p.stepSimulation()
time.sleep(1. / 240.)

View File

@ -0,0 +1,75 @@
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)
geomBox = p.createCollisionShape(p.GEOM_BOX, halfExtents=[0.2, 0.2, 0.2])
baseOrientationB = p.getQuaternionFromEuler([0, 0.3, 0]) #[0,0.5,0.5,0]
basePositionB = [1.5, 0, 1]
obA = -1
obB = -1
obA = p.createMultiBody(baseMass=0, baseCollisionShapeIndex=geom, basePosition=[0.5, 0, 1])
obB = p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=geomBox,
basePosition=basePositionB,
baseOrientation=baseOrientationB)
lineWidth = 3
colorRGB = [1, 0, 0]
lineId = p.addUserDebugLine(lineFromXYZ=[0, 0, 0],
lineToXYZ=[0, 0, 0],
lineColorRGB=colorRGB,
lineWidth=lineWidth,
lifeTime=0)
pitch = 0
yaw = 0
while (p.isConnected()):
pitch += 0.01
if (pitch >= 3.1415 * 2.):
pitch = 0
yaw += 0.01
if (yaw >= 3.1415 * 2.):
yaw = 0
baseOrientationB = p.getQuaternionFromEuler([yaw, pitch, 0])
if (obB >= 0):
p.resetBasePositionAndOrientation(obB, basePositionB, baseOrientationB)
if (useCollisionShapeQuery):
pts = p.getClosestPoints(bodyA=-1,
bodyB=-1,
distance=100,
collisionShapeA=geom,
collisionShapeB=geomBox,
collisionShapePositionA=[0.5, 0, 1],
collisionShapePositionB=basePositionB,
collisionShapeOrientationB=baseOrientationB)
#pts = p.getClosestPoints(bodyA=obA, bodyB=-1, distance=100, collisionShapeB=geomBox, collisionShapePositionB=basePositionB, collisionShapeOrientationB=baseOrientationB)
else:
pts = p.getClosestPoints(bodyA=obA, bodyB=obB, distance=100)
if len(pts) > 0:
#print(pts)
distance = pts[0][8]
#print("distance=",distance)
ptA = pts[0][5]
ptB = pts[0][6]
p.addUserDebugLine(lineFromXYZ=ptA,
lineToXYZ=ptB,
lineColorRGB=colorRGB,
lineWidth=lineWidth,
lifeTime=0,
replaceItemUniqueId=lineId)
#time.sleep(1./240.)
#removeCollisionShape is optional:
#only use removeCollisionShape if the collision shape is not used to create a body
#and if you want to keep on creating new collision shapes for different queries (not recommended)
p.removeCollisionShape(geom)
p.removeCollisionShape(geomBox)

View File

@ -0,0 +1,21 @@
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)
curTexUid = visualData[0][8]
print(curTexUid)
texUid = p.loadTexture("tex256.png")
print("texUid=", texUid)
p.changeVisualShape(plane, -1, textureUniqueId=texUid)
for i in range(100):
p.getCameraImage(320, 200)
p.changeVisualShape(plane, -1, textureUniqueId=curTexUid)
for i in range(100):
p.getCameraImage(320, 200)

View File

@ -0,0 +1,138 @@
import pybullet as p
import pybullet_data as pd
import math
import time
p.connect(p.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
textureId = -1
useProgrammatic = 0
useTerrainFromPNG = 1
useDeepLocoCSV = 2
updateHeightfield = False
heightfieldSource = useProgrammatic
import random
random.seed(10)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
heightPerturbationRange = 0.05
if heightfieldSource==useProgrammatic:
numHeightfieldRows = 256
numHeightfieldColumns = 256
heightfieldData = [0]*numHeightfieldRows*numHeightfieldColumns
for j in range (int(numHeightfieldColumns/2)):
for i in range (int(numHeightfieldRows/2) ):
height = random.uniform(0,heightPerturbationRange)
heightfieldData[2*i+2*j*numHeightfieldRows]=height
heightfieldData[2*i+1+2*j*numHeightfieldRows]=height
heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height
heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns)
terrain = p.createMultiBody(0, terrainShape)
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
if heightfieldSource==useDeepLocoCSV:
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128)
terrain = p.createMultiBody(0, terrainShape)
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
if heightfieldSource==useTerrainFromPNG:
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.1,.1,24],fileName = "heightmaps/wm_height_out.png")
textureId = p.loadTexture("heightmaps/gimp_overlay_out.png")
terrain = p.createMultiBody(0, terrainShape)
p.changeVisualShape(terrain, -1, textureUniqueId = textureId)
p.changeVisualShape(terrain, -1, rgbaColor=[1,1,1,1])
sphereRadius = 0.05
colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius)
colBoxId = p.createCollisionShape(p.GEOM_BOX,
halfExtents=[sphereRadius, sphereRadius, sphereRadius])
mass = 1
visualShapeId = -1
link_Masses = [1]
linkCollisionShapeIndices = [colBoxId]
linkVisualShapeIndices = [-1]
linkPositions = [[0, 0, 0.11]]
linkOrientations = [[0, 0, 0, 1]]
linkInertialFramePositions = [[0, 0, 0]]
linkInertialFrameOrientations = [[0, 0, 0, 1]]
indices = [0]
jointTypes = [p.JOINT_REVOLUTE]
axis = [[0, 0, 1]]
for i in range(3):
for j in range(3):
for k in range(3):
basePosition = [
i * 5 * sphereRadius, j * 5 * sphereRadius, 1 + k * 5 * sphereRadius + 1
]
baseOrientation = [0, 0, 0, 1]
if (k & 2):
sphereUid = p.createMultiBody(mass, colSphereId, visualShapeId, basePosition,
baseOrientation)
else:
sphereUid = p.createMultiBody(mass,
colBoxId,
visualShapeId,
basePosition,
baseOrientation,
linkMasses=link_Masses,
linkCollisionShapeIndices=linkCollisionShapeIndices,
linkVisualShapeIndices=linkVisualShapeIndices,
linkPositions=linkPositions,
linkOrientations=linkOrientations,
linkInertialFramePositions=linkInertialFramePositions,
linkInertialFrameOrientations=linkInertialFrameOrientations,
linkParentIndices=indices,
linkJointTypes=jointTypes,
linkJointAxis=axis)
p.changeDynamics(sphereUid,
-1,
spinningFriction=0.001,
rollingFriction=0.001,
linearDamping=0.0)
for joint in range(p.getNumJoints(sphereUid)):
p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
p.getNumJoints(sphereUid)
for i in range(p.getNumJoints(sphereUid)):
p.getJointInfo(sphereUid, i)
while (p.isConnected()):
keys = p.getKeyboardEvents()
if updateHeightfield and heightfieldSource==useProgrammatic:
for j in range (int(numHeightfieldColumns/2)):
for i in range (int(numHeightfieldRows/2) ):
height = random.uniform(0,heightPerturbationRange)#+math.sin(time.time())
heightfieldData[2*i+2*j*numHeightfieldRows]=height
heightfieldData[2*i+1+2*j*numHeightfieldRows]=height
heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height
heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height
#GEOM_CONCAVE_INTERNAL_EDGE may help avoid getting stuck at an internal (shared) edge of the triangle/heightfield.
#GEOM_CONCAVE_INTERNAL_EDGE is a bit slower to build though.
#flags = p.GEOM_CONCAVE_INTERNAL_EDGE
flags = 0
terrainShape2 = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, flags = flags, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns, replaceHeightfieldIndex = terrainShape)
#print(keys)
#getCameraImage note: software/TinyRenderer doesn't render/support heightfields!
#p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL)
time.sleep(0.01)

View File

@ -0,0 +1,614 @@
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
showJointMotorTorques = False
if useYUp:
p.configureDebugVisualizer(p.COV_ENABLE_Y_AXIS_UP, 1)
from pybullet_examples.pdControllerExplicit import PDControllerExplicitMultiDof
from pybullet_examples.pdControllerStable import PDControllerStableMultiDof
explicitPD = PDControllerExplicitMultiDof(p)
stablePD = PDControllerStableMultiDof(p)
p.resetDebugVisualizerCamera(cameraDistance=7.4,
cameraYaw=-94,
cameraPitch=-14,
cameraTargetPosition=[0.24, -0.02, -0.09])
import pybullet_data
p.setTimeOut(10000)
useMotionCapture = False
useMotionCaptureReset = False #not useMotionCapture
useExplicitPD = True
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.setPhysicsEngineParameter(numSolverIterations=30)
#p.setPhysicsEngineParameter(solverResidualThreshold=1e-30)
#explicit PD control requires small timestep
timeStep = 1. / 600.
#timeStep = 1./240.
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
path = pybullet_data.getDataPath() + "/data/motions/humanoid3d_backflip.txt"
#path = pybullet_data.getDataPath()+"/data/motions/humanoid3d_cartwheel.txt"
#path = pybullet_data.getDataPath()+"/data/motions/humanoid3d_walk.txt"
#p.loadURDF("plane.urdf",[0,0,-1.03])
print("path = ", path)
with open(path, 'r') as f:
motion_dict = json.load(f)
#print("motion_dict = ", motion_dict)
print("len motion=", len(motion_dict))
print(motion_dict['Loop'])
numFrames = len(motion_dict['Frames'])
print("#frames = ", numFrames)
frameId = p.addUserDebugParameter("frame", 0, numFrames - 1, 0)
erpId = p.addUserDebugParameter("erp", 0, 1, 0.2)
kpMotorId = p.addUserDebugParameter("kpMotor", 0, 1, .2)
forceMotorId = p.addUserDebugParameter("forceMotor", 0, 2000, 1000)
jointTypes = [
"JOINT_REVOLUTE", "JOINT_PRISMATIC", "JOINT_SPHERICAL", "JOINT_PLANAR", "JOINT_FIXED"
]
startLocations = [[0, 0, 2], [0, 0, 0], [0, 0, -2], [0, 0, -4], [0, 0, 4]]
p.addUserDebugText("Stable PD",
[startLocations[0][0], startLocations[0][1] + 1, startLocations[0][2]],
[0, 0, 0])
p.addUserDebugText("Spherical Drive",
[startLocations[1][0], startLocations[1][1] + 1, startLocations[1][2]],
[0, 0, 0])
p.addUserDebugText("Explicit PD",
[startLocations[2][0], startLocations[2][1] + 1, startLocations[2][2]],
[0, 0, 0])
p.addUserDebugText("Kinematic",
[startLocations[3][0], startLocations[3][1] + 1, startLocations[3][2]],
[0, 0, 0])
p.addUserDebugText("Stable PD (Py)",
[startLocations[4][0], startLocations[4][1] + 1, startLocations[4][2]],
[0, 0, 0])
flags=p.URDF_MAINTAIN_LINK_ORDER+p.URDF_USE_SELF_COLLISION
humanoid = p.loadURDF("humanoid/humanoid.urdf",
startLocations[0],
globalScaling=0.25,
useFixedBase=False,
flags=flags)
humanoid2 = p.loadURDF("humanoid/humanoid.urdf",
startLocations[1],
globalScaling=0.25,
useFixedBase=False,
flags=flags)
humanoid3 = p.loadURDF("humanoid/humanoid.urdf",
startLocations[2],
globalScaling=0.25,
useFixedBase=False,
flags=flags)
humanoid4 = p.loadURDF("humanoid/humanoid.urdf",
startLocations[3],
globalScaling=0.25,
useFixedBase=False,
flags=flags)
humanoid5 = p.loadURDF("humanoid/humanoid.urdf",
startLocations[4],
globalScaling=0.25,
useFixedBase=False,
flags=flags)
humanoid_fix = p.createConstraint(humanoid, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
startLocations[0], [0, 0, 0, 1])
humanoid2_fix = p.createConstraint(humanoid2, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
startLocations[1], [0, 0, 0, 1])
humanoid3_fix = p.createConstraint(humanoid3, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
startLocations[2], [0, 0, 0, 1])
humanoid3_fix = p.createConstraint(humanoid4, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
startLocations[3], [0, 0, 0, 1])
humanoid4_fix = p.createConstraint(humanoid5, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0],
startLocations[4], [0, 0, 0, 1])
startPose = [
2, 0.847532, 0, 0.9986781045, 0.01410400148, -0.0006980000731, -0.04942300517, 0.9988133229,
0.009485003066, -0.04756001538, -0.004475001447, 1, 0, 0, 0, 0.9649395871, 0.02436898957,
-0.05755497537, 0.2549218909, -0.249116, 0.9993661511, 0.009952001505, 0.03265400494,
0.01009800153, 0.9854981188, -0.06440700776, 0.09324301124, -0.1262970152, 0.170571,
0.9927545808, -0.02090099117, 0.08882396249, -0.07817796699, -0.391532, 0.9828788495,
0.1013909845, -0.05515999155, 0.143618978, 0.9659421276, 0.1884590249, -0.1422460188,
0.105854014, 0.581348
]
startVel = [
1.235314324, -0.008525509087, 0.1515293946, -1.161516553, 0.1866449799, -0.1050802848, 0,
0.935706195, 0.08277326387, 0.3002461862, 0, 0, 0, 0, 0, 1.114409628, 0.3618553952,
-0.4505575061, 0, -1.725374735, -0.5052852598, -0.8555179722, -0.2221173515, 0, -0.1837617357,
0.00171895706, 0.03912837591, 0, 0.147945294, 1.837653345, 0.1534535548, 1.491385941, 0,
-4.632454387, -0.9111172777, -1.300648184, -1.345694622, 0, -1.084238535, 0.1313680236,
-0.7236998534, 0, -0.5278312973
]
p.resetBasePositionAndOrientation(humanoid, startLocations[0], [0, 0, 0, 1])
p.resetBasePositionAndOrientation(humanoid2, startLocations[1], [0, 0, 0, 1])
p.resetBasePositionAndOrientation(humanoid3, startLocations[2], [0, 0, 0, 1])
p.resetBasePositionAndOrientation(humanoid4, startLocations[3], [0, 0, 0, 1])
p.resetBasePositionAndOrientation(humanoid5, startLocations[4], [0, 0, 0, 1])
index0 = 7
for j in range(p.getNumJoints(humanoid)):
ji = p.getJointInfo(humanoid, j)
targetPosition = [0]
jointType = ji[2]
if (jointType == p.JOINT_SPHERICAL):
targetPosition = [
startPose[index0 + 1], startPose[index0 + 2], startPose[index0 + 3], startPose[index0 + 0]
]
targetVel = [startVel[index0 + 0], startVel[index0 + 1], startVel[index0 + 2]]
index0 += 4
print("spherical position: ", targetPosition)
print("spherical velocity: ", targetVel)
p.resetJointStateMultiDof(humanoid, j, targetValue=targetPosition, targetVelocity=targetVel)
p.resetJointStateMultiDof(humanoid5, j, targetValue=targetPosition, targetVelocity=targetVel)
p.resetJointStateMultiDof(humanoid2, j, targetValue=targetPosition, targetVelocity=targetVel)
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
targetPosition = [startPose[index0]]
targetVel = [startVel[index0]]
index0 += 1
print("revolute:", targetPosition)
print("revolute velocity:", targetVel)
p.resetJointStateMultiDof(humanoid, j, targetValue=targetPosition, targetVelocity=targetVel)
p.resetJointStateMultiDof(humanoid5, j, targetValue=targetPosition, targetVelocity=targetVel)
p.resetJointStateMultiDof(humanoid2, j, targetValue=targetPosition, targetVelocity=targetVel)
for j in range(p.getNumJoints(humanoid)):
ji = p.getJointInfo(humanoid, j)
targetPosition = [0]
jointType = ji[2]
if (jointType == p.JOINT_SPHERICAL):
targetPosition = [0, 0, 0, 1]
p.setJointMotorControlMultiDof(humanoid,
j,
p.POSITION_CONTROL,
targetPosition,
targetVelocity=[0, 0, 0],
positionGain=0,
velocityGain=1,
force=[0, 0, 0])
p.setJointMotorControlMultiDof(humanoid5,
j,
p.POSITION_CONTROL,
targetPosition,
targetVelocity=[0, 0, 0],
positionGain=0,
velocityGain=1,
force=[0, 0, 0])
p.setJointMotorControlMultiDof(humanoid3,
j,
p.POSITION_CONTROL,
targetPosition,
targetVelocity=[0, 0, 0],
positionGain=0,
velocityGain=1,
force=[31, 31, 31])
p.setJointMotorControlMultiDof(humanoid4,
j,
p.POSITION_CONTROL,
targetPosition,
targetVelocity=[0, 0, 0],
positionGain=0,
velocityGain=1,
force=[1, 1, 1])
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
p.setJointMotorControl2(humanoid, j, p.VELOCITY_CONTROL, targetVelocity=0, force=0)
p.setJointMotorControl2(humanoid3, j, p.VELOCITY_CONTROL, targetVelocity=0, force=31)
p.setJointMotorControl2(humanoid4, j, p.VELOCITY_CONTROL, targetVelocity=0, force=10)
p.setJointMotorControl2(humanoid5, j, p.VELOCITY_CONTROL, targetVelocity=0, force=0)
#print(ji)
print("joint[", j, "].type=", jointTypes[ji[2]])
print("joint[", j, "].name=", ji[1])
jointIds = []
paramIds = []
for j in range(p.getNumJoints(humanoid)):
#p.changeDynamics(humanoid,j,linearDamping=0, angularDamping=0)
p.changeVisualShape(humanoid, j, rgbaColor=[1, 1, 1, 1])
info = p.getJointInfo(humanoid, j)
#print(info)
if (not useMotionCapture):
jointName = info[1]
jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
jointIds.append(j)
#paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"),-4,4,0))
#print("jointName=",jointName, "at ", j)
p.changeVisualShape(humanoid, 2, rgbaColor=[1, 0, 0, 1])
chest = 1
neck = 2
rightHip = 3
rightKnee = 4
rightAnkle = 5
rightShoulder = 6
rightElbow = 7
leftHip = 9
leftKnee = 10
leftAnkle = 11
leftShoulder = 12
leftElbow = 13
#rightShoulder=3
#rightElbow=4
#leftShoulder=6
#leftElbow = 7
#rightHip = 9
#rightKnee=10
#rightAnkle=11
#leftHip = 12
#leftKnee=13
#leftAnkle=14
import time
kpOrg = [
0, 0, 0, 0, 0, 0, 0, 1000, 1000, 1000, 1000, 100, 100, 100, 100, 500, 500, 500, 500, 500, 400,
400, 400, 400, 400, 400, 400, 400, 300, 500, 500, 500, 500, 500, 400, 400, 400, 400, 400, 400,
400, 400, 300
]
kdOrg = [
0, 0, 0, 0, 0, 0, 0, 100, 100, 100, 100, 10, 10, 10, 10, 50, 50, 50, 50, 50, 40, 40, 40, 40,
40, 40, 40, 40, 30, 50, 50, 50, 50, 50, 40, 40, 40, 40, 40, 40, 40, 40, 30
]
once = True
p.getCameraImage(320, 200)
while (p.isConnected()):
if useGUI:
erp = p.readUserDebugParameter(erpId)
kpMotor = p.readUserDebugParameter(kpMotorId)
maxForce = p.readUserDebugParameter(forceMotorId)
frameReal = p.readUserDebugParameter(frameId)
else:
erp = 0.2
kpMotor = 0.2
maxForce = 1000
frameReal = 0
kp = kpMotor
frame = int(frameReal)
frameNext = frame + 1
if (frameNext >= numFrames):
frameNext = frame
frameFraction = frameReal - frame
#print("frameFraction=",frameFraction)
#print("frame=",frame)
#print("frameNext=", frameNext)
#getQuaternionSlerp
frameData = motion_dict['Frames'][frame]
frameDataNext = motion_dict['Frames'][frameNext]
#print("duration=",frameData[0])
#print(pos=[frameData])
basePos1Start = [frameData[1], frameData[2], frameData[3]]
basePos1End = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
basePos1 = [
basePos1Start[0] + frameFraction * (basePos1End[0] - basePos1Start[0]),
basePos1Start[1] + frameFraction * (basePos1End[1] - basePos1Start[1]),
basePos1Start[2] + frameFraction * (basePos1End[2] - basePos1Start[2])
]
baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
baseOrn1Next = [frameDataNext[5], frameDataNext[6], frameDataNext[7], frameDataNext[4]]
baseOrn1 = p.getQuaternionSlerp(baseOrn1Start, baseOrn1Next, frameFraction)
#pre-rotate to make z-up
if (useZUp):
y2zPos = [0, 0, 0.0]
y2zOrn = p.getQuaternionFromEuler([1.57, 0, 0])
basePos, baseOrn = p.multiplyTransforms(y2zPos, y2zOrn, basePos1, baseOrn1)
p.resetBasePositionAndOrientation(humanoid, basePos, baseOrn)
y2zPos = [0, 2, 0.0]
y2zOrn = p.getQuaternionFromEuler([1.57, 0, 0])
basePos, baseOrn = p.multiplyTransforms(y2zPos, y2zOrn, basePos1, baseOrn1)
p.resetBasePositionAndOrientation(humanoid2, basePos, baseOrn)
chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]]
chestRotEnd = [frameDataNext[9], frameDataNext[10], frameDataNext[11], frameDataNext[8]]
chestRot = p.getQuaternionSlerp(chestRotStart, chestRotEnd, frameFraction)
neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]]
neckRotEnd = [frameDataNext[13], frameDataNext[14], frameDataNext[15], frameDataNext[12]]
neckRot = p.getQuaternionSlerp(neckRotStart, neckRotEnd, frameFraction)
rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]]
rightHipRotEnd = [frameDataNext[17], frameDataNext[18], frameDataNext[19], frameDataNext[16]]
rightHipRot = p.getQuaternionSlerp(rightHipRotStart, rightHipRotEnd, frameFraction)
rightKneeRotStart = [frameData[20]]
rightKneeRotEnd = [frameDataNext[20]]
rightKneeRot = [
rightKneeRotStart[0] + frameFraction * (rightKneeRotEnd[0] - rightKneeRotStart[0])
]
rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]]
rightAnkleRotEnd = [frameDataNext[22], frameDataNext[23], frameDataNext[24], frameDataNext[21]]
rightAnkleRot = p.getQuaternionSlerp(rightAnkleRotStart, rightAnkleRotEnd, frameFraction)
rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]]
rightShoulderRotEnd = [
frameDataNext[26], frameDataNext[27], frameDataNext[28], frameDataNext[25]
]
rightShoulderRot = p.getQuaternionSlerp(rightShoulderRotStart, rightShoulderRotEnd,
frameFraction)
rightElbowRotStart = [frameData[29]]
rightElbowRotEnd = [frameDataNext[29]]
rightElbowRot = [
rightElbowRotStart[0] + frameFraction * (rightElbowRotEnd[0] - rightElbowRotStart[0])
]
leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]]
leftHipRotEnd = [frameDataNext[31], frameDataNext[32], frameDataNext[33], frameDataNext[30]]
leftHipRot = p.getQuaternionSlerp(leftHipRotStart, leftHipRotEnd, frameFraction)
leftKneeRotStart = [frameData[34]]
leftKneeRotEnd = [frameDataNext[34]]
leftKneeRot = [leftKneeRotStart[0] + frameFraction * (leftKneeRotEnd[0] - leftKneeRotStart[0])]
leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]]
leftAnkleRotEnd = [frameDataNext[36], frameDataNext[37], frameDataNext[38], frameDataNext[35]]
leftAnkleRot = p.getQuaternionSlerp(leftAnkleRotStart, leftAnkleRotEnd, frameFraction)
leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]]
leftShoulderRotEnd = [frameDataNext[40], frameDataNext[41], frameDataNext[42], frameDataNext[39]]
leftShoulderRot = p.getQuaternionSlerp(leftShoulderRotStart, leftShoulderRotEnd, frameFraction)
leftElbowRotStart = [frameData[43]]
leftElbowRotEnd = [frameDataNext[43]]
leftElbowRot = [
leftElbowRotStart[0] + frameFraction * (leftElbowRotEnd[0] - leftElbowRotStart[0])
]
if (0): #if (once):
p.resetJointStateMultiDof(humanoid, chest, chestRot)
p.resetJointStateMultiDof(humanoid, neck, neckRot)
p.resetJointStateMultiDof(humanoid, rightHip, rightHipRot)
p.resetJointStateMultiDof(humanoid, rightKnee, rightKneeRot)
p.resetJointStateMultiDof(humanoid, rightAnkle, rightAnkleRot)
p.resetJointStateMultiDof(humanoid, rightShoulder, rightShoulderRot)
p.resetJointStateMultiDof(humanoid, rightElbow, rightElbowRot)
p.resetJointStateMultiDof(humanoid, leftHip, leftHipRot)
p.resetJointStateMultiDof(humanoid, leftKnee, leftKneeRot)
p.resetJointStateMultiDof(humanoid, leftAnkle, leftAnkleRot)
p.resetJointStateMultiDof(humanoid, leftShoulder, leftShoulderRot)
p.resetJointStateMultiDof(humanoid, leftElbow, leftElbowRot)
once = False
#print("chestRot=",chestRot)
p.setGravity(0, 0, -10)
kp = kpMotor
if (useExplicitPD):
jointDofCounts = [4, 4, 4, 1, 4, 4, 1, 4, 1, 4, 4, 1]
#[x,y,z] base position and [x,y,z,w] base orientation!
totalDofs = 7
for dof in jointDofCounts:
totalDofs += dof
jointIndicesAll = [
chest, neck, rightHip, rightKnee, rightAnkle, rightShoulder, rightElbow, leftHip, leftKnee,
leftAnkle, leftShoulder, leftElbow
]
basePos, baseOrn = p.getBasePositionAndOrientation(humanoid)
pose = [
basePos[0], basePos[1], basePos[2], baseOrn[0], baseOrn[1], baseOrn[2], baseOrn[3],
chestRot[0], chestRot[1], chestRot[2], chestRot[3], neckRot[0], neckRot[1], neckRot[2],
neckRot[3], rightHipRot[0], rightHipRot[1], rightHipRot[2], rightHipRot[3],
rightKneeRot[0], rightAnkleRot[0], rightAnkleRot[1], rightAnkleRot[2], rightAnkleRot[3],
rightShoulderRot[0], rightShoulderRot[1], rightShoulderRot[2], rightShoulderRot[3],
rightElbowRot[0], leftHipRot[0], leftHipRot[1], leftHipRot[2], leftHipRot[3],
leftKneeRot[0], leftAnkleRot[0], leftAnkleRot[1], leftAnkleRot[2], leftAnkleRot[3],
leftShoulderRot[0], leftShoulderRot[1], leftShoulderRot[2], leftShoulderRot[3],
leftElbowRot[0]
]
#print("pose=")
#for po in pose:
# print(po)
taus = stablePD.computePD(bodyUniqueId=humanoid5,
jointIndices=jointIndicesAll,
desiredPositions=pose,
desiredVelocities=[0] * totalDofs,
kps=kpOrg,
kds=kdOrg,
maxForces=[maxForce] * totalDofs,
timeStep=timeStep)
indices = [chest, neck, rightHip, rightKnee,
rightAnkle, rightShoulder, rightElbow,
leftHip, leftKnee, leftAnkle,
leftShoulder, leftElbow]
targetPositions = [chestRot,neckRot,rightHipRot, rightKneeRot,
rightAnkleRot, rightShoulderRot, rightElbowRot,
leftHipRot, leftKneeRot, leftAnkleRot,
leftShoulderRot, leftElbowRot]
maxForces = [ [maxForce,maxForce,maxForce], [maxForce,maxForce,maxForce],[maxForce,maxForce,maxForce],[maxForce],
[maxForce,maxForce,maxForce],[maxForce,maxForce,maxForce],[maxForce],
[maxForce,maxForce,maxForce], [maxForce], [maxForce,maxForce,maxForce],
[maxForce,maxForce,maxForce], [maxForce]]
kps = [1000]*12
kds = [100]*12
p.setJointMotorControlMultiDofArray(humanoid,
indices,
p.STABLE_PD_CONTROL,
targetPositions=targetPositions,
positionGains=kps,
velocityGains=kds,
forces=maxForces)
taus3 = explicitPD.computePD(bodyUniqueId=humanoid3,
jointIndices=jointIndicesAll,
desiredPositions=pose,
desiredVelocities=[0] * totalDofs,
kps=kpOrg,
kds=kdOrg,
maxForces=[maxForce * 0.05] * totalDofs,
timeStep=timeStep)
#taus=[0]*43
dofIndex = 7
for index in range(len(jointIndicesAll)):
jointIndex = jointIndicesAll[index]
if jointDofCounts[index] == 4:
p.setJointMotorControlMultiDof(
humanoid5,
jointIndex,
p.TORQUE_CONTROL,
force=[taus[dofIndex + 0], taus[dofIndex + 1], taus[dofIndex + 2]])
p.setJointMotorControlMultiDof(
humanoid3,
jointIndex,
p.TORQUE_CONTROL,
force=[taus3[dofIndex + 0], taus3[dofIndex + 1], taus3[dofIndex + 2]])
if jointDofCounts[index] == 1:
p.setJointMotorControlMultiDof(humanoid5,
jointIndex,
controlMode=p.TORQUE_CONTROL,
force=[taus[dofIndex]])
p.setJointMotorControlMultiDof(humanoid3,
jointIndex,
controlMode=p.TORQUE_CONTROL,
force=[taus3[dofIndex]])
dofIndex += jointDofCounts[index]
#print("len(taus)=",len(taus))
#print("taus=",taus)
p.setJointMotorControlMultiDof(humanoid2,
chest,
p.POSITION_CONTROL,
targetPosition=chestRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
neck,
p.POSITION_CONTROL,
targetPosition=neckRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
rightHip,
p.POSITION_CONTROL,
targetPosition=rightHipRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
rightKnee,
p.POSITION_CONTROL,
targetPosition=rightKneeRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
rightAnkle,
p.POSITION_CONTROL,
targetPosition=rightAnkleRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
rightShoulder,
p.POSITION_CONTROL,
targetPosition=rightShoulderRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
rightElbow,
p.POSITION_CONTROL,
targetPosition=rightElbowRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
leftHip,
p.POSITION_CONTROL,
targetPosition=leftHipRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
leftKnee,
p.POSITION_CONTROL,
targetPosition=leftKneeRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
leftAnkle,
p.POSITION_CONTROL,
targetPosition=leftAnkleRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
leftShoulder,
p.POSITION_CONTROL,
targetPosition=leftShoulderRot,
positionGain=kp,
force=[maxForce])
p.setJointMotorControlMultiDof(humanoid2,
leftElbow,
p.POSITION_CONTROL,
targetPosition=leftElbowRot,
positionGain=kp,
force=[maxForce])
kinematicHumanoid4 = True
if (kinematicHumanoid4):
p.resetJointStateMultiDof(humanoid4, chest, chestRot)
p.resetJointStateMultiDof(humanoid4, neck, neckRot)
p.resetJointStateMultiDof(humanoid4, rightHip, rightHipRot)
p.resetJointStateMultiDof(humanoid4, rightKnee, rightKneeRot)
p.resetJointStateMultiDof(humanoid4, rightAnkle, rightAnkleRot)
p.resetJointStateMultiDof(humanoid4, rightShoulder, rightShoulderRot)
p.resetJointStateMultiDof(humanoid4, rightElbow, rightElbowRot)
p.resetJointStateMultiDof(humanoid4, leftHip, leftHipRot)
p.resetJointStateMultiDof(humanoid4, leftKnee, leftKneeRot)
p.resetJointStateMultiDof(humanoid4, leftAnkle, leftAnkleRot)
p.resetJointStateMultiDof(humanoid4, leftShoulder, leftShoulderRot)
p.resetJointStateMultiDof(humanoid4, leftElbow, leftElbowRot)
p.stepSimulation()
if showJointMotorTorques:
for j in range(p.getNumJoints(humanoid2)):
jointState = p.getJointStateMultiDof(humanoid2, j)
print("jointStateMultiDof[", j, "].pos=", jointState[0])
print("jointStateMultiDof[", j, "].vel=", jointState[1])
print("jointStateMultiDof[", j, "].jointForces=", jointState[3])
time.sleep(timeStep)

View File

@ -0,0 +1,167 @@
import pybullet as bullet
import pybullet_data as pd
plot = True
import time
if (plot):
import matplotlib.pyplot as plt
import math
verbose = False
# Parameters:
robot_base = [0., 0., 0.]
robot_orientation = [0., 0., 0., 1.]
delta_t = 0.0001
# Initialize Bullet Simulator
id_simulator = bullet.connect(bullet.GUI) # or bullet.DIRECT for non-graphical version
bullet.setTimeStep(delta_t)
bullet.setAdditionalSearchPath(pd.getDataPath())
# Switch between URDF with/without FIXED joints
with_fixed_joints = True
if with_fixed_joints:
id_revolute_joints = [0, 3]
id_robot = bullet.loadURDF("TwoJointRobot_w_fixedJoints.urdf",
robot_base,
robot_orientation,
useFixedBase=True)
else:
id_revolute_joints = [0, 1]
id_robot = bullet.loadURDF("TwoJointRobot_wo_fixedJoints.urdf",
robot_base,
robot_orientation,
useFixedBase=True)
bullet.changeDynamics(id_robot, -1, linearDamping=0, angularDamping=0)
bullet.changeDynamics(id_robot, 0, linearDamping=0, angularDamping=0)
bullet.changeDynamics(id_robot, 1, linearDamping=0, angularDamping=0)
jointTypeNames = [
"JOINT_REVOLUTE", "JOINT_PRISMATIC", "JOINT_SPHERICAL", "JOINT_PLANAR", "JOINT_FIXED",
"JOINT_POINT2POINT", "JOINT_GEAR"
]
# Disable the motors for torque control:
bullet.setJointMotorControlArray(id_robot,
id_revolute_joints,
bullet.VELOCITY_CONTROL,
forces=[0.0, 0.0])
# Target Positions:
start = 0.0
end = 1.0
steps = int((end - start) / delta_t)
t = [0] * steps
q_pos_desired = [[0.] * steps, [0.] * steps]
q_vel_desired = [[0.] * steps, [0.] * steps]
q_acc_desired = [[0.] * steps, [0.] * steps]
for s in range(steps):
t[s] = start + s * delta_t
q_pos_desired[0][s] = 1. / (2. * math.pi) * math.sin(2. * math.pi * t[s]) - t[s]
q_pos_desired[1][s] = -1. / (2. * math.pi) * (math.cos(2. * math.pi * t[s]) - 1.0)
q_vel_desired[0][s] = math.cos(2. * math.pi * t[s]) - 1.
q_vel_desired[1][s] = math.sin(2. * math.pi * t[s])
q_acc_desired[0][s] = -2. * math.pi * math.sin(2. * math.pi * t[s])
q_acc_desired[1][s] = 2. * math.pi * math.cos(2. * math.pi * t[s])
q_pos = [[0.] * steps, [0.] * steps]
q_vel = [[0.] * steps, [0.] * steps]
q_tor = [[0.] * steps, [0.] * steps]
# Do Torque Control:
for i in range(len(t)):
# Read Sensor States:
joint_states = bullet.getJointStates(id_robot, id_revolute_joints)
q_pos[0][i] = joint_states[0][0]
a = joint_states[1][0]
if (verbose):
print("joint_states[1][0]")
print(joint_states[1][0])
q_pos[1][i] = a
q_vel[0][i] = joint_states[0][1]
q_vel[1][i] = joint_states[1][1]
# Computing the torque from inverse dynamics:
obj_pos = [q_pos[0][i], q_pos[1][i]]
obj_vel = [q_vel[0][i], q_vel[1][i]]
obj_acc = [q_acc_desired[0][i], q_acc_desired[1][i]]
if (verbose):
print("calculateInverseDynamics")
print("id_robot")
print(id_robot)
print("obj_pos")
print(obj_pos)
print("obj_vel")
print(obj_vel)
print("obj_acc")
print(obj_acc)
torque = bullet.calculateInverseDynamics(id_robot, obj_pos, obj_vel, obj_acc)
q_tor[0][i] = torque[0]
q_tor[1][i] = torque[1]
if (verbose):
print("torque=")
print(torque)
# Set the Joint Torques:
bullet.setJointMotorControlArray(id_robot,
id_revolute_joints,
bullet.TORQUE_CONTROL,
forces=[torque[0], torque[1]])
# Step Simulation
bullet.stepSimulation()
# Plot the Position, Velocity and Acceleration:
if plot:
figure = plt.figure(figsize=[15, 4.5])
figure.subplots_adjust(left=0.05, bottom=0.11, right=0.97, top=0.9, wspace=0.4, hspace=0.55)
ax_pos = figure.add_subplot(141)
ax_pos.set_title("Joint Position")
ax_pos.plot(t, q_pos_desired[0], '--r', lw=4, label='Desired q0')
ax_pos.plot(t, q_pos_desired[1], '--b', lw=4, label='Desired q1')
ax_pos.plot(t, q_pos[0], '-r', lw=1, label='Measured q0')
ax_pos.plot(t, q_pos[1], '-b', lw=1, label='Measured q1')
ax_pos.set_ylim(-1., 1.)
ax_pos.legend()
ax_vel = figure.add_subplot(142)
ax_vel.set_title("Joint Velocity")
ax_vel.plot(t, q_vel_desired[0], '--r', lw=4, label='Desired q0')
ax_vel.plot(t, q_vel_desired[1], '--b', lw=4, label='Desired q1')
ax_vel.plot(t, q_vel[0], '-r', lw=1, label='Measured q0')
ax_vel.plot(t, q_vel[1], '-b', lw=1, label='Measured q1')
ax_vel.set_ylim(-2., 2.)
ax_vel.legend()
ax_acc = figure.add_subplot(143)
ax_acc.set_title("Joint Acceleration")
ax_acc.plot(t, q_acc_desired[0], '--r', lw=4, label='Desired q0')
ax_acc.plot(t, q_acc_desired[1], '--b', lw=4, label='Desired q1')
ax_acc.set_ylim(-10., 10.)
ax_acc.legend()
ax_tor = figure.add_subplot(144)
ax_tor.set_title("Executed Torque")
ax_tor.plot(t, q_tor[0], '-r', lw=2, label='Torque q0')
ax_tor.plot(t, q_tor[1], '-b', lw=2, label='Torque q1')
ax_tor.set_ylim(-20., 20.)
ax_tor.legend()
plt.pause(0.01)
while (1):
bullet.stepSimulation()
time.sleep(0.01)

View File

@ -0,0 +1,125 @@
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])
kukaEndEffectorIndex = 6
numJoints = p.getNumJoints(kukaId)
if (numJoints != 7):
exit()
#lower limits for null space
ll = [-.967, -2, -2.96, 0.19, -2.96, -2.09, -3.05]
#upper limits for null space
ul = [.967, 2, 2.96, 2.29, 2.96, 2.09, 3.05]
#joint ranges for null space
jr = [5.8, 4, 5.8, 4, 5.8, 4, 6]
#restposes for null space
rp = [0, 0, 0, 0.5 * math.pi, 0, -math.pi * 0.5 * 0.66, 0]
#joint damping coefficents
jd = [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
for i in range(numJoints):
p.resetJointState(kukaId, i, rp[i])
p.setGravity(0, 0, 0)
t = 0.
prevPose = [0, 0, 0]
prevPose1 = [0, 0, 0]
hasPrevPose = 0
useNullSpace = 1
useOrientation = 1
#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control.
#This can be used to test the IK result accuracy.
useSimulation = 1
useRealTimeSimulation = 0
ikSolver = 0
p.setRealTimeSimulation(useRealTimeSimulation)
#trailDuration is duration (in seconds) after debug lines will be removed automatically
#use 0 for no-removal
trailDuration = 15
i=0
while 1:
i+=1
#p.getCameraImage(320,
# 200,
# flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX,
# renderer=p.ER_BULLET_HARDWARE_OPENGL)
if (useRealTimeSimulation):
dt = datetime.now()
t = (dt.second / 60.) * 2. * math.pi
else:
t = t + 0.01
if (useSimulation and useRealTimeSimulation == 0):
p.stepSimulation()
for i in range(1):
pos = [-0.4, 0.2 * math.cos(t), 0. + 0.2 * math.sin(t)]
#end effector points down, not up (in case useOrientation==1)
orn = p.getQuaternionFromEuler([0, -math.pi, 0])
if (useNullSpace == 1):
if (useOrientation == 1):
jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos, orn, ll, ul,
jr, rp)
else:
jointPoses = p.calculateInverseKinematics(kukaId,
kukaEndEffectorIndex,
pos,
lowerLimits=ll,
upperLimits=ul,
jointRanges=jr,
restPoses=rp)
else:
if (useOrientation == 1):
jointPoses = p.calculateInverseKinematics(kukaId,
kukaEndEffectorIndex,
pos,
orn,
jointDamping=jd,
solver=ikSolver,
maxNumIterations=100,
residualThreshold=.01)
else:
jointPoses = p.calculateInverseKinematics(kukaId,
kukaEndEffectorIndex,
pos,
solver=ikSolver)
if (useSimulation):
for i in range(numJoints):
p.setJointMotorControl2(bodyIndex=kukaId,
jointIndex=i,
controlMode=p.POSITION_CONTROL,
targetPosition=jointPoses[i],
targetVelocity=0,
force=500,
positionGain=0.03,
velocityGain=1)
else:
#reset the joint state (ignoring all dynamics, not recommended to use during simulation)
for i in range(numJoints):
p.resetJointState(kukaId, i, jointPoses[i])
ls = p.getLinkState(kukaId, kukaEndEffectorIndex)
if (hasPrevPose):
p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration)
p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration)
prevPose = pos
prevPose1 = ls[4]
hasPrevPose = 1
p.disconnect()

View File

@ -0,0 +1,202 @@
import pybullet as p
import time
import math
from datetime import datetime
from datetime import datetime
import pybullet_data
clid = p.connect(p.SHARED_MEMORY)
if (clid < 0):
p.connect(p.GUI)
p.setPhysicsEngineParameter(enableConeFriction=0)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.loadURDF("plane.urdf", [0, 0, -0.3])
husky = p.loadURDF("husky/husky.urdf", [0.290388, 0.329902, -0.310270],
[0.002328, -0.000984, 0.996491, 0.083659])
for i in range(p.getNumJoints(husky)):
print(p.getJointInfo(husky, i))
kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf", 0.193749, 0.345564, 0.120208, 0.002327,
-0.000988, 0.996491, 0.083659)
ob = kukaId
jointPositions = [3.559609, 0.411182, 0.862129, 1.744441, 0.077299, -1.129685, 0.006001]
for jointIndex in range(p.getNumJoints(ob)):
p.resetJointState(ob, jointIndex, jointPositions[jointIndex])
#put kuka on top of husky
cid = p.createConstraint(husky, -1, kukaId, -1, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0., 0., -.5],
[0, 0, 0, 1])
baseorn = p.getQuaternionFromEuler([3.1415, 0, 0.3])
baseorn = [0, 0, 0, 1]
#[0, 0, 0.707, 0.707]
#p.resetBasePositionAndOrientation(kukaId,[0,0,0],baseorn)#[0,0,0,1])
kukaEndEffectorIndex = 6
numJoints = p.getNumJoints(kukaId)
if (numJoints != 7):
exit()
#lower limits for null space
ll = [-.967, -2, -2.96, 0.19, -2.96, -2.09, -3.05]
#upper limits for null space
ul = [.967, 2, 2.96, 2.29, 2.96, 2.09, 3.05]
#joint ranges for null space
jr = [5.8, 4, 5.8, 4, 5.8, 4, 6]
#restposes for null space
rp = [0, 0, 0, 0.5 * math.pi, 0, -math.pi * 0.5 * 0.66, 0]
#joint damping coefficents
jd = [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
for i in range(numJoints):
p.resetJointState(kukaId, i, rp[i])
p.setGravity(0, 0, -10)
t = 0.
prevPose = [0, 0, 0]
prevPose1 = [0, 0, 0]
hasPrevPose = 0
useNullSpace = 0
useOrientation = 0
#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control.
#This can be used to test the IK result accuracy.
useSimulation = 1
useRealTimeSimulation = 1
p.setRealTimeSimulation(useRealTimeSimulation)
#trailDuration is duration (in seconds) after debug lines will be removed automatically
#use 0 for no-removal
trailDuration = 15
basepos = [0, 0, 0]
ang = 0
ang = 0
def accurateCalculateInverseKinematics(kukaId, endEffectorId, targetPos, threshold, maxIter):
closeEnough = False
iter = 0
dist2 = 1e30
while (not closeEnough and iter < maxIter):
jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, targetPos)
for i in range(numJoints):
p.resetJointState(kukaId, i, jointPoses[i])
ls = p.getLinkState(kukaId, kukaEndEffectorIndex)
newPos = ls[4]
diff = [targetPos[0] - newPos[0], targetPos[1] - newPos[1], targetPos[2] - newPos[2]]
dist2 = (diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2])
closeEnough = (dist2 < threshold)
iter = iter + 1
#print ("Num iter: "+str(iter) + "threshold: "+str(dist2))
return jointPoses
wheels = [2, 3, 4, 5]
#(2, b'front_left_wheel', 0, 7, 6, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'front_left_wheel_link')
#(3, b'front_right_wheel', 0, 8, 7, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'front_right_wheel_link')
#(4, b'rear_left_wheel', 0, 9, 8, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'rear_left_wheel_link')
#(5, b'rear_right_wheel', 0, 10, 9, 1, 0.0, 0.0, 0.0, -1.0, 0.0, 0.0, b'rear_right_wheel_link')
wheelVelocities = [0, 0, 0, 0]
wheelDeltasTurn = [1, -1, 1, -1]
wheelDeltasFwd = [1, 1, 1, 1]
while 1:
keys = p.getKeyboardEvents()
shift = 0.01
wheelVelocities = [0, 0, 0, 0]
speed = 1.0
for k in keys:
if ord('s') in keys:
p.saveWorld("state.py")
if ord('a') in keys:
basepos = basepos = [basepos[0], basepos[1] - shift, basepos[2]]
if ord('d') in keys:
basepos = basepos = [basepos[0], basepos[1] + shift, basepos[2]]
if p.B3G_LEFT_ARROW in keys:
for i in range(len(wheels)):
wheelVelocities[i] = wheelVelocities[i] - speed * wheelDeltasTurn[i]
if p.B3G_RIGHT_ARROW in keys:
for i in range(len(wheels)):
wheelVelocities[i] = wheelVelocities[i] + speed * wheelDeltasTurn[i]
if p.B3G_UP_ARROW in keys:
for i in range(len(wheels)):
wheelVelocities[i] = wheelVelocities[i] + speed * wheelDeltasFwd[i]
if p.B3G_DOWN_ARROW in keys:
for i in range(len(wheels)):
wheelVelocities[i] = wheelVelocities[i] - speed * wheelDeltasFwd[i]
baseorn = p.getQuaternionFromEuler([0, 0, ang])
for i in range(len(wheels)):
p.setJointMotorControl2(husky,
wheels[i],
p.VELOCITY_CONTROL,
targetVelocity=wheelVelocities[i],
force=1000)
#p.resetBasePositionAndOrientation(kukaId,basepos,baseorn)#[0,0,0,1])
if (useRealTimeSimulation):
t = time.time() #(dt, micro) = datetime.utcnow().strftime('%Y-%m-%d %H:%M:%S.%f').split('.')
#t = (dt.second/60.)*2.*math.pi
else:
t = t + 0.001
if (useSimulation and useRealTimeSimulation == 0):
p.stepSimulation()
for i in range(1):
#pos = [-0.4,0.2*math.cos(t),0.+0.2*math.sin(t)]
pos = [0.2 * math.cos(t), 0, 0. + 0.2 * math.sin(t) + 0.7]
#end effector points down, not up (in case useOrientation==1)
orn = p.getQuaternionFromEuler([0, -math.pi, 0])
if (useNullSpace == 1):
if (useOrientation == 1):
jointPoses = p.calculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos, orn, ll, ul,
jr, rp)
else:
jointPoses = p.calculateInverseKinematics(kukaId,
kukaEndEffectorIndex,
pos,
lowerLimits=ll,
upperLimits=ul,
jointRanges=jr,
restPoses=rp)
else:
if (useOrientation == 1):
jointPoses = p.calculateInverseKinematics(kukaId,
kukaEndEffectorIndex,
pos,
orn,
jointDamping=jd)
else:
threshold = 0.001
maxIter = 100
jointPoses = accurateCalculateInverseKinematics(kukaId, kukaEndEffectorIndex, pos,
threshold, maxIter)
if (useSimulation):
for i in range(numJoints):
p.setJointMotorControl2(bodyIndex=kukaId,
jointIndex=i,
controlMode=p.POSITION_CONTROL,
targetPosition=jointPoses[i],
targetVelocity=0,
force=500,
positionGain=1,
velocityGain=0.1)
else:
#reset the joint state (ignoring all dynamics, not recommended to use during simulation)
for i in range(numJoints):
p.resetJointState(kukaId, i, jointPoses[i])
ls = p.getLinkState(kukaId, kukaEndEffectorIndex)
if (hasPrevPose):
p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration)
p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration)
prevPose = pos
prevPose1 = ls[4]
hasPrevPose = 1

View File

@ -0,0 +1,66 @@
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])
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.resetBasePositionAndOrientation(sawyerId, [0, 0, 0], [0, 0, 0, 1])
sawyerEndEffectorIndex = 3
numJoints = p.getNumJoints(sawyerId)
#joint damping coefficents
jd = [0.1, 0.1, 0.1, 0.1]
p.setGravity(0, 0, 0)
t = 0.
prevPose = [0, 0, 0]
prevPose1 = [0, 0, 0]
hasPrevPose = 0
ikSolver = 0
useRealTimeSimulation = 0
p.setRealTimeSimulation(useRealTimeSimulation)
#trailDuration is duration (in seconds) after debug lines will be removed automatically
#use 0 for no-removal
trailDuration = 1
while 1:
if (useRealTimeSimulation):
dt = datetime.now()
t = (dt.second / 60.) * 2. * math.pi
else:
t = t + 0.01
time.sleep(0.01)
for i in range(1):
pos = [2. * math.cos(t), 2. * math.cos(t), 0. + 2. * math.sin(t)]
jointPoses = p.calculateInverseKinematics(sawyerId,
sawyerEndEffectorIndex,
pos,
jointDamping=jd,
solver=ikSolver,
maxNumIterations=100)
#reset the joint state (ignoring all dynamics, not recommended to use during simulation)
for i in range(numJoints):
jointInfo = p.getJointInfo(sawyerId, i)
qIndex = jointInfo[3]
if qIndex > -1:
p.resetJointState(sawyerId, i, jointPoses[qIndex - 7])
ls = p.getLinkState(sawyerId, sawyerEndEffectorIndex)
if (hasPrevPose):
p.addUserDebugLine(prevPose, pos, [0, 0, 0.3], 1, trailDuration)
p.addUserDebugLine(prevPose1, ls[4], [1, 0, 0], 1, trailDuration)
prevPose = pos
prevPose1 = ls[4]
hasPrevPose = 1

View File

@ -0,0 +1,102 @@
import pybullet as p
import pybullet_data
def getJointStates(robot):
joint_states = p.getJointStates(robot, range(p.getNumJoints(robot)))
joint_positions = [state[0] for state in joint_states]
joint_velocities = [state[1] for state in joint_states]
joint_torques = [state[3] for state in joint_states]
return joint_positions, joint_velocities, joint_torques
def getMotorJointStates(robot):
joint_states = p.getJointStates(robot, range(p.getNumJoints(robot)))
joint_infos = [p.getJointInfo(robot, i) for i in range(p.getNumJoints(robot))]
joint_states = [j for j, i in zip(joint_states, joint_infos) if i[3] > -1]
joint_positions = [state[0] for state in joint_states]
joint_velocities = [state[1] for state in joint_states]
joint_torques = [state[3] for state in joint_states]
return joint_positions, joint_velocities, joint_torques
def setJointPosition(robot, position, kp=1.0, kv=0.3):
num_joints = p.getNumJoints(robot)
zero_vec = [0.0] * num_joints
if len(position) == num_joints:
p.setJointMotorControlArray(robot,
range(num_joints),
p.POSITION_CONTROL,
targetPositions=position,
targetVelocities=zero_vec,
positionGains=[kp] * num_joints,
velocityGains=[kv] * num_joints)
else:
print("Not setting torque. "
"Expected torque vector of "
"length {}, got {}".format(num_joints, len(torque)))
def multiplyJacobian(robot, jacobian, vector):
result = [0.0, 0.0, 0.0]
i = 0
for c in range(len(vector)):
if p.getJointInfo(robot, c)[3] > -1:
for r in range(3):
result[r] += jacobian[r][i] * vector[c]
i += 1
return result
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()
p.setTimeStep(time_step)
p.setGravity(0.0, 0.0, gravity_constant)
p.loadURDF("plane.urdf", [0, 0, -0.3])
kukaId = p.loadURDF("TwoJointRobot_w_fixedJoints.urdf", useFixedBase=True)
#kukaId = p.loadURDF("TwoJointRobot_w_fixedJoints.urdf",[0,0,0])
#kukaId = p.loadURDF("kuka_iiwa/model.urdf",[0,0,0])
#kukaId = p.loadURDF("kuka_lwr/kuka.urdf",[0,0,0])
#kukaId = p.loadURDF("humanoid/nao.urdf",[0,0,0])
p.resetBasePositionAndOrientation(kukaId, [0, 0, 0], [0, 0, 0, 1])
numJoints = p.getNumJoints(kukaId)
kukaEndEffectorIndex = numJoints - 1
# Set a joint target for the position control and step the sim.
setJointPosition(kukaId, [0.1] * numJoints)
p.stepSimulation()
# Get the joint and link state directly from Bullet.
pos, vel, torq = getJointStates(kukaId)
mpos, mvel, mtorq = getMotorJointStates(kukaId)
result = p.getLinkState(kukaId,
kukaEndEffectorIndex,
computeLinkVelocity=1,
computeForwardKinematics=1)
link_trn, link_rot, com_trn, com_rot, frame_pos, frame_rot, link_vt, link_vr = result
# Get the Jacobians for the CoM of the end-effector link.
# Note that in this example com_rot = identity, and we would need to use com_rot.T * com_trn.
# The localPosition is always defined in terms of the link frame coordinates.
zero_vec = [0.0] * len(mpos)
jac_t, jac_r = p.calculateJacobian(kukaId, kukaEndEffectorIndex, com_trn, mpos, zero_vec, zero_vec)
print("Link linear velocity of CoM from getLinkState:")
print(link_vt)
print("Link linear velocity of CoM from linearJacobian * q_dot:")
print(multiplyJacobian(kukaId, jac_t, vel))
print("Link angular velocity of CoM from getLinkState:")
print(link_vr)
print("Link angular velocity of CoM from angularJacobian * q_dot:")
print(multiplyJacobian(kukaId, jac_r, vel))

View File

@ -0,0 +1,38 @@
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()
p.loadURDF("plane.urdf", useMaximalCoordinates=True)
p.loadURDF("tray/traybox.urdf", useMaximalCoordinates=True)
gravXid = p.addUserDebugParameter("gravityX", -10, 10, 0)
gravYid = p.addUserDebugParameter("gravityY", -10, 10, 0)
gravZid = p.addUserDebugParameter("gravityZ", -10, 10, -10)
p.setPhysicsEngineParameter(numSolverIterations=10)
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
for i in range(10):
for j in range(10):
for k in range(10):
ob = p.loadURDF("sphere_1cm.urdf", [0.02 * i, 0.02 * j, 0.2 + 0.02 * k],
useMaximalCoordinates=True)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
while True:
gravX = p.readUserDebugParameter(gravXid)
gravY = p.readUserDebugParameter(gravYid)
gravZ = p.readUserDebugParameter(gravZid)
p.setGravity(gravX, gravY, gravZ)
time.sleep(0.01)

View File

@ -0,0 +1,50 @@
#a mimic joint can act as a gear between two joints
#you can control the gear ratio in magnitude and sign (>0 reverses direction)
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)):
print(p.getJointInfo(wheelA, i))
p.setJointMotorControl2(wheelA, i, p.VELOCITY_CONTROL, targetVelocity=0, force=0)
c = p.createConstraint(wheelA,
1,
wheelA,
3,
jointType=p.JOINT_GEAR,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=1, maxForce=10000)
c = p.createConstraint(wheelA,
2,
wheelA,
4,
jointType=p.JOINT_GEAR,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=-1, maxForce=10000)
c = p.createConstraint(wheelA,
1,
wheelA,
4,
jointType=p.JOINT_GEAR,
jointAxis=[0, 1, 0],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(c, gearRatio=-1, maxForce=10000)
p.setRealTimeSimulation(1)
while (1):
p.setGravity(0, 0, -10)
time.sleep(0.01)
#p.removeConstraint(c)

View File

@ -0,0 +1,22 @@
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,
1,
p.POSITION_CONTROL,
targetPosition=1000,
targetVelocity=0,
force=1000,
positionGain=1,
velocityGain=0,
maxVelocity=0.5)
while (1):
p.setGravity(0, 0, -10)
js = p.getJointState(cartpole, 1)
print("position=", js[0], "velocity=", js[1])
time.sleep(0.01)

View File

@ -0,0 +1,152 @@
import pybullet as p
from pdControllerExplicit import PDControllerExplicitMultiDof
from pdControllerExplicit import PDControllerExplicit
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)
pole4 = p.loadURDF("cartpole.urdf", [0, 3, 0], useMaximalCoordinates=useMaximalCoordinates)
exPD = PDControllerExplicitMultiDof(p)
sPD = PDControllerStable(p)
for i in range(p.getNumJoints(pole2)):
#disable default constraint-based motors
p.setJointMotorControl2(pole, i, p.POSITION_CONTROL, targetPosition=0, force=0)
p.setJointMotorControl2(pole2, i, p.POSITION_CONTROL, targetPosition=0, force=0)
p.setJointMotorControl2(pole3, i, p.POSITION_CONTROL, targetPosition=0, force=0)
p.setJointMotorControl2(pole4, i, p.POSITION_CONTROL, targetPosition=0, force=0)
#print("joint",i,"=",p.getJointInfo(pole2,i))
timeStepId = p.addUserDebugParameter("timeStep", 0.001, 0.1, 0.01)
desiredPosCartId = p.addUserDebugParameter("desiredPosCart", -10, 10, 2)
desiredVelCartId = p.addUserDebugParameter("desiredVelCart", -10, 10, 0)
kpCartId = p.addUserDebugParameter("kpCart", 0, 500, 1300)
kdCartId = p.addUserDebugParameter("kdCart", 0, 300, 150)
maxForceCartId = p.addUserDebugParameter("maxForceCart", 0, 5000, 1000)
textColor = [1, 1, 1]
shift = 0.05
p.addUserDebugText("explicit PD", [shift, 0, .1],
textColor,
parentObjectUniqueId=pole,
parentLinkIndex=1)
p.addUserDebugText("explicit PD plugin", [shift, 0, -.1],
textColor,
parentObjectUniqueId=pole2,
parentLinkIndex=1)
p.addUserDebugText("stablePD", [shift, 0, .1],
textColor,
parentObjectUniqueId=pole4,
parentLinkIndex=1)
p.addUserDebugText("position constraint", [shift, 0, -.1],
textColor,
parentObjectUniqueId=pole3,
parentLinkIndex=1)
desiredPosPoleId = p.addUserDebugParameter("desiredPosPole", -10, 10, 0)
desiredVelPoleId = p.addUserDebugParameter("desiredVelPole", -10, 10, 0)
kpPoleId = p.addUserDebugParameter("kpPole", 0, 500, 1200)
kdPoleId = p.addUserDebugParameter("kdPole", 0, 300, 100)
maxForcePoleId = p.addUserDebugParameter("maxForcePole", 0, 5000, 1000)
pd = p.loadPlugin("pdControlPlugin")
p.setGravity(0, 0, -10)
useRealTimeSim = False
p.setRealTimeSimulation(useRealTimeSim)
timeStep = 0.001
while p.isConnected():
#p.getCameraImage(320,200)
timeStep = p.readUserDebugParameter(timeStepId)
p.setTimeStep(timeStep)
desiredPosCart = p.readUserDebugParameter(desiredPosCartId)
desiredVelCart = p.readUserDebugParameter(desiredVelCartId)
kpCart = p.readUserDebugParameter(kpCartId)
kdCart = p.readUserDebugParameter(kdCartId)
maxForceCart = p.readUserDebugParameter(maxForceCartId)
desiredPosPole = p.readUserDebugParameter(desiredPosPoleId)
desiredVelPole = p.readUserDebugParameter(desiredVelPoleId)
kpPole = p.readUserDebugParameter(kpPoleId)
kdPole = p.readUserDebugParameter(kdPoleId)
maxForcePole = p.readUserDebugParameter(maxForcePoleId)
basePos, baseOrn = p.getBasePositionAndOrientation(pole)
baseDof = 7
taus = exPD.computePD(pole, [0, 1], [
basePos[0], basePos[1], basePos[2], baseOrn[0], baseOrn[1], baseOrn[2], baseOrn[3],
desiredPosCart, desiredPosPole
], [0, 0, 0, 0, 0, 0, 0, desiredVelCart, desiredVelPole], [0, 0, 0, 0, 0, 0, 0, kpCart, kpPole],
[0, 0, 0, 0, 0, 0, 0, kdCart, kdPole],
[0, 0, 0, 0, 0, 0, 0, maxForceCart, maxForcePole], timeStep)
for j in [0, 1]:
p.setJointMotorControlMultiDof(pole,
j,
controlMode=p.TORQUE_CONTROL,
force=[taus[j + baseDof]])
#p.setJointMotorControlArray(pole, [0,1], controlMode=p.TORQUE_CONTROL, forces=taus)
if (pd >= 0):
link = 0
p.setJointMotorControl2(bodyUniqueId=pole2,
jointIndex=link,
controlMode=p.PD_CONTROL,
targetPosition=desiredPosCart,
targetVelocity=desiredVelCart,
force=maxForceCart,
positionGain=kpCart,
velocityGain=kdCart)
link = 1
p.setJointMotorControl2(bodyUniqueId=pole2,
jointIndex=link,
controlMode=p.PD_CONTROL,
targetPosition=desiredPosPole,
targetVelocity=desiredVelPole,
force=maxForcePole,
positionGain=kpPole,
velocityGain=kdPole)
taus = sPD.computePD(pole4, [0, 1], [desiredPosCart, desiredPosPole],
[desiredVelCart, desiredVelPole], [kpCart, kpPole], [kdCart, kdPole],
[maxForceCart, maxForcePole], timeStep)
#p.setJointMotorControlArray(pole4, [0,1], controlMode=p.TORQUE_CONTROL, forces=taus)
for j in [0, 1]:
p.setJointMotorControlMultiDof(pole4, j, controlMode=p.TORQUE_CONTROL, force=[taus[j]])
p.setJointMotorControl2(pole3,
0,
p.POSITION_CONTROL,
targetPosition=desiredPosCart,
targetVelocity=desiredVelCart,
positionGain=timeStep * (kpCart / 150.),
velocityGain=0.5,
force=maxForceCart)
p.setJointMotorControl2(pole3,
1,
p.POSITION_CONTROL,
targetPosition=desiredPosPole,
targetVelocity=desiredVelPole,
positionGain=timeStep * (kpPole / 150.),
velocityGain=0.5,
force=maxForcePole)
if (not useRealTimeSim):
p.stepSimulation()
time.sleep(timeStep)

View File

@ -0,0 +1,98 @@
import numpy as np
class PDControllerExplicitMultiDof(object):
def __init__(self, pb):
self._pb = pb
def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds,
maxForces, timeStep):
numJoints = len(jointIndices) #self._pb.getNumJoints(bodyUniqueId)
curPos, curOrn = self._pb.getBasePositionAndOrientation(bodyUniqueId)
q1 = [curPos[0], curPos[1], curPos[2], curOrn[0], curOrn[1], curOrn[2], curOrn[3]]
baseLinVel, baseAngVel = self._pb.getBaseVelocity(bodyUniqueId)
qdot1 = [
baseLinVel[0], baseLinVel[1], baseLinVel[2], baseAngVel[0], baseAngVel[1], baseAngVel[2], 0
]
qError = [0, 0, 0, 0, 0, 0, 0]
qIndex = 7
qdotIndex = 7
zeroAccelerations = [0, 0, 0, 0, 0, 0, 0]
for i in range(numJoints):
js = self._pb.getJointStateMultiDof(bodyUniqueId, jointIndices[i])
jointPos = js[0]
jointVel = js[1]
q1 += jointPos
if len(js[0]) == 1:
desiredPos = desiredPositions[qIndex]
qdiff = desiredPos - jointPos[0]
qError.append(qdiff)
zeroAccelerations.append(0.)
qdot1 += jointVel
qIndex += 1
qdotIndex += 1
if len(js[0]) == 4:
desiredPos = [
desiredPositions[qIndex], desiredPositions[qIndex + 1], desiredPositions[qIndex + 2],
desiredPositions[qIndex + 3]
]
axis = self._pb.getAxisDifferenceQuaternion(desiredPos, jointPos)
jointVelNew = [jointVel[0], jointVel[1], jointVel[2], 0]
qdot1 += jointVelNew
qError.append(axis[0])
qError.append(axis[1])
qError.append(axis[2])
qError.append(0)
desiredVel = [
desiredVelocities[qdotIndex], desiredVelocities[qdotIndex + 1],
desiredVelocities[qdotIndex + 2]
]
zeroAccelerations += [0., 0., 0., 0.]
qIndex += 4
qdotIndex += 4
q = np.array(q1)
qdot = np.array(qdot1)
qdotdesired = np.array(desiredVelocities)
qdoterr = qdotdesired - qdot
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
p = Kp.dot(qError)
d = Kd.dot(qdoterr)
forces = p + d
maxF = np.array(maxForces)
forces = np.clip(forces, -maxF, maxF)
return forces
class PDControllerExplicit(object):
def __init__(self, pb):
self._pb = pb
def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds,
maxForces, timeStep):
numJoints = self._pb.getNumJoints(bodyUniqueId)
jointStates = self._pb.getJointStates(bodyUniqueId, jointIndices)
q1 = []
qdot1 = []
for i in range(numJoints):
q1.append(jointStates[i][0])
qdot1.append(jointStates[i][1])
q = np.array(q1)
qdot = np.array(qdot1)
qdes = np.array(desiredPositions)
qdotdes = np.array(desiredVelocities)
qError = qdes - q
qdotError = qdotdes - qdot
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
forces = Kp.dot(qError) + Kd.dot(qdotError)
maxF = np.array(maxForces)
forces = np.clip(forces, -maxF, maxF)
return forces

View File

@ -0,0 +1,147 @@
import numpy as np
class PDControllerStableMultiDof(object):
def __init__(self, pb):
self._pb = pb
def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds,
maxForces, timeStep):
numJoints = len(jointIndices) #self._pb.getNumJoints(bodyUniqueId)
curPos, curOrn = self._pb.getBasePositionAndOrientation(bodyUniqueId)
#q1 = [desiredPositions[0],desiredPositions[1],desiredPositions[2],desiredPositions[3],desiredPositions[4],desiredPositions[5],desiredPositions[6]]
q1 = [curPos[0], curPos[1], curPos[2], curOrn[0], curOrn[1], curOrn[2], curOrn[3]]
#qdot1 = [0,0,0, 0,0,0,0]
baseLinVel, baseAngVel = self._pb.getBaseVelocity(bodyUniqueId)
qdot1 = [
baseLinVel[0], baseLinVel[1], baseLinVel[2], baseAngVel[0], baseAngVel[1], baseAngVel[2], 0
]
qError = [0, 0, 0, 0, 0, 0, 0]
qIndex = 7
qdotIndex = 7
zeroAccelerations = [0, 0, 0, 0, 0, 0, 0]
for i in range(numJoints):
js = self._pb.getJointStateMultiDof(bodyUniqueId, jointIndices[i])
jointPos = js[0]
jointVel = js[1]
q1 += jointPos
if len(js[0]) == 1:
desiredPos = desiredPositions[qIndex]
qdiff = desiredPos - jointPos[0]
qError.append(qdiff)
zeroAccelerations.append(0.)
qdot1 += jointVel
qIndex += 1
qdotIndex += 1
if len(js[0]) == 4:
desiredPos = [
desiredPositions[qIndex], desiredPositions[qIndex + 1], desiredPositions[qIndex + 2],
desiredPositions[qIndex + 3]
]
axis = self._pb.getAxisDifferenceQuaternion(desiredPos, jointPos)
jointVelNew = [jointVel[0], jointVel[1], jointVel[2], 0]
qdot1 += jointVelNew
qError.append(axis[0])
qError.append(axis[1])
qError.append(axis[2])
qError.append(0)
desiredVel = [
desiredVelocities[qdotIndex], desiredVelocities[qdotIndex + 1],
desiredVelocities[qdotIndex + 2]
]
zeroAccelerations += [0., 0., 0., 0.]
qIndex += 4
qdotIndex += 4
q = np.array(q1)
qdot = np.array(qdot1)
qdotdesired = np.array(desiredVelocities)
qdoterr = qdotdesired - qdot
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
# Compute -Kp(q + qdot - qdes)
p_term = Kp.dot(qError - qdot*timeStep)
# Compute -Kd(qdot - qdotdes)
d_term = Kd.dot(qdoterr)
# Compute Inertia matrix M(q)
M = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1)
M = np.array(M)
# Given: M(q) * qddot + C(q, qdot) = T_ext + T_int
# Compute Coriolis and External (Gravitational) terms G = C - T_ext
G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1)
G = np.array(G)
# Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions
qddot = np.linalg.solve(a=(M + Kd * timeStep),
b=p_term + d_term - G)
# Compute control generalized forces (T_int)
tau = p_term + d_term - Kd.dot(qddot) * timeStep
# Clip generalized forces to actuator limits
maxF = np.array(maxForces)
generalized_forces = np.clip(tau, -maxF, maxF)
return generalized_forces
class PDControllerStable(object):
"""
Implementation based on: Tan, J., Liu, K., & Turk, G. (2011). "Stable proportional-derivative controllers"
DOI: 10.1109/MCG.2011.30
"""
def __init__(self, pb):
self._pb = pb
def computePD(self, bodyUniqueId, jointIndices, desiredPositions, desiredVelocities, kps, kds,
maxForces, timeStep):
numJoints = self._pb.getNumJoints(bodyUniqueId)
jointStates = self._pb.getJointStates(bodyUniqueId, jointIndices)
q1 = []
qdot1 = []
zeroAccelerations = []
for i in range(numJoints):
q1.append(jointStates[i][0])
qdot1.append(jointStates[i][1])
zeroAccelerations.append(0)
q = np.array(q1)
qdot = np.array(qdot1)
qdes = np.array(desiredPositions)
qdotdes = np.array(desiredVelocities)
qError = qdes - q
qdotError = qdotdes - qdot
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
# Compute -Kp(q + qdot - qdes)
p_term = Kp.dot(qError - qdot*timeStep)
# Compute -Kd(qdot - qdotdes)
d_term = Kd.dot(qdotError)
# Compute Inertia matrix M(q)
M = self._pb.calculateMassMatrix(bodyUniqueId, q1)
M = np.array(M)
# Given: M(q) * qddot + C(q, qdot) = T_ext + T_int
# Compute Coriolis and External (Gravitational) terms G = C - T_ext
G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations)
G = np.array(G)
# Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions
qddot = np.linalg.solve(a=(M + Kd * timeStep),
b=(-G + p_term + d_term))
# Compute control generalized forces (T_int)
tau = p_term + d_term - (Kd.dot(qddot) * timeStep)
# Clip generalized forces to actuator limits
maxF = np.array(maxForces)
generalized_forces = np.clip(tau, -maxF, maxF)
return generalized_forces

View File

@ -0,0 +1,138 @@
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])
def getRayFromTo(mouseX, mouseY):
width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera(
)
camPos = [
camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1],
camTarget[2] - dist * camForward[2]
]
farPlane = 10000
rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])]
lenFwd = math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] * rayForward[1] +
rayForward[2] * rayForward[2])
invLen = farPlane * 1. / lenFwd
rayForward = [invLen * rayForward[0], invLen * rayForward[1], invLen * rayForward[2]]
rayFrom = camPos
oneOverWidth = float(1) / float(width)
oneOverHeight = float(1) / float(height)
dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight]
rayToCenter = [
rayFrom[0] + rayForward[0], rayFrom[1] + rayForward[1], rayFrom[2] + rayForward[2]
]
ortho = [
-0.5 * horizon[0] + 0.5 * vertical[0] + float(mouseX) * dHor[0] - float(mouseY) * dVer[0],
-0.5 * horizon[1] + 0.5 * vertical[1] + float(mouseX) * dHor[1] - float(mouseY) * dVer[1],
-0.5 * horizon[2] + 0.5 * vertical[2] + float(mouseX) * dHor[2] - float(mouseY) * dVer[2]
]
rayTo = [
rayFrom[0] + rayForward[0] + ortho[0], rayFrom[1] + rayForward[1] + ortho[1],
rayFrom[2] + rayForward[2] + ortho[2]
]
lenOrtho = math.sqrt(ortho[0] * ortho[0] + ortho[1] * ortho[1] + ortho[2] * ortho[2])
alpha = math.atan(lenOrtho / farPlane)
return rayFrom, rayTo, alpha
width, height, viewMat, projMat, cameraUp, camForward, horizon, vertical, _, _, dist, camTarget = p.getDebugVisualizerCamera(
)
camPos = [
camTarget[0] - dist * camForward[0], camTarget[1] - dist * camForward[1],
camTarget[2] - dist * camForward[2]
]
farPlane = 10000
rayForward = [(camTarget[0] - camPos[0]), (camTarget[1] - camPos[1]), (camTarget[2] - camPos[2])]
lenFwd = math.sqrt(rayForward[0] * rayForward[0] + rayForward[1] * rayForward[1] +
rayForward[2] * rayForward[2])
oneOverWidth = float(1) / float(width)
oneOverHeight = float(1) / float(height)
dHor = [horizon[0] * oneOverWidth, horizon[1] * oneOverWidth, horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight, vertical[1] * oneOverHeight, vertical[2] * oneOverHeight]
lendHor = math.sqrt(dHor[0] * dHor[0] + dHor[1] * dHor[1] + dHor[2] * dHor[2])
lendVer = math.sqrt(dVer[0] * dVer[0] + dVer[1] * dVer[1] + dVer[2] * dVer[2])
cornersX = [0, width, width, 0]
cornersY = [0, 0, height, height]
corners3D = []
imgW = int(width / 4)
imgH = int(height / 4)
img = p.getCameraImage(imgW, imgH, renderer=p.ER_BULLET_HARDWARE_OPENGL)
rgbBuffer = img[2]
depthBuffer = img[3]
print("rgbBuffer.shape=", rgbBuffer.shape)
print("depthBuffer.shape=", depthBuffer.shape)
#disable rendering temporary makes adding objects faster
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER, 0)
visualShapeId = p.createVisualShape(shapeType=p.GEOM_SPHERE, rgbaColor=[1, 1, 1, 1], radius=0.03)
collisionShapeId = -1 #p.createCollisionShape(shapeType=p.GEOM_MESH, fileName="duck_vhacd.obj", collisionFramePosition=shift,meshScale=meshScale)
for i in range(4):
w = cornersX[i]
h = cornersY[i]
rayFrom, rayTo, _ = getRayFromTo(w, h)
rf = np.array(rayFrom)
rt = np.array(rayTo)
vec = rt - rf
l = np.sqrt(np.dot(vec, vec))
newTo = (0.01 / l) * vec + rf
#print("len vec=",np.sqrt(np.dot(vec,vec)))
p.addUserDebugLine(rayFrom, newTo, [1, 0, 0])
corners3D.append(newTo)
count = 0
stepX = 5
stepY = 5
for w in range(0, imgW, stepX):
for h in range(0, imgH, stepY):
count += 1
if ((count % 100) == 0):
print(count, "out of ", imgW * imgH / (stepX * stepY))
rayFrom, rayTo, alpha = getRayFromTo(w * (width / imgW), h * (height / imgH))
rf = np.array(rayFrom)
rt = np.array(rayTo)
vec = rt - rf
l = np.sqrt(np.dot(vec, vec))
depthImg = float(depthBuffer[h, w])
far = 1000.
near = 0.01
depth = far * near / (far - (far - near) * depthImg)
depth /= math.cos(alpha)
newTo = (depth / l) * vec + rf
#p.addUserDebugLine(rayFrom, newTo, [1, 0, 0])
mb = p.createMultiBody(baseMass=0,
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=newTo,
useMaximalCoordinates=True)
color = rgbBuffer[h, w]
color = [color[0] / 255., color[1] / 255., color[2] / 255., 1]
p.changeVisualShape(mb, -1, rgbaColor=color)
p.addUserDebugLine(corners3D[0], corners3D[1], [1, 0, 0])
p.addUserDebugLine(corners3D[1], corners3D[2], [1, 0, 0])
p.addUserDebugLine(corners3D[2], corners3D[3], [1, 0, 0])
p.addUserDebugLine(corners3D[3], corners3D[0], [1, 0, 0])
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
print("ready\n")
#p.removeBody(plane)
#p.removeBody(cube)
while (1):
p.setGravity(0, 0, -10)

View File

@ -0,0 +1,25 @@
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
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json")
while (time.time() < t):
p.stepSimulation()
p.submitProfileTiming("pythontest")
time.sleep(1./240.)
p.submitProfileTiming("nested")
for i in range (100):
p.submitProfileTiming("deep_nested")
p.submitProfileTiming()
time.sleep(1./1000.)
p.submitProfileTiming()
p.submitProfileTiming()
p.stopStateLogging(logId)

View File

@ -0,0 +1,41 @@
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])
bearId1 = p.loadURDF("plane.urdf", bearStartPos1, bearStartOrientation1)
bearStartPos2 = [0, 0, 0]
bearStartOrientation2 = p.getQuaternionFromEuler([0, 0, 0])
bearId2 = p.loadURDF("teddy_large.urdf", bearStartPos2, bearStartOrientation2)
textureId = p.loadTexture("checker_grid.jpg")
#p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
#p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
useRealTimeSimulation = 1
if (useRealTimeSimulation):
p.setRealTimeSimulation(1)
while 1:
if (useRealTimeSimulation):
camera = p.getDebugVisualizerCamera()
viewMat = camera[2]
projMat = camera[3]
#An example of setting the view matrix for the projective texture.
#viewMat = p.computeViewMatrix(cameraEyePosition=[7,0,0], cameraTargetPosition=[0,0,0], cameraUpVector=[0,0,1])
p.getCameraImage(300,
300,
renderer=p.ER_BULLET_HARDWARE_OPENGL,
flags=p.ER_USE_PROJECTIVE_TEXTURE,
projectiveTextureView=viewMat,
projectiveTextureProj=projMat)
p.setGravity(0, 0, 0)
else:
p.stepSimulation()

View File

@ -0,0 +1,28 @@
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)
yawId = p.addUserDebugParameter("yaw", -1.5, 1.5, 0)
fwdxId = p.addUserDebugParameter("fwd_x", -1, 1, 0)
fwdyId = p.addUserDebugParameter("fwd_y", -1, 1, 0)
fwdzId = p.addUserDebugParameter("fwd_z", -1, 1, 0)
while True:
roll = p.readUserDebugParameter(rollId)
pitch = p.readUserDebugParameter(pitchId)
yaw = p.readUserDebugParameter(yawId)
x = p.readUserDebugParameter(fwdxId)
y = p.readUserDebugParameter(fwdyId)
z = p.readUserDebugParameter(fwdzId)
orn = p.getQuaternionFromEuler([roll, pitch, yaw])
p.resetBasePositionAndOrientation(q, [x, y, z], orn)
#p.stepSimulation()#not really necessary for this demo, no physics used

View File

@ -0,0 +1,21 @@
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],
globalScaling=50,
useFixedBase=True,
flags=p.URDF_INITIALIZE_SAT_FEATURES)
p.loadURDF("cube.urdf", [0, 0, 1], globalScaling=1, flags=p.URDF_INITIALIZE_SAT_FEATURES)
p.loadURDF("duck_vhacd.urdf", [1, 0, 1], globalScaling=1, flags=p.URDF_INITIALIZE_SAT_FEATURES)
while (p.isConnected()):
p.stepSimulation()
pts = p.getContactPoints()
#print("num contacts = ", len(pts))
time.sleep(1. / 240.)

View File

@ -0,0 +1,42 @@
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])
dt = 1./240.
p.setTimeStep(dt)
def getSceneAABB():
aabbMins=[]
aabbMaxs=[]
for i in range(p.getNumBodies()):
uid = p.getBodyUniqueId(i)
aabb = p.getAABB(uid)
aabbMins.append(np.array(aabb[0]))
aabbMaxs.append(np.array(aabb[1]))
if len(aabbMins):
sceneAABBMin = aabbMins[0]
sceneAABBMax = aabbMaxs[0]
for aabb in aabbMins:
sceneAABBMin = np.minimum(sceneAABBMin,aabb)
for aabb in aabbMaxs:
sceneAABBMax = np.maximum(sceneAABBMax,aabb)
print("sceneAABBMin=",sceneAABBMin)
print("sceneAABBMax=",sceneAABBMax)
getSceneAABB()
while (1):
p.stepSimulation()
time.sleep(dt)

View File

@ -0,0 +1,17 @@
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):
p.loadURDF("sphere_1cm.urdf", [i * 0.02, 0, 0.5])
p.loadURDF("duck_vhacd.urdf")
timeStep = 1. / 240.
p.setTimeStep(timeStep)
while (1):
p.stepSimulation()
time.sleep(timeStep)

View File

@ -0,0 +1,144 @@
import pybullet as p
import time
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)
useMaximalCoordinates = True
sphereRadius = 0.25
#colBoxId = p.createCollisionShapeArray([p.GEOM_BOX, p.GEOM_SPHERE],radii=[sphereRadius+0.03,sphereRadius+0.03], halfExtents=[[sphereRadius,sphereRadius,sphereRadius],[sphereRadius,sphereRadius,sphereRadius]])
colBoxId = p.createCollisionShape(p.GEOM_BOX,
halfExtents=[sphereRadius, sphereRadius, sphereRadius])
mass = 1
visualShapeId = -1
link_Masses = []
linkCollisionShapeIndices = []
linkVisualShapeIndices = []
linkPositions = []
linkOrientations = []
linkInertialFramePositions = []
linkInertialFrameOrientations = []
indices = []
jointTypes = []
axis = []
for i in range(36):
link_Masses.append(1)
linkCollisionShapeIndices.append(colBoxId)
linkVisualShapeIndices.append(-1)
linkPositions.append([0, sphereRadius * 2.0 + 0.01, 0])
linkOrientations.append([0, 0, 0, 1])
linkInertialFramePositions.append([0, 0, 0])
linkInertialFrameOrientations.append([0, 0, 0, 1])
indices.append(i)
jointTypes.append(p.JOINT_REVOLUTE)
axis.append([0, 0, 1])
basePosition = [0, 0, 1]
baseOrientation = [0, 0, 0, 1]
sphereUid = p.createMultiBody(mass,
colBoxId,
visualShapeId,
basePosition,
baseOrientation,
linkMasses=link_Masses,
linkCollisionShapeIndices=linkCollisionShapeIndices,
linkVisualShapeIndices=linkVisualShapeIndices,
linkPositions=linkPositions,
linkOrientations=linkOrientations,
linkInertialFramePositions=linkInertialFramePositions,
linkInertialFrameOrientations=linkInertialFrameOrientations,
linkParentIndices=indices,
linkJointTypes=jointTypes,
linkJointAxis=axis,
useMaximalCoordinates=useMaximalCoordinates)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(0)
anistropicFriction = [1, 0.01, 0.01]
p.changeDynamics(sphereUid, -1, lateralFriction=2, anisotropicFriction=anistropicFriction)
p.getNumJoints(sphereUid)
for i in range(p.getNumJoints(sphereUid)):
p.getJointInfo(sphereUid, i)
p.changeDynamics(sphereUid, i, lateralFriction=2, anisotropicFriction=anistropicFriction)
dt = 1. / 240.
SNAKE_NORMAL_PERIOD = 0.1 #1.5
m_wavePeriod = SNAKE_NORMAL_PERIOD
m_waveLength = 4
m_wavePeriod = 1.5
m_waveAmplitude = 0.4
m_waveFront = 0.0
#our steering value
m_steering = 0.0
m_segmentLength = sphereRadius * 2.0
forward = 0
while (1):
keys = p.getKeyboardEvents()
for k, v in keys.items():
if (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_TRIGGERED)):
m_steering = -.2
if (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_RELEASED)):
m_steering = 0
if (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_TRIGGERED)):
m_steering = .2
if (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_RELEASED)):
m_steering = 0
amp = 0.2
offset = 0.6
numMuscles = p.getNumJoints(sphereUid)
scaleStart = 1.0
#start of the snake with smaller waves.
#I think starting the wave at the tail would work better ( while it still goes from head to tail )
if (m_waveFront < m_segmentLength * 4.0):
scaleStart = m_waveFront / (m_segmentLength * 4.0)
segment = numMuscles - 1
#we simply move a sin wave down the body of the snake.
#this snake may be going backwards, but who can tell ;)
for joint in range(p.getNumJoints(sphereUid)):
segment = joint #numMuscles-1-joint
#map segment to phase
phase = (m_waveFront - (segment + 1) * m_segmentLength) / m_waveLength
phase -= math.floor(phase)
phase *= math.pi * 2.0
#map phase to curvature
targetPos = math.sin(phase) * scaleStart * m_waveAmplitude
#// steer snake by squashing +ve or -ve side of sin curve
if (m_steering > 0 and targetPos < 0):
targetPos *= 1.0 / (1.0 + m_steering)
if (m_steering < 0 and targetPos > 0):
targetPos *= 1.0 / (1.0 - m_steering)
#set our motor
p.setJointMotorControl2(sphereUid,
joint,
p.POSITION_CONTROL,
targetPosition=targetPos + m_steering,
force=30)
#wave keeps track of where the wave is in time
m_waveFront += dt / m_wavePeriod * m_waveLength
p.stepSimulation()
time.sleep(dt)

View File

@ -0,0 +1,17 @@
import pybullet as p
import pybullet_data as pd
import time
p.connect(p.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
offset = 0
for scale in range (1,10,1):
ball = p.loadURDF("soccerball.urdf",[offset,0,1], globalScaling=scale*0.1)
p.changeDynamics(ball,-1,linearDamping=0, angularDamping=0, rollingFriction=0.001, spinningFriction=0.001)
p.changeVisualShape(ball,-1,rgbaColor=[0.8,0.8,0.8,1])
offset += 2*scale*0.1
p.loadURDF("plane.urdf")
p.setGravity(0,0,-10)
p.setRealTimeSimulation(1)
while p.isConnected():
#p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL)
time.sleep(0.5)

View File

@ -0,0 +1,32 @@
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)
#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001)
p.loadURDF("plane.urdf")
radius = 0.025
distance = 1.86
yaw = 135
pitch = -11
targetPos = [0, 0, 0]
p.setPhysicsEngineParameter(solverResidualThreshold=0.001, numSolverIterations=200)
p.resetDebugVisualizerCamera(distance, yaw, pitch, targetPos)
objectId = -1
for i in range(10):
objectId = p.loadURDF("cube_small.urdf", [1, 1, radius + i * 2 * radius])
p.changeDynamics(objectId, -1, 100)
timeStep = 1. / 240.
p.setGravity(0, 0, -10)
while (p.isConnected()):
p.stepSimulation()
time.sleep(timeStep)

View File

@ -0,0 +1,102 @@
#using the eglRendererPlugin (hardware OpenGL acceleration)
#using EGL on Linux and default OpenGL window on Win32.
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
#otherwise use testrender.py (slower but compatible without numpy)
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)
import numpy as np
import matplotlib.pyplot as plt
import pybullet
import time
import pkgutil
plt.ion()
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):
pluginId = pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin")
else:
pluginId = pybullet.loadPlugin("eglRendererPlugin")
print("pluginId=",pluginId)
pybullet.loadURDF("plane.urdf", [0, 0, -1])
pybullet.loadURDF("r2d2.urdf")
camTargetPos = [0, 0, 0]
cameraUp = [0, 0, 1]
cameraPos = [1, 1, 1]
pybullet.setGravity(0, 0, -10)
pitch = -10.0
roll = 0
upAxisIndex = 2
camDistance = 4
pixelWidth = 320
pixelHeight = 200
nearPlane = 0.01
farPlane = 100
fov = 60
main_start = time.time()
while (1):
for yaw in range(0, 360, 10):
pybullet.stepSimulation()
start = time.time()
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch,
roll, upAxisIndex)
aspect = pixelWidth / pixelHeight
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane)
img_arr = pybullet.getCameraImage(pixelWidth,
pixelHeight,
viewMatrix,
projectionMatrix,
shadow=1,
lightDirection=[1, 1, 1],
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
stop = time.time()
#print("renderImage %f" % (stop - start))
w = img_arr[0] #width of the image, in pixels
h = img_arr[1] #height of the image, in pixels
rgb = img_arr[2] #color data RGB
dep = img_arr[3] #depth data
#print('width = %d height = %d' % (w, h))
#note that sending the data to matplotlib is really slow
#reshape is not needed
np_img_arr = np.reshape(rgb, (h, w, 4))
np_img_arr = np_img_arr * (1. / 255.)
#show
#plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200))
#image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah")
image.set_data(np_img_arr)
ax.plot([0])
#plt.draw()
#plt.show()
plt.pause(0.01)
#image.draw()
main_stop = time.time()
print("Total time %f" % (main_stop - main_start))
pybullet.resetSimulation()

View File

@ -0,0 +1,90 @@
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
#otherwise use testrender.py (slower but compatible without numpy)
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)
import numpy as np
import matplotlib.pyplot as plt
import pybullet
import time
import pybullet_data
plt.ion()
img = np.random.rand(200, 320)
#img = [tandard_normal((50,100))
image = plt.imshow(img, interpolation='none', animated=True, label="blah")
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")
camTargetPos = [0, 0, 0]
cameraUp = [0, 0, 1]
cameraPos = [1, 1, 1]
pybullet.setGravity(0, 0, -10)
pitch = -10.0
roll = 0
upAxisIndex = 2
camDistance = 4
pixelWidth = 320
pixelHeight = 200
nearPlane = 0.01
farPlane = 100
fov = 60
main_start = time.time()
while (1):
for yaw in range(0, 360, 10):
pybullet.stepSimulation()
start = time.time()
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch,
roll, upAxisIndex)
aspect = pixelWidth / pixelHeight
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane)
img_arr = pybullet.getCameraImage(pixelWidth,
pixelHeight,
viewMatrix,
projectionMatrix,
shadow=1,
lightDirection=[1, 1, 1],
renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
stop = time.time()
print("renderImage %f" % (stop - start))
w = img_arr[0] #width of the image, in pixels
h = img_arr[1] #height of the image, in pixels
rgb = img_arr[2] #color data RGB
dep = img_arr[3] #depth data
print('width = %d height = %d' % (w, h))
#note that sending the data to matplotlib is really slow
#reshape is needed
np_img_arr = np.reshape(rgb, (h, w, 4))
np_img_arr = np_img_arr * (1. / 255.)
#show
#plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200))
#image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah")
image.set_data(np_img_arr)
ax.plot([0])
#plt.draw()
#plt.show()
plt.pause(0.01)
#image.draw()
main_stop = time.time()
print("Total time %f" % (main_stop - main_start))
pybullet.resetSimulation()

View File

@ -0,0 +1,25 @@
import pybullet as p
import time
import pybullet_data
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.loadURDF("plane.urdf")
sphereUid = p.loadURDF("sphere_transparent.urdf", [0, 0, 2])
redSlider = p.addUserDebugParameter("red", 0, 1, 1)
greenSlider = p.addUserDebugParameter("green", 0, 1, 0)
blueSlider = p.addUserDebugParameter("blue", 0, 1, 0)
alphaSlider = p.addUserDebugParameter("alpha", 0, 1, 0.5)
while (1):
red = p.readUserDebugParameter(redSlider)
green = p.readUserDebugParameter(greenSlider)
blue = p.readUserDebugParameter(blueSlider)
alpha = p.readUserDebugParameter(alphaSlider)
p.changeVisualShape(sphereUid, -1, rgbaColor=[red, green, blue, alpha])
p.getCameraImage(320,
200,
flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX,
renderer=p.ER_BULLET_HARDWARE_OPENGL)
time.sleep(0.01)

View File

@ -0,0 +1,13 @@
import pybullet as p
import pybullet_data as pd
import os
import pybullet_data
p.connect(p.DIRECT)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
name_in = os.path.join(pd.getDataPath(), "duck.obj")
name_out = "duck_vhacd.obj"
name_log = "log.txt"
p.vhacd(name_in, name_out, name_log)

View File

@ -0,0 +1,32 @@
import pybullet as p
import time
import pybullet_data
#Once the video is recorded, you can extract all individual frames using ffmpeg
#mkdir frames
#ffmpeg -i test.mp4 "frames/out-%03d.png"
#by default, PyBullet runs at 240Hz
p.connect(p.GUI, options="--width=320 --height=200 --mp4=\"test.mp4\" --mp4fps=240")
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
p.loadURDF("plane.urdf")
#in 3 seconds, the object travels about 0.5*g*t^2 meter ~ 45 meter.
r2d2 = p.loadURDF("r2d2.urdf",[0,0,45])
#disable linear damping
p.changeDynamics(r2d2,-1, linearDamping=0)
p.setGravity(0,0,-10)
for i in range (3*240):
txt = "frame "+str(i)
item = p.addUserDebugText(txt, [0,1,0])
p.stepSimulation()
#synchronize the visualizer (rendering frames for the video mp4) with stepSimulation
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
#print("r2d2 vel=", p.getBaseVelocity(r2d2)[0][2])
p.removeUserDebugItem(item)
p.disconnect()

View File

@ -0,0 +1,184 @@
import pybullet as p
import time
#p.connect(p.UDP,"192.168.86.100")
import pybullet_data
cid = p.connect(p.SHARED_MEMORY)
if (cid < 0):
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
#disable rendering during loading makes it much faster
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
objects = [
p.loadURDF("plane.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.000000)
]
objects = [
p.loadURDF("samurai.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("pr2_gripper.urdf", 0.500000, 0.300006, 0.700000, -0.000000, -0.000000, -0.000031,
1.000000)
]
pr2_gripper = objects[0]
print("pr2_gripper=")
print(pr2_gripper)
jointPositions = [0.550569, 0.000000, 0.549657, 0.000000]
for jointIndex in range(p.getNumJoints(pr2_gripper)):
p.resetJointState(pr2_gripper, jointIndex, jointPositions[jointIndex])
pr2_cid = p.createConstraint(pr2_gripper, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0.2, 0, 0],
[0.500000, 0.300006, 0.700000])
print("pr2_cid")
print(pr2_cid)
objects = [
p.loadURDF("kuka_iiwa/model_vr_limits.urdf", 1.400000, -0.200000, 0.600000, 0.000000, 0.000000,
0.000000, 1.000000)
]
kuka = objects[0]
jointPositions = [-0.000000, -0.000000, 0.000000, 1.570793, 0.000000, -1.036725, 0.000001]
for jointIndex in range(p.getNumJoints(kuka)):
p.resetJointState(kuka, jointIndex, jointPositions[jointIndex])
p.setJointMotorControl2(kuka, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex], 0)
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.700000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.800000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.900000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = p.loadSDF("gripper/wsg50_one_motor_gripper_new_free_base.sdf")
kuka_gripper = objects[0]
print("kuka gripper=")
print(kuka_gripper)
p.resetBasePositionAndOrientation(kuka_gripper, [0.923103, -0.200000, 1.250036],
[-0.000000, 0.964531, -0.000002, -0.263970])
jointPositions = [
0.000000, -0.011130, -0.206421, 0.205143, -0.009999, 0.000000, -0.010055, 0.000000
]
for jointIndex in range(p.getNumJoints(kuka_gripper)):
p.resetJointState(kuka_gripper, jointIndex, jointPositions[jointIndex])
p.setJointMotorControl2(kuka_gripper, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex],
0)
kuka_cid = p.createConstraint(kuka, 6, kuka_gripper, 0, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0.05],
[0, 0, 0])
pr2_cid2 = p.createConstraint(kuka_gripper,
4,
kuka_gripper,
6,
jointType=p.JOINT_GEAR,
jointAxis=[1, 1, 1],
parentFramePosition=[0, 0, 0],
childFramePosition=[0, 0, 0])
p.changeConstraint(pr2_cid2, gearRatio=-1, erp=0.5, relativePositionTarget=0, maxForce=100)
objects = [
p.loadURDF("jenga/jenga.urdf", 1.300000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.200000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.100000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.000000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 0.900000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 0.800000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("table/table.urdf", 1.000000, -0.200000, 0.000000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("teddy_vhacd.urdf", 1.050000, -0.500000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("cube_small.urdf", 0.950000, -0.100000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("sphere_small.urdf", 0.850000, -0.400000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("duck_vhacd.urdf", 0.850000, -0.400000, 0.900000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = p.loadSDF("kiva_shelf/model.sdf")
ob = objects[0]
p.resetBasePositionAndOrientation(ob, [0.000000, 1.000000, 1.204500],
[0.000000, 0.000000, 0.000000, 1.000000])
objects = [
p.loadURDF("teddy_vhacd.urdf", -0.100000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("sphere_small.urdf", -0.100000, 0.955006, 1.169706, 0.633232, -0.000000, -0.000000,
0.773962)
]
objects = [
p.loadURDF("cube_small.urdf", 0.300000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("table_square/table_square.urdf", -1.000000, 0.000000, 0.000000, 0.000000, 0.000000,
0.000000, 1.000000)
]
ob = objects[0]
jointPositions = [0.000000]
for jointIndex in range(p.getNumJoints(ob)):
p.resetJointState(ob, jointIndex, jointPositions[jointIndex])
objects = [
p.loadURDF("husky/husky.urdf", 2.000000, -5.000000, 1.000000, 0.000000, 0.000000, 0.000000,
1.000000)
]
ob = objects[0]
jointPositions = [
0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000,
0.000000
]
for jointIndex in range(p.getNumJoints(ob)):
p.resetJointState(ob, jointIndex, jointPositions[jointIndex])
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0.000000, 0.000000, 0.000000)
p.setGravity(0, 0, -10)
##show this for 10 seconds
#now = time.time()
#while (time.time() < now+10):
# p.stepSimulation()
p.setRealTimeSimulation(1)
while (1):
p.setGravity(0, 0, -10)
p.disconnect()

View File

@ -459,7 +459,7 @@ hh = setup_py_dir + "/" + datadir
for root, dirs, files in os.walk(hh):
for fn in files:
ext = os.path.splitext(fn)[1][1:]
if ext and ext in 'yaml index meta data-00000-of-00001 png gif jpg urdf sdf obj txt mtl dae off stl STL xml '.split(
if ext and ext in 'yaml index meta data-00000-of-00001 png gif jpg urdf sdf obj txt mtl dae off stl STL xml gin npy '.split(
):
fn = root + "/" + fn
need_files.append(fn[1 + len(hh):])
@ -501,7 +501,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
setup(
name='pybullet',
version='3.1.0',
version='3.1.2',
description=
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description=