fix pybullet.c compilation for Windows

add lego.urdf, duck.urdf (optimized using VHACD convex decomposition)
optimize Kiva shelf collision model (by hand, using boxes/Blender)
physics timescale toggle between  1 -> 0,25 -> 0
This commit is contained in:
erwincoumans
2016-09-24 11:25:05 -07:00
parent 0dfe20c036
commit f5e65197f4
13 changed files with 16333 additions and 38 deletions

13
data/duck.mtl Normal file
View File

@@ -0,0 +1,13 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl blinn3
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.640000 0.640000 0.640000
Ks 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Ka duckCM.png
map_Kd duckCM.png

8604
data/duck.obj Normal file

File diff suppressed because it is too large Load Diff

BIN
data/duckCM.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

609
data/duck_vhacd.obj Normal file
View File

@@ -0,0 +1,609 @@
o convex_0
v -0.086018 0.502143 0.615873
v -0.225720 0.427101 -0.544625
v -0.268729 0.362660 -0.533833
v 0.623016 0.276638 -0.017993
v 0.601512 0.867587 -0.082516
v -0.601818 0.867587 0.003477
v -0.677007 0.126174 0.228965
v 0.386620 0.244455 0.476150
v 0.300756 0.137003 -0.351171
v 0.569331 0.835252 0.282696
v -0.677007 0.190691 -0.286648
v -0.709188 0.631101 0.379366
v -0.472792 0.706295 -0.383432
v 0.483314 0.577413 -0.404901
v -0.859718 0.545154 -0.050254
v 0.150225 0.104745 0.432983
v -0.386774 0.867587 0.293487
v -0.537305 0.244455 0.486828
v -0.247225 0.094067 -0.329701
v 0.623016 0.588166 0.368574
v -0.666179 0.534402 -0.394110
v -0.257901 0.867587 -0.232917
v -0.107523 0.620348 -0.512363
v -0.290081 0.620348 0.572820
v 0.386620 0.104745 0.121503
v 0.666025 0.523649 -0.189864
v -0.838214 0.287390 0.121503
v 0.515647 0.856758 -0.200656
v 0.161053 0.373413 -0.523041
v 0.225414 0.577413 0.562029
v -0.257901 0.362660 0.615873
v -0.279405 0.094067 0.400949
v 0.687529 0.502295 0.207382
v -0.655503 0.405595 0.476150
v 0.461810 0.330402 -0.394110
v -0.633999 0.104745 -0.146925
v 0.526323 0.222949 0.293374
v -0.677007 0.770811 -0.168508
v -0.161207 0.169261 -0.447841
v 0.515647 0.867587 0.271904
v -0.838214 0.620424 0.132295
v 0.118045 0.341079 0.594290
v -0.805881 0.287390 -0.168508
v 0.311431 0.094067 -0.157716
v -0.601818 0.287466 -0.415579
v 0.676853 0.749306 0.024946
v 0.483314 0.566660 0.486828
v -0.193388 0.169261 0.519089
v -0.752196 0.341154 0.357896
v -0.644674 0.792241 0.250435
v 0.128721 0.577413 -0.512250
v 0.633845 0.652607 -0.254387
v -0.580314 0.663359 0.454567
v 0.472638 0.180014 -0.222239
v -0.419107 0.566660 -0.490894
v -0.118199 0.663359 0.540559
v -0.504972 0.158508 -0.372527
v -0.773701 0.179938 -0.039576
v 0.289927 0.094067 0.304165
v -0.397603 0.523649 0.583612
v -0.483620 0.867587 -0.179186
v 0.547827 0.362660 0.400949
v -0.655503 0.169186 0.357896
v -0.773701 0.727800 -0.039576
f 41 50 64
f 5 6 17
f 6 5 22
f 13 22 23
f 22 5 28
f 23 22 28
f 3 2 29
f 24 1 30
f 4 26 33
f 18 31 34
f 9 29 35
f 29 14 35
f 32 7 36
f 19 32 36
f 25 4 37
f 4 33 37
f 13 21 38
f 9 19 39
f 3 29 39
f 29 9 39
f 10 5 40
f 5 17 40
f 30 10 40
f 15 27 41
f 16 8 42
f 30 1 42
f 1 31 42
f 15 21 43
f 27 15 43
f 19 9 44
f 32 19 44
f 11 43 45
f 43 21 45
f 5 10 46
f 10 20 46
f 20 33 46
f 33 26 46
f 20 10 47
f 10 30 47
f 42 8 47
f 30 42 47
f 31 18 48
f 32 16 48
f 16 42 48
f 42 31 48
f 34 12 49
f 12 41 49
f 41 27 49
f 17 6 50
f 41 12 50
f 2 23 51
f 28 14 51
f 23 28 51
f 29 2 51
f 14 29 51
f 28 5 52
f 14 28 52
f 26 35 52
f 35 14 52
f 5 46 52
f 46 26 52
f 24 17 53
f 12 34 53
f 17 50 53
f 50 12 53
f 4 25 54
f 26 4 54
f 9 35 54
f 35 26 54
f 44 9 54
f 25 44 54
f 2 3 55
f 21 13 55
f 23 2 55
f 13 23 55
f 3 45 55
f 45 21 55
f 17 24 56
f 24 30 56
f 40 17 56
f 30 40 56
f 36 11 57
f 19 36 57
f 3 39 57
f 39 19 57
f 45 3 57
f 11 45 57
f 7 27 58
f 11 36 58
f 36 7 58
f 43 11 58
f 27 43 58
f 8 16 59
f 16 32 59
f 37 8 59
f 25 37 59
f 44 25 59
f 32 44 59
f 1 24 60
f 31 1 60
f 34 31 60
f 24 53 60
f 53 34 60
f 6 22 61
f 22 13 61
f 38 6 61
f 13 38 61
f 33 20 62
f 8 37 62
f 37 33 62
f 47 8 62
f 20 47 62
f 27 7 63
f 7 32 63
f 18 34 63
f 48 18 63
f 32 48 63
f 49 27 63
f 34 49 63
f 21 15 64
f 6 38 64
f 38 21 64
f 15 41 64
f 50 6 64
o convex_1
v -0.193580 1.125601 0.443872
v -0.236532 1.179294 -0.383444
v -0.236532 1.275851 -0.383444
v -0.741519 1.222234 0.368646
v -0.150542 1.619669 0.089200
v -0.032381 0.867587 -0.007315
v -0.709262 1.114847 -0.179140
v -0.601710 1.544392 -0.125539
v 0.139599 1.254419 -0.018086
v -0.526501 0.867587 0.207508
v -0.451206 1.533714 0.347105
v -0.365302 0.867587 -0.232909
v 0.021352 1.297359 0.314961
v -0.139847 1.512131 -0.243679
v -0.000124 1.104094 -0.275907
v -0.043162 0.942863 0.261193
v -0.440511 1.061079 0.454558
v -0.505025 1.200802 -0.351133
v -0.677005 0.953692 -0.028772
v -0.300960 1.437006 0.422331
v -0.741519 1.372559 0.175280
v -0.215056 0.867587 0.293336
v 0.053609 1.458514 -0.071770
v -0.386864 1.641176 -0.028772
v -0.365388 1.501453 -0.286593
v -0.741519 1.093340 0.336418
v 0.107342 1.039647 0.067827
v -0.000124 1.480021 0.207340
v -0.000124 1.340298 -0.265136
v -0.612577 1.533714 0.164510
v -0.150628 0.932109 -0.265136
v -0.505025 1.050325 -0.329676
v -0.537196 0.867587 -0.136226
v -0.741519 1.275851 -0.082541
v -0.558758 1.447760 -0.254366
v -0.440511 1.190048 0.476184
v -0.279570 1.608991 0.228881
v 0.075085 1.028817 -0.125455
v 0.064304 1.125601 0.261193
v 0.118037 1.286605 0.153739
v -0.193580 1.608991 -0.114684
v -0.096809 1.404745 0.368646
v -0.451206 1.630422 0.099886
v -0.225837 1.050325 -0.361903
v 0.096561 1.254419 -0.168453
v -0.741519 1.082662 -0.050229
v -0.515806 0.953692 0.347105
v -0.644748 1.211556 -0.265136
v -0.107590 1.028893 0.379332
v -0.182799 1.555222 0.282734
v -0.096895 0.867587 -0.157683
v -0.397559 1.350976 -0.361903
v -0.139847 1.232987 0.433185
v -0.698481 1.447760 -0.050229
v -0.666224 1.018139 -0.189910
v -0.193580 1.404745 -0.340446
v -0.096809 1.232987 -0.351133
v -0.032381 1.555222 -0.028772
v -0.580234 0.867587 0.110741
v -0.354693 1.576729 -0.200765
v -0.558758 1.523036 0.282650
v 0.075085 1.437006 0.089200
v -0.397559 1.480021 0.400874
v -0.053943 0.867587 0.153655
f 91 80 128
f 70 74 76
f 67 66 82
f 74 70 86
f 81 68 90
f 68 85 90
f 78 87 93
f 82 66 96
f 76 74 97
f 96 76 97
f 90 85 98
f 72 89 99
f 68 81 100
f 81 65 100
f 73 91 102
f 91 70 102
f 80 91 103
f 103 91 104
f 91 73 104
f 92 77 104
f 77 103 104
f 88 69 105
f 77 92 106
f 69 88 107
f 88 72 107
f 72 94 107
f 75 101 107
f 101 69 107
f 95 76 108
f 79 95 108
f 96 66 108
f 76 96 108
f 87 73 109
f 79 93 109
f 93 87 109
f 73 102 109
f 102 79 109
f 83 90 110
f 98 71 110
f 90 98 110
f 74 86 111
f 86 81 111
f 81 90 111
f 90 74 111
f 82 96 112
f 71 98 112
f 99 82 112
f 65 81 113
f 86 80 113
f 81 86 113
f 80 103 113
f 92 69 114
f 101 75 114
f 69 101 114
f 84 106 114
f 106 92 114
f 70 76 115
f 76 95 115
f 95 79 115
f 79 102 115
f 102 70 115
f 67 82 116
f 82 99 116
f 99 89 116
f 100 65 117
f 84 100 117
f 103 77 117
f 77 106 117
f 106 84 117
f 65 113 117
f 113 103 117
f 85 94 118
f 94 72 118
f 98 85 118
f 72 99 118
f 112 98 118
f 99 112 118
f 97 83 119
f 96 97 119
f 110 71 119
f 83 110 119
f 112 96 119
f 71 112 119
f 89 78 120
f 78 93 120
f 67 116 120
f 116 89 120
f 66 67 121
f 93 79 121
f 108 66 121
f 79 108 121
f 67 120 121
f 120 93 121
f 87 78 122
f 69 92 122
f 105 69 122
f 78 105 122
f 74 90 123
f 90 83 123
f 97 74 123
f 83 97 123
f 72 88 124
f 78 89 124
f 89 72 124
f 105 78 124
f 88 105 124
f 68 75 125
f 85 68 125
f 94 85 125
f 75 107 125
f 107 94 125
f 73 87 126
f 104 73 126
f 92 104 126
f 87 122 126
f 122 92 126
f 75 68 127
f 68 100 127
f 100 84 127
f 114 75 127
f 84 114 127
f 86 70 128
f 80 86 128
f 70 91 128
o convex_2
v -0.881191 1.372585 0.314915
v -0.752297 1.157735 -0.093320
v -0.741541 1.157735 -0.093320
v -0.741541 1.157735 0.357909
v -0.945660 1.243704 0.078656
v -0.741541 1.340341 0.046399
v -0.956394 1.361845 0.100130
v -0.891925 1.275925 0.347218
v -0.741541 1.361845 0.185979
v -0.870435 1.168500 0.035662
v -0.945660 1.404830 0.228973
v -0.741541 1.211460 0.379476
v -0.806010 1.179240 0.357909
v -0.752297 1.232964 -0.082537
v -0.945660 1.254444 0.035662
v -0.967172 1.351105 0.228973
v -0.838256 1.157735 -0.039589
v -0.902681 1.404830 0.207499
v -0.902681 1.351105 0.336481
v -0.827500 1.329601 0.336481
v -0.848990 1.222224 0.368692
v -0.741541 1.318861 0.003405
v -0.924170 1.394066 0.153815
v -0.827500 1.179240 -0.061063
v -0.967172 1.318861 0.078656
v -0.848990 1.297381 0.368692
v -0.773787 1.157735 0.336481
v -0.945660 1.297381 0.046399
v -0.741541 1.243704 0.357909
v -0.967172 1.383326 0.228973
v -0.956394 1.265185 0.100130
v -0.881191 1.394066 0.261230
v -0.741541 1.361845 0.132341
f 146 137 161
f 130 131 132
f 132 131 134
f 132 134 137
f 132 137 140
f 133 138 141
f 132 140 141
f 131 130 142
f 138 133 143
f 130 132 145
f 138 143 145
f 129 139 147
f 144 136 147
f 137 129 148
f 133 141 149
f 141 140 149
f 134 131 150
f 131 142 150
f 142 135 150
f 135 139 151
f 146 134 151
f 139 146 151
f 134 150 151
f 150 135 151
f 142 130 152
f 130 145 152
f 145 143 152
f 129 147 154
f 147 136 154
f 148 129 154
f 136 149 154
f 149 140 154
f 132 141 155
f 141 138 155
f 145 132 155
f 138 145 155
f 135 142 156
f 142 152 156
f 152 143 156
f 153 135 156
f 143 153 156
f 140 137 157
f 137 148 157
f 148 154 157
f 154 140 157
f 139 135 158
f 147 139 158
f 144 147 158
f 135 153 158
f 153 144 158
f 143 133 159
f 136 144 159
f 133 149 159
f 149 136 159
f 153 143 159
f 144 153 159
f 129 137 160
f 139 129 160
f 137 146 160
f 146 139 160
f 137 134 161
f 134 146 161
o convex_3
v 0.343788 0.867587 0.153823
v 0.623140 0.878339 0.057098
v 0.623140 0.867587 0.057098
v 0.429760 0.878339 -0.168537
v 0.483464 0.953541 0.046370
v 0.515649 0.878339 0.261277
v 0.547888 0.867587 -0.147038
v 0.408267 0.921300 -0.093312
v 0.408267 0.921300 0.164552
v 0.558634 0.910564 -0.093312
v 0.558634 0.921300 0.164552
v 0.354535 0.867587 -0.103998
v 0.569381 0.867587 0.229007
v 0.580127 0.921300 0.024913
v 0.494156 0.932044 -0.093312
v 0.376028 0.910564 0.024913
v 0.429760 0.867587 0.250506
v 0.472745 0.932044 0.175280
v 0.537142 0.942788 0.024913
v 0.408267 0.932044 0.024913
v 0.429760 0.889084 0.239778
v 0.515649 0.878339 -0.168537
v 0.590874 0.878339 -0.082541
v 0.343788 0.878339 0.153823
v 0.354535 0.878339 -0.103998
f 185 177 186
f 164 162 168
f 168 162 173
f 165 168 173
f 162 164 174
f 164 163 174
f 163 172 174
f 172 167 174
f 172 163 175
f 169 166 176
f 165 169 176
f 162 174 178
f 174 167 178
f 166 170 179
f 167 172 179
f 172 166 179
f 166 172 180
f 175 171 180
f 172 175 180
f 176 166 180
f 171 176 180
f 166 169 181
f 170 166 181
f 169 177 181
f 177 170 181
f 178 167 182
f 179 170 182
f 167 179 182
f 168 165 183
f 171 168 183
f 165 176 183
f 176 171 183
f 163 164 184
f 164 168 184
f 168 171 184
f 175 163 184
f 171 175 184
f 173 162 185
f 170 177 185
f 162 178 185
f 182 170 185
f 178 182 185
f 169 165 186
f 165 173 186
f 177 169 186
f 173 185 186
o convex_4
v -0.924164 1.082508 0.121620
v -0.741519 1.136206 0.357985
v -0.752291 1.136206 0.357985
v -0.741519 1.157711 -0.082575
v -0.741519 1.061012 0.089363
v -0.881191 1.157711 0.089363
v -0.902678 1.061012 0.250519
v -0.902678 1.125462 0.261257
v -0.816750 1.114719 -0.050317
v -0.752291 1.157711 0.336466
v -0.741519 1.071765 0.271952
v -0.902678 1.146949 0.057149
v -0.773777 1.082508 -0.018060
v -0.902678 1.061012 0.143009
v -0.795264 1.093251 0.336466
v -0.827503 1.146949 0.325728
v -0.924164 1.136206 0.164529
v -0.806017 1.157711 -0.071793
v -0.741519 1.093251 -0.039580
v -0.870438 1.103995 0.304252
v -0.934917 1.103995 0.153747
v -0.741519 1.061012 0.207480
f 197 193 208
f 190 188 191
f 189 188 196
f 188 190 196
f 190 192 196
f 191 188 197
f 195 187 198
f 195 199 200
f 193 187 200
f 191 193 200
f 187 195 200
f 199 191 200
f 188 189 201
f 197 188 201
f 193 197 201
f 189 196 202
f 196 192 202
f 192 198 203
f 202 192 203
f 194 202 203
f 192 190 204
f 190 195 204
f 198 192 204
f 195 198 204
f 190 191 205
f 195 190 205
f 191 199 205
f 199 195 205
f 194 193 206
f 201 189 206
f 193 201 206
f 202 194 206
f 189 202 206
f 187 193 207
f 193 194 207
f 198 187 207
f 194 203 207
f 203 198 207
f 193 191 208
f 191 197 208

32
data/duck_vhacd.urdf Normal file
View File

@@ -0,0 +1,32 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<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.02 0.0"/>
<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="duck.obj" scale=".05 .05 .05"/>
</geometry>
<material name="yellow">
<color rgba="1 1 0.4 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="duck_vhacd.obj" scale=".05 .05 .05"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -31,25 +31,175 @@
<collision concave="yes" name="pod_collision"> <collision concave="yes" name="pod_collision">
<pose>0 0 0 1.5707 0 0</pose> <pose>0 0 1.21515 1.5707 0 0</pose>
<geometry> <geometry>
<mesh> <box>
<uri>meshes/pod_lowres.stl</uri> <size>0.875 1.754 0.03</size>
</mesh> </box>
</geometry> </geometry>
<surface>
<friction>
<ode>
<mu>0.8</mu>
<mu2>0.8</mu2>
<fdir1>0.0 0.0 0.0</fdir1>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision> </collision>
<collision concave="yes" name="pod_collision">
<pose>-0.42 0 1.18 1.5707 0 1.5707 </pose>
<geometry>
<box>
<size>0.875 1.754 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0.42 0.42 1.17 1.5707 0 0</pose>
<geometry>
<box>
<size>0.03 2.3 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>-0.42 0.42 1.17 1.5707 0 0</pose>
<geometry>
<box>
<size>0.03 2.3 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>-0.42 -0.42 1.17 1.5707 0 0</pose>
<geometry>
<box>
<size>0.03 2.3 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0.42 -0.42 1.17 1.5707 0 0</pose>
<geometry>
<box>
<size>0.03 2.3 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0.15 0 1.49 1.5707 0 1.5707 </pose>
<geometry>
<box>
<size>0.875 1.32 0.01</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>-0.15 0 1.49 1.5707 0 1.5707 </pose>
<geometry>
<box>
<size>0.875 1.32 0.01</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 .57 1.5707 0 1.5707 </pose>
<geometry>
<box>
<size>0.875 0.45 0.01</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0.42 0 1.18 1.5707 0 1.5707 </pose>
<geometry>
<box>
<size>0.875 1.754 0.03</size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 1.06 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 1.06 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 0.80 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0.43 0.81 0 0 0 </pose>
<geometry>
<box>
<size>0.856 0.018 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 -0.43 0.81 0 0 0 </pose>
<geometry>
<box>
<size>0.856 0.018 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0.43 1.08 0 0 0 </pose>
<geometry>
<box>
<size>0.856 0.018 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 -0.43 1.08 0 0 0 </pose>
<geometry>
<box>
<size>0.856 0.018 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 0.37 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 1.29 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 1.53 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
<collision concave="yes" name="pod_collision">
<pose>0 0 1.78 0 0 0 </pose>
<geometry>
<box>
<size>0.905 0.856 0.028 </size>
</box>
</geometry>
</collision>
</link> </link>
</model> </model>
</sdf> </sdf>

3751
data/lego/lego.obj Normal file

File diff suppressed because it is too large Load Diff

32
data/lego/lego.urdf Normal file
View File

@@ -0,0 +1,32 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="legobrick">
<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.0 0.0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="1.570796 0 0" xyz="-0.016 -0.016 -0.0115"/>
<geometry>
<mesh filename="lego.obj" scale=".1 .1 .1"/>
</geometry>
<material name="yellow">
<color rgba="1 1 0.4 1"/>
</material>
</visual>
<collision>
<origin rpy="1.570796 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.032 0.023 0.032"/>
</geometry>
</collision>
</link>
</robot>

3072
data/lego/lego_vhacd.obj Normal file

File diff suppressed because it is too large Load Diff

View File

@@ -225,7 +225,8 @@ void ConvertURDF2BulletInternal(
{ {
btVector3 color = selectColor2(); btVector4 color = selectColor2();
u2b.getLinkColor(urdfLinkIndex,color);
/* /*
if (visual->material.get()) if (visual->material.get())
{ {
@@ -255,7 +256,7 @@ void ConvertURDF2BulletInternal(
btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape); btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape);
linkRigidBody = body; linkRigidBody = body;
world1->addRigidBody(body, bodyCollisionFilterGroup, bodyCollisionFilterMask); world1->addRigidBody(body);
compoundShape->setUserIndex(graphicsIndex); compoundShape->setUserIndex(graphicsIndex);

View File

@@ -1,6 +1,5 @@
#include "PhysicsServerCommandProcessor.h" #include "PhysicsServerCommandProcessor.h"
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h" #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h" #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
#include "../Importers/ImportURDFDemo/URDF2Bullet.h" #include "../Importers/ImportURDFDemo/URDF2Bullet.h"
@@ -563,7 +562,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
m_data = new PhysicsServerCommandProcessorInternalData(); m_data = new PhysicsServerCommandProcessorInternalData();
createEmptyDynamicsWorld(); createEmptyDynamicsWorld();
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0001; m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100; m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
} }
@@ -604,7 +603,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.05; m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
} }
@@ -1887,6 +1886,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
applyJointDamping(i); applyJointDamping(i);
} }
btScalar deltaTimeScaled = m_data->m_physicsDeltaTime*simTimeScalingFactor; btScalar deltaTimeScaled = m_data->m_physicsDeltaTime*simTimeScalingFactor;
if (m_data->m_numSimulationSubSteps > 0) if (m_data->m_numSimulationSubSteps > 0)
@@ -2820,6 +2822,7 @@ void PhysicsServerCommandProcessor::removePickingConstraint()
m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint); m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint);
delete m_data->m_pickedConstraint; delete m_data->m_pickedConstraint;
m_data->m_pickedConstraint = 0; m_data->m_pickedConstraint = 0;
m_data->m_pickedBody->forceActivationState(ACTIVE_TAG);
m_data->m_pickedBody = 0; m_data->m_pickedBody = 0;
} }
if (m_data->m_pickingMultiBodyPoint2Point) if (m_data->m_pickingMultiBodyPoint2Point)
@@ -2889,11 +2892,12 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
btVector3 shiftPos = spawnDir*spawnDistance; btVector3 shiftPos = spawnDir*spawnDistance;
btVector3 spawnPos = gVRGripperPos + shiftPos; btVector3 spawnPos = gVRGripperPos + shiftPos;
loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("lego/lego.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_sphereId = bodyId; m_data->m_sphereId = bodyId;
InteralBodyData* parentBody = m_data->getHandle(bodyId); InteralBodyData* parentBody = m_data->getHandle(bodyId);
if (parentBody->m_multiBody) if (parentBody->m_multiBody)
{ {
parentBody->m_multiBody->setBaseVel(spawnDir * 3); parentBody->m_multiBody->setBaseVel(spawnDir * 5);
} }
} }
@@ -2942,9 +2946,9 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
loadUrdf("cube.urdf", btVector3(3, -2, 0.5+i), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("cube.urdf", btVector3(3, -2, 0.5+i), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
} }
loadUrdf("sphere2.urdf", btVector3(-5, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("lego/lego.urdf", btVector3(-3, 0, .1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere2.urdf", btVector3(-5, 0, 2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("lego/lego.urdf", btVector3(-3, 0, .2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("lego/lego.urdf", btVector3(-3, 0, .3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("r2d2.urdf", btVector3(2, -2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("r2d2.urdf", btVector3(2, -2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
@@ -2974,6 +2978,13 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
} }
#endif #endif
for (int i = 0; i < 6; i++)
{
loadUrdf("jenga/jenga.urdf", btVector3(-1-0.1*i,-0.5, .07), btQuaternion(btVector3(0,1,0),SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
}
//loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("husky/husky.urdf", btVector3(5, 2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("husky/husky.urdf", btVector3(5, 2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_huskyId = bodyId; m_data->m_huskyId = bodyId;
@@ -2981,7 +2992,12 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
} }
loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true); loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("duck_vhacd.urdf", btVector3(-0.3, 0.6, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("cup/cup_small.urdf", btVector3(-0.3, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("cup/pitcher_small.urdf", btVector3(-0.3, 0.6, 1.15), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10)); m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));

View File

@@ -1181,16 +1181,22 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
} else } else
{ {
gDebugRenderToggle = 0; gDebugRenderToggle = 0;
simTimeScalingFactor *= 0.5;
if (simTimeScalingFactor==0) if (simTimeScalingFactor==0)
{ {
simTimeScalingFactor = 1; simTimeScalingFactor = 1;
} else
{
if (simTimeScalingFactor==1)
{
simTimeScalingFactor = 0.25;
} }
if (simTimeScalingFactor<0.01) else
{ {
simTimeScalingFactor = 0; simTimeScalingFactor = 0;
} }
} }
}
} else } else
{ {

View File

@@ -909,6 +909,11 @@ static PyObject* pybullet_getJointState(PyObject* self, PyObject* args) {
if (size == 2) // get body index and joint index if (size == 2) // get body index and joint index
{ {
if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) { if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) {
int status_type = 0;
b3SharedMemoryCommandHandle cmd_handle;
b3SharedMemoryStatusHandle status_handle;
if (bodyIndex < 0) { if (bodyIndex < 0) {
PyErr_SetString(SpamError, "getJointState failed; invalid bodyIndex"); PyErr_SetString(SpamError, "getJointState failed; invalid bodyIndex");
return NULL; return NULL;
@@ -918,10 +923,10 @@ static PyObject* pybullet_getJointState(PyObject* self, PyObject* args) {
return NULL; return NULL;
} }
int status_type = 0;
b3SharedMemoryCommandHandle cmd_handle = cmd_handle =
b3RequestActualStateCommandInit(sm, bodyIndex); b3RequestActualStateCommandInit(sm, bodyIndex);
b3SharedMemoryStatusHandle status_handle = status_handle =
b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
status_type = b3GetStatusType(status_handle); status_type = b3GetStatusType(status_handle);
@@ -984,6 +989,10 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args) {
if (PySequence_Size(args) == 2) // body index and link index if (PySequence_Size(args) == 2) // body index and link index
{ {
if (PyArg_ParseTuple(args, "ii", &bodyIndex, &linkIndex)) { if (PyArg_ParseTuple(args, "ii", &bodyIndex, &linkIndex)) {
int status_type = 0;
b3SharedMemoryCommandHandle cmd_handle;
b3SharedMemoryStatusHandle status_handle;
if (bodyIndex < 0) { if (bodyIndex < 0) {
PyErr_SetString(SpamError, "getLinkState failed; invalid bodyIndex"); PyErr_SetString(SpamError, "getLinkState failed; invalid bodyIndex");
return NULL; return NULL;
@@ -993,10 +1002,10 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args) {
return NULL; return NULL;
} }
int status_type = 0;
b3SharedMemoryCommandHandle cmd_handle = cmd_handle =
b3RequestActualStateCommandInit(sm, bodyIndex); b3RequestActualStateCommandInit(sm, bodyIndex);
b3SharedMemoryStatusHandle status_handle = status_handle =
b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
status_type = b3GetStatusType(status_handle); status_type = b3GetStatusType(status_handle);