Merge pull request #1405 from erwincoumans/master

vr kitchen upgrade with marble countertop,  premake4 add option --enable_static_vr_plugin etc
This commit is contained in:
erwincoumans 2017-10-25 18:33:27 +00:00 committed by GitHub
commit c208505800
49 changed files with 2938 additions and 229 deletions

View File

@ -45,6 +45,13 @@
description = "Try to link and use system X11 headers instead of dynamically loading X11 (dlopen is default)"
}
newoption
{
trigger = "enable_static_vr_plugin",
description = "Statically link vr plugin (in examples/SharedMemory/plugins/vrSyncPlugin)"
}
newoption
{
trigger = "noopengl3",
@ -276,6 +283,11 @@ end
if not _OPTIONS["glfw_lib_name"] then
_OPTIONS["glfw_lib_name"] = default_glfw_lib_name
end
if (_OPTIONS["enable_static_vr_plugin"]) then
defines("STATIC_LINK_VR_PLUGIN")
end
newoption
{
trigger = "glfw_include_dir",

View File

@ -17,7 +17,8 @@ del tmp1234.txt
cd build3
premake4 --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
premake4 --double --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
#premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010

View File

@ -4135,123 +4135,7 @@
</visual>
</link>
</model>
<model name='part106.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>
<link name='link_d106'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_106'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part106.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part106.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.600000 0.894100 0.600000 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part107.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>
<link name='link_d107'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_107'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part107.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part107.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.690200 0.102000 0.102000 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part108.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>
<link name='link_d108'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_108'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part108.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part108.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>0.600000 0.894100 0.600000 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part109.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>

Binary file not shown.

After

Width:  |  Height:  |  Size: 159 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 131 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 335 KiB

View File

@ -9,7 +9,8 @@ newmtl wire_028089177
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.1098 0.3490 0.6941
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_214229166
Ns 32
@ -19,7 +20,8 @@ newmtl wire_214229166
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.8392 0.8980 0.6510
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl Rubi
Ns 10.0000
@ -54,6 +56,7 @@ newmtl wire_115115115
Ka 0.0000 0.0000 0.0000
Kd 0.4510 0.4510 0.4510
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_087224198
Ns 32
@ -63,7 +66,8 @@ newmtl wire_087224198
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.3412 0.8784 0.7765
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_086086086
Ns 32
@ -73,7 +77,8 @@ newmtl wire_086086086
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.3373 0.3373 0.3373
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_026177088
Ns 32
@ -83,7 +88,8 @@ newmtl wire_026177088
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.1020 0.6941 0.3451
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_000000000
Ns 32
@ -93,7 +99,8 @@ newmtl wire_000000000
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.0000 0.0000 0.0000
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_153228153
Ns 32
@ -103,7 +110,8 @@ newmtl wire_153228153
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.6000 0.8941 0.6000
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_176026026
Ns 32
@ -113,7 +121,8 @@ newmtl wire_176026026
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.6902 0.1020 0.1020
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_255255255
Ns 32
@ -123,7 +132,19 @@ newmtl wire_255255255
illum 2
Ka 0.0000 0.0000 0.0000
Kd 1.0000 1.0000 1.0000
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd WoodFine0010_M.jpg
newmtl marble_255255255
Ns 32
d 1
Tr 1
Tf 1 1 1
illum 2
Ka 0.0000 0.0000 0.0000
Kd 1.0000 1.0000 1.0000
Ks 0.3500 0.3500 0.3500
map_Kd Seamless_Aegean_Marble_Texture.jpg
newmtl wire_165000082
Ns 32
@ -133,7 +154,7 @@ newmtl wire_165000082
illum 2
Ka 0.0000 0.0000 0.0000
Kd 1 1 1
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd 48x48copsy.png
newmtl wire_255223127
@ -144,7 +165,8 @@ newmtl wire_255223127
illum 2
Ka 0.0000 0.0000 0.0000
Kd 1.0000 0.8745 0.4980
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl wire_165103082
Ns 32
@ -154,7 +176,8 @@ newmtl wire_165103082
illum 2
Ka 0.0000 0.0000 0.0000
Kd 0.6471 0.4039 0.3216
Ks 0.3500 0.3500 0.3500
Ks 0.3500 0.3500 0.3500
map_Kd Concrete.jpg
newmtl 02___Default
Ns 32.0000

Binary file not shown.

After

Width:  |  Height:  |  Size: 162 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 289 KiB

View File

@ -479,7 +479,7 @@ v 119.729897 158.723099 9.000000
v 150.229904 158.723099 9.000000
v 119.729897 158.723099 8.700000
v 150.229904 158.723099 8.700000
usemtl wire_255255255
usemtl marble_255255255
vn -1.000000 0.000000 0.000000
vn -1.000000 0.000000 0.000000

11
data/marble_cube.mtl Normal file
View File

@ -0,0 +1,11 @@
# Blender MTL File: 'marble_cube.blend'
# 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 tiles.jpg

50
data/marble_cube.obj Normal file
View File

@ -0,0 +1,50 @@
# Blender v2.68 (sub 0) OBJ File: 'marble_cube.blend'
# www.blender.org
mtllib marble_cube.mtl
o Cube
v -1.000000 -1.000000 1.000000
v -1.000000 -1.000000 -1.000000
v 1.000000 -1.000000 -1.000000
v 1.000000 -1.000000 1.000000
v -1.000000 1.000000 1.000000
v -1.000000 1.000000 -1.000000
v 1.000000 1.000000 -1.000000
v 1.000000 1.000000 1.000000
vt 0.900965 0.983117
vt 0.607937 0.967373
vt 0.920037 0.686085
vt 0.327732 0.352741
vt 0.031938 0.342703
vt 0.332102 0.029274
vt 0.618409 0.671643
vt 0.324243 0.658970
vt 0.630389 0.363047
vt 0.919788 0.686473
vt 0.618344 0.672098
vt 0.939406 0.372060
vt 0.039476 0.936128
vt 0.319860 0.951754
vt 0.036647 0.646397
vt 0.642259 0.035851
vt 0.630105 0.363646
vt 0.332098 0.029351
vt 0.617757 0.671237
vt 0.027235 0.021626
vt 0.327768 0.352473
vt 0.630480 0.363422
vt 0.325108 0.659325
vt 0.327845 0.352523
usemtl None
s off
f 5/1 6/2 1/3
f 6/4 7/5 2/6
f 7/7 8/8 3/9
f 8/10 5/11 4/12
f 1/13 2/14 4/15
f 8/16 7/17 5/18
f 6/2 2/19 1/3
f 7/5 3/20 2/6
f 8/8 4/21 3/9
f 5/11 1/22 4/12
f 2/14 3/23 4/15
f 7/17 6/24 5/18

32
data/marble_cube.urdf Normal file
View File

@ -0,0 +1,32 @@
<?xml version="0.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="marble_cube.obj" scale=".5 .5 .5"/>
</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,27 @@
LICENSE:
Copyright (c) 2017, Erwin Coumans
Google Inc.
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are
met:
1. Redistributions or derived work must retain this copyright notice,
this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

27
data/table/license.txt Normal file
View File

@ -0,0 +1,27 @@
LICENSE:
Copyright (c) 2017, Erwin Coumans
Google Inc.
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are
met:
1. Redistributions or derived work must retain this copyright notice,
this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

11
data/table/table2.mtl Normal file
View File

@ -0,0 +1,11 @@
# Blender MTL File: 'table1.blend'
# 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 tabletop.jpg

2050
data/table/table2.obj Normal file

File diff suppressed because it is too large Load Diff

32
data/table/table2.urdf Normal file
View File

@ -0,0 +1,32 @@
<?xml version="0.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="-1.57079632679 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="table2.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>
<cylinder length="0.01" radius="0.5"/>
</geometry>
</collision>
</link>
</robot>

BIN
data/table/tabletop.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.3 MiB

BIN
data/tiles.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.3 MiB

View File

@ -99,7 +99,7 @@ struct GUIHelperInterface
virtual void drawText3D( const char* txt, float posX, float posY, float posZ, float size){}
virtual void drawText3D( const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag){}
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags){return -1;}
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid){return -1;}
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex){return -1;};
virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue){return -1;};
virtual int readUserDebugParameter(int itemUniqueId, double* value) { return 0;}

View File

@ -175,6 +175,11 @@ if (hasCL and findOpenGL3()) then
"../OpenCL/rigidbody/GpuRigidBodyDemo.cpp",
}
end
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Linux") then
initX11()
end

View File

@ -8,14 +8,37 @@
#include "Bullet3Common/b3FileUtils.h"
#include "stb_image/stb_image.h"
#include "../ImportObjDemo/LoadMeshFromObj.h"
#include "Bullet3Common/b3HashMap.h"
struct CachedTextureResult
{
std::string m_textureName;
int m_width;
int m_height;
unsigned char* m_pixels;
CachedTextureResult()
:m_width(0),
m_height(0),
m_pixels(0)
{
}
};
static b3HashMap<b3HashString, CachedTextureResult> gCachedTextureResults;
bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData)
{
B3_PROFILE("loadAndRegisterMeshFromFileInternal");
meshData.m_gfxShape = 0;
meshData.m_textureImage = 0;
meshData.m_textureImage1 = 0;
meshData.m_textureHeight = 0;
meshData.m_textureWidth = 0;
meshData.m_isCached = false;
char relativeFileName[1024];
if (b3ResourcePath::findResourcePath(fileName.c_str(), relativeFileName, 1024))
@ -37,7 +60,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
B3_PROFILE("Load Texture");
//int textureIndex = -1;
//try to load some texture
for (int i = 0; meshData.m_textureImage == 0 && i < shapes.size(); i++)
for (int i = 0; meshData.m_textureImage1 == 0 && i < shapes.size(); i++)
{
const tinyobj::shape_t& shape = shapes[i];
if (shape.material.diffuse_texname.length() > 0)
@ -57,21 +80,51 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
char relativeFileName2[1024];
if (b3ResourcePath::findResourcePath(relativeFileName, relativeFileName2, 1024))
{
image = stbi_load(relativeFileName, &width, &height, &n, 3);
meshData.m_textureImage = image;
if (image)
if (b3IsFileCachingEnabled())
{
meshData.m_textureWidth = width;
meshData.m_textureHeight = height;
}
else
{
b3Warning("Unsupported texture image format [%s]\n", relativeFileName);
meshData.m_textureWidth = 0;
meshData.m_textureHeight = 0;
break;
CachedTextureResult* texture = gCachedTextureResults[relativeFileName];
if (texture)
{
image = texture->m_pixels;
width = texture->m_width;
height = texture->m_height;
meshData.m_textureWidth = width;
meshData.m_textureHeight = height;
meshData.m_textureImage1 = image;
meshData.m_isCached = true;
}
}
if (image==0)
{
image = stbi_load(relativeFileName, &width, &height, &n, 3);
meshData.m_textureImage1 = image;
if (image)
{
meshData.m_textureWidth = width;
meshData.m_textureHeight = height;
if (b3IsFileCachingEnabled())
{
CachedTextureResult result;
result.m_textureName = relativeFileName;
result.m_width = width;
result.m_height = height;
result.m_pixels = image;
meshData.m_isCached = true;
gCachedTextureResults.insert(relativeFileName,result);
}
}
else
{
b3Warning("Unsupported texture image format [%s]\n", relativeFileName);
break;
}
}
}
else
{

View File

@ -7,7 +7,8 @@ struct b3ImportMeshData
{
struct GLInstanceGraphicsShape* m_gfxShape;
unsigned char* m_textureImage;//in 3 component 8-bit RGB data
unsigned char* m_textureImage1;//in 3 component 8-bit RGB data
bool m_isCached;
int m_textureWidth;
int m_textureHeight;
};

View File

@ -65,9 +65,9 @@ int loadAndRegisterMeshFromFile2(const std::string& fileName, CommonRenderInterf
{
int textureIndex = -1;
if (meshData.m_textureImage)
if (meshData.m_textureImage1)
{
textureIndex = renderer->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
textureIndex = renderer->registerTexture(meshData.m_textureImage1,meshData.m_textureWidth,meshData.m_textureHeight);
}
shapeId = renderer->registerShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
@ -77,7 +77,10 @@ int loadAndRegisterMeshFromFile2(const std::string& fileName, CommonRenderInterf
B3_GL_TRIANGLES,
textureIndex);
delete meshData.m_gfxShape;
delete meshData.m_textureImage;
if (!meshData.m_isCached)
{
delete meshData.m_textureImage1;
}
}
return shapeId;
}

View File

@ -878,12 +878,13 @@ void BulletURDFImporter::convertURDFToVisualShapeInternal(const UrdfVisual* visu
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData))
{
if (meshData.m_textureImage)
if (meshData.m_textureImage1)
{
BulletURDFTexture texData;
texData.m_width = meshData.m_textureWidth;
texData.m_height = meshData.m_textureHeight;
texData.textureData = meshData.m_textureImage;
texData.textureData1 = meshData.m_textureImage1;
texData.m_isCached = meshData.m_isCached;
texturesOut.push_back(texData);
}
glmesh = meshData.m_gfxShape;
@ -1137,7 +1138,7 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
if (textures.size())
{
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData1,textures[0].m_width,textures[0].m_height);
}
{
B3_PROFILE("registerGraphicsShape");
@ -1151,7 +1152,10 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP
for (int i=0;i<textures.size();i++)
{
B3_PROFILE("free textureData");
free( textures[i].textureData);
if (!textures[i].m_isCached)
{
free( textures[i].textureData1);
}
}
return graphicsIndex;
}

View File

@ -9,7 +9,8 @@ struct BulletURDFTexture
{
int m_width;
int m_height;
unsigned char* textureData;
unsigned char* textureData1;
bool m_isCached;
};

View File

@ -210,6 +210,7 @@ void SimpleOpenGL2App::setBackgroundColor(float red, float green, float blue)
void SimpleOpenGL2App::drawGrid(DrawGridData data)
{
glEnable(GL_COLOR_MATERIAL);
int gridSize = data.gridSize;
float upOffset = data.upOffset;
int upAxis = data.upAxis;

View File

@ -169,9 +169,9 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
{
int textureIndex = -1;
if (meshData.m_textureImage)
if (meshData.m_textureImage1)
{
textureIndex = m_guiHelper->getRenderInterface()->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
textureIndex = m_guiHelper->getRenderInterface()->registerTexture(meshData.m_textureImage1,meshData.m_textureWidth,meshData.m_textureHeight);
}
shapeId = m_guiHelper->getRenderInterface()->registerShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
@ -205,7 +205,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
ob->registerMeshShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
meshData.m_gfxShape->m_numvertices,
indices,
meshData.m_gfxShape->m_numIndices,color, meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight);
meshData.m_gfxShape->m_numIndices,color, meshData.m_textureImage1,meshData.m_textureWidth,meshData.m_textureHeight);
ob->m_localScaling.setValue(scaling[0],scaling[1],scaling[2]);
@ -214,7 +214,10 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
delete meshData.m_gfxShape;
delete meshData.m_textureImage;
if (!meshData.m_isCached)
{
delete meshData.m_textureImage1;
}
}
}
}

View File

@ -168,7 +168,10 @@ bool TinyVRGui::init()
delete meshData.m_gfxShape;
delete meshData.m_textureImage;
if (!meshData.m_isCached)
{
free(meshData.m_textureImage1);
}
}

View File

@ -197,6 +197,11 @@ if not _OPTIONS["no-enet"] then
"MinitaurSetup.h",
myfiles
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Linux") then
initX11()
end
@ -280,6 +285,11 @@ project ("App_VRGloveHandSimulator")
"b3RobotSimulatorClientAPI.h",
myfiles
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Linux") then
initX11()
end

View File

@ -2632,6 +2632,18 @@ B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle com
}
B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItemUniqueId)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
b3Assert(command->m_updateFlags & USER_DEBUG_HAS_TEXT);
command->m_userDebugDrawArgs.m_replaceItemUniqueId = replaceItemUniqueId;
command->m_updateFlags |= USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID;
}
B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex)
{

View File

@ -175,6 +175,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3Physics
B3_SHARED_API b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[/*3*/], double colorRGB[/*3*/], double textSize, double lifeTime);
B3_SHARED_API void b3UserDebugTextSetOptionFlags(b3SharedMemoryCommandHandle commandHandle, int optionFlags);
B3_SHARED_API void b3UserDebugTextSetOrientation(b3SharedMemoryCommandHandle commandHandle, double orientation[/*4*/]);
B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHandle commandHandle, int replaceItem);
B3_SHARED_API void b3UserDebugItemSetParentObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);

View File

@ -78,7 +78,7 @@ struct PhysicsClientSharedMemoryInternalData {
m_hasLastServerStatus(false),
m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_verboseOutput(false),
m_timeOutInSeconds(30)
m_timeOutInSeconds(1e30)
{}
void processServerStatus();

View File

@ -1,5 +1,4 @@
#include "PhysicsServerCommandProcessor.h"
#include "../CommonInterfaces/CommonRenderInterface.h"
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
@ -4483,7 +4482,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
if (textures.size())
{
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height);
textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData1,textures[0].m_width,textures[0].m_height);
}
int graphicsIndex = -1;
{
@ -8223,27 +8222,35 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
if (clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId>=0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(clientCmd.m_userDebugDrawArgs.m_parentObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
if (bodyHandle)
{
int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex;
if (linkIndex ==-1)
int linkIndex = -1;
if (bodyHandle->m_multiBody)
{
if (bodyHandle->m_multiBody->getBaseCollider())
int linkIndex = clientCmd.m_userDebugDrawArgs.m_parentLinkIndex;
if (linkIndex ==-1)
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
}
} else
{
if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks())
{
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
if (bodyHandle->m_multiBody->getBaseCollider())
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
trackingVisualShapeIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
}
} else
{
if (linkIndex >=0 && linkIndex < bodyHandle->m_multiBody->getNumLinks())
{
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
{
trackingVisualShapeIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
}
}
}
}
if (bodyHandle->m_rigidBody)
{
trackingVisualShapeIndex = bodyHandle->m_rigidBody->getUserIndex();
}
}
}
@ -8329,7 +8336,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
int replaceItemUniqueId = -1;
if ((clientCmd.m_updateFlags & USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID)!=0)
{
replaceItemUniqueId = clientCmd.m_userDebugDrawArgs.m_replaceItemUniqueId;
}
int uid = m_data->m_guiHelper->addUserDebugText3D(clientCmd.m_userDebugDrawArgs.m_text,
@ -8339,7 +8350,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
clientCmd.m_userDebugDrawArgs.m_textSize,
clientCmd.m_userDebugDrawArgs.m_lifeTime,
trackingVisualShapeIndex,
optionFlags);
optionFlags,
replaceItemUniqueId);
if (uid>=0)
{

View File

@ -13,13 +13,14 @@
#include "../Utils/b3Clock.h"
#include "../MultiThreading/b3ThreadSupportInterface.h"
#include "SharedMemoryPublic.h"
//#define BT_ENABLE_VR
#ifdef BT_ENABLE_VR
#include "../RenderingExamples/TinyVRGui.h"
#endif//BT_ENABLE_VR
#include "../CommonInterfaces/CommonParameterInterface.h"
#include "../Importers/ImportURDFDemo/urdfStringSplit.h"
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
bool gEnablePicking=true;
@ -36,9 +37,7 @@ static bool gEnableDefaultKeyboardShortcuts = true;
static bool gEnableDefaultMousePicking = true;
//extern btVector3 gLastPickPos;
btVector3 gVRTeleportPosLocal(0,0,0);
btQuaternion gVRTeleportOrnLocal(0,0,0,1);
btScalar gVRTeleportRotZ = 0;
@ -1132,10 +1131,17 @@ public:
UserDebugText m_tmpText;
int m_resultUserDebugTextUid;
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags)
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid)
{
m_tmpText.m_itemUniqueId = m_uidGenerator++;
if (replaceItemUid>=0)
{
m_tmpText.m_itemUniqueId = replaceItemUid;
} else
{
m_tmpText.m_itemUniqueId = m_uidGenerator++;
}
m_tmpText.m_lifeTime = lifeTime;
m_tmpText.textSize = size;
//int len = strlen(txt);
@ -2171,10 +2177,26 @@ void PhysicsServerExample::updateGraphics()
case eGUIUserDebugAddText:
{
B3_PROFILE("eGUIUserDebugAddText");
bool replaced = false;
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId;
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpText.m_itemUniqueId)
{
m_multiThreadedHelper->m_userDebugText[i] = m_multiThreadedHelper->m_tmpText;
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_tmpText.m_itemUniqueId;
replaced = true;
}
}
if (!replaced)
{
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size()-1].m_itemUniqueId;
}
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIUserDebugAddParameter:
@ -2503,10 +2525,35 @@ void PhysicsServerExample::drawUserDebugLines()
}
{
btAlignedObjectArray<std::string> pieces;
btAlignedObjectArray<std::string> separators;
separators.push_back("\n");
urdfStringSplit(pieces,m_multiThreadedHelper->m_userDebugText[i].m_text,separators);
double sz = m_multiThreadedHelper->m_userDebugText[i].textSize;
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(pos[0],pos[1],pos[2]));
tr.setRotation(btQuaternion(orientation[0],orientation[1],orientation[2],orientation[3]));
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
pos,orientation,colorRGBA,
m_multiThreadedHelper->m_userDebugText[i].textSize,optionFlag);
//float newpos[3]={pos[0]-float(t)*sz,pos[1],pos[2]};
for (int t=0;t<pieces.size();t++)
{
btTransform offset;
offset.setIdentity();
offset.setOrigin(btVector3(0,-float(t)*sz,0));
btTransform result = tr*offset;
float newpos[3] = {result.getOrigin()[0],result.getOrigin()[1],result.getOrigin()[2]};
m_guiHelper->getAppInterface()->drawText3D(pieces[t].c_str(),
newpos,orientation,colorRGBA,
sz,optionFlag);
}
}
/*m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,

View File

@ -691,7 +691,7 @@ enum EnumUserDebugDrawFlags
USER_DEBUG_HAS_OPTION_FLAGS=256,
USER_DEBUG_HAS_TEXT_ORIENTATION = 512,
USER_DEBUG_HAS_PARENT_OBJECT=1024,
USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID=2048,
};
struct UserDebugDrawArgs
@ -712,7 +712,7 @@ struct UserDebugDrawArgs
double m_textColorRGB[3];
double m_textSize;
int m_optionFlags;
int m_replaceItemUniqueId;
double m_rangeMin;
double m_rangeMax;

View File

@ -38,9 +38,10 @@ subject to the following restrictions:
struct MyTexture2
{
unsigned char* textureData;
unsigned char* textureData1;
int m_width;
int m_height;
bool m_isCached;
};
struct TinyRendererObjectArray
@ -308,12 +309,13 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(visual->m_geometry.m_meshFileName, meshData))
{
if (meshData.m_textureImage)
if (meshData.m_textureImage1)
{
MyTexture2 texData;
texData.m_width = meshData.m_textureWidth;
texData.m_height = meshData.m_textureHeight;
texData.textureData = meshData.m_textureImage;
texData.textureData1 = meshData.m_textureImage1;
texData.m_isCached = meshData.m_isCached;
texturesOut.push_back(texData);
}
glmesh = meshData.m_gfxShape;
@ -628,27 +630,32 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
if (vertices.size() && indices.size())
{
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId);
unsigned char* textureImage=0;
unsigned char* textureImage1=0;
int textureWidth=0;
int textureHeight=0;
bool isCached = false;
if (textures.size())
{
textureImage = textures[0].textureData;
textureImage1 = textures[0].textureData1;
textureWidth = textures[0].m_width;
textureHeight = textures[0].m_height;
isCached = textures[0].m_isCached;
}
{
B3_PROFILE("registerMeshShape");
tinyObj->registerMeshShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(), rgbaColor,
textureImage, textureWidth, textureHeight);
textureImage1, textureWidth, textureHeight);
}
visuals->m_renderObjects.push_back(tinyObj);
}
for (int i=0;i<textures.size();i++)
{
free(textures[i].textureData);
if (!textures[i].m_isCached)
{
free(textures[i].textureData1);
}
}
}
}
@ -1090,7 +1097,10 @@ void TinyRendererVisualShapeConverter::resetAll()
for (int i=0;i<m_data->m_textures.size();i++)
{
free(m_data->m_textures[i].textureData);
if (!m_data->m_textures[i].m_isCached)
{
free(m_data->m_textures[i].textureData1);
}
}
m_data->m_textures.clear();
m_data->m_swRenderInstances.clear();
@ -1117,7 +1127,7 @@ void TinyRendererVisualShapeConverter::activateShapeTexture(int objectUniqueId,
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
if ((shapeIndex < 0) || (shapeIndex == v))
{
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
renderObj->m_model->setDiffuseTextureFromData(m_data->m_textures[textureUniqueId].textureData1, m_data->m_textures[textureUniqueId].m_width, m_data->m_textures[textureUniqueId].m_height);
}
}
}
@ -1131,7 +1141,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
MyTexture2 texData;
texData.m_width = width;
texData.m_height = height;
texData.textureData = texels;
texData.textureData1 = texels;
m_data->m_textures.push_back(texData);
return m_data->m_textures.size()-1;
}

View File

@ -104,11 +104,16 @@ myfiles =
}
files {
myfiles,
"main.cpp",
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
files {
"../MultiThreading/b3ThreadSupportInterface.cpp",
@ -202,6 +207,10 @@ files {
"../ExampleBrowser/GL_ShapeDrawer.cpp",
"../ExampleBrowser/CollisionShape2TriangleMesh.cpp",
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Linux") then initX11() end
@ -353,6 +362,10 @@ if os.is("Windows") then
"../ThirdPartyLibs/openvr/samples/shared/pathtools.h",
"../ThirdPartyLibs/openvr/samples/shared/Vectors.h",
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Windows") then
configuration {"x32"}
libdirs {"../ThirdPartyLibs/openvr/lib/win32"}

View File

@ -1,14 +1,27 @@
//#define USE_OPENGL2
#ifdef USE_OPENGL2
#include "OpenGLWindow/SimpleOpenGL2App.h"
typedef SimpleOpenGL2App SimpleOpenGLApp ;
#else
#include "OpenGLWindow/SimpleOpenGL3App.h"
typedef SimpleOpenGL3App SimpleOpenGLApp ;
#endif //USE_OPENGL2
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include "assert.h"
#include <stdio.h>
char* gVideoFileName = 0;
char* gPngFileName = 0;
static char* gVideoFileName = 0;
static char* gPngFileName = 0;
static b3WheelCallback sOldWheelCB = 0;
static b3ResizeCallback sOldResizeCB = 0;
@ -17,15 +30,15 @@ static b3MouseButtonCallback sOldMouseButtonCB = 0;
static b3KeyboardCallback sOldKeyboardCB = 0;
//static b3RenderCallback sOldRenderCB = 0;
float gWidth = 1024;
float gHeight = 768;
static float gWidth = 1024;
static float gHeight = 768;
void MyWheelCallback(float deltax, float deltay)
void MyWheelCallback2(float deltax, float deltay)
{
if (sOldWheelCB)
sOldWheelCB(deltax,deltay);
}
void MyResizeCallback( float width, float height)
void MyResizeCallback2( float width, float height)
{
gWidth = width;
gHeight = height;
@ -33,21 +46,21 @@ void MyResizeCallback( float width, float height)
if (sOldResizeCB)
sOldResizeCB(width,height);
}
void MyMouseMoveCallback( float x, float y)
void MyMouseMoveCallback2( float x, float y)
{
printf("Mouse Move: %f, %f\n", x,y);
if (sOldMouseMoveCB)
sOldMouseMoveCB(x,y);
}
void MyMouseButtonCallback(int button, int state, float x, float y)
void MyMouseButtonCallback2(int button, int state, float x, float y)
{
if (sOldMouseButtonCB)
sOldMouseButtonCB(button,state,x,y);
}
void MyKeyboardCallback(int keycode, int state)
static void MyKeyboardCallback2(int keycode, int state)
{
//keycodes are in examples/CommonInterfaces/CommonWindowInterface.h
//for example B3G_ESCAPE for escape key
@ -65,21 +78,21 @@ int main(int argc, char* argv[])
b3CommandLineArgs myArgs(argc, argv);
SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App", gWidth, gHeight, true);
SimpleOpenGLApp* app = new SimpleOpenGLApp("SimpleOpenGL3App", gWidth, gHeight);
app->m_instancingRenderer->getActiveCamera()->setCameraDistance(13);
app->m_instancingRenderer->getActiveCamera()->setCameraPitch(0);
app->m_instancingRenderer->getActiveCamera()->setCameraTargetPosition(0, 0, 0);
app->m_renderer->getActiveCamera()->setCameraDistance(13);
app->m_renderer->getActiveCamera()->setCameraPitch(0);
app->m_renderer->getActiveCamera()->setCameraTargetPosition(0, 0, 0);
sOldKeyboardCB = app->m_window->getKeyboardCallback();
app->m_window->setKeyboardCallback(MyKeyboardCallback);
app->m_window->setKeyboardCallback(MyKeyboardCallback2);
sOldMouseMoveCB = app->m_window->getMouseMoveCallback();
app->m_window->setMouseMoveCallback(MyMouseMoveCallback);
app->m_window->setMouseMoveCallback(MyMouseMoveCallback2);
sOldMouseButtonCB = app->m_window->getMouseButtonCallback();
app->m_window->setMouseButtonCallback(MyMouseButtonCallback);
app->m_window->setMouseButtonCallback(MyMouseButtonCallback2);
sOldWheelCB = app->m_window->getWheelCallback();
app->m_window->setWheelCallback(MyWheelCallback);
app->m_window->setWheelCallback(MyWheelCallback2);
sOldResizeCB = app->m_window->getResizeCallback();
app->m_window->setResizeCallback(MyResizeCallback);
app->m_window->setResizeCallback(MyResizeCallback2);
myArgs.GetCmdLineArgument("mp4_file", gVideoFileName);
@ -134,10 +147,12 @@ int main(int argc, char* argv[])
app->m_primRenderer->drawTexturedRect(100, 200, gWidth / 2 - 50, gHeight / 2 - 50, color, 0, 0, 1, 1, true);
app->m_instancingRenderer->init();
app->m_instancingRenderer->updateCamera();
app->m_renderer->init();
int upAxis = 1;
app->m_renderer->updateCamera(upAxis);
app->m_renderer->renderScene();
app->drawGrid();
char bla[1024];
sprintf(bla, "2d text:%d", frameCount);

View File

@ -73,6 +73,7 @@ void ImGui_ImplBullet_CreateDeviceObjects()
void ImGui_ImplBullet_RenderDrawLists(ImDrawData* draw_data)
{
glEnable(GL_COLOR_MATERIAL);
// Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates)
ImGuiIO& io = ImGui::GetIO();
int fb_width = (int)(io.DisplaySize.x * io.DisplayFramebufferScale.x);
@ -96,7 +97,7 @@ void ImGui_ImplBullet_RenderDrawLists(ImDrawData* draw_data)
glEnableClientState(GL_TEXTURE_COORD_ARRAY);
glEnableClientState(GL_COLOR_ARRAY);
glEnable(GL_TEXTURE_2D);
//glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context
glUseProgram(0); // You may want this if using this code in an OpenGL 3+ context
// Setup viewport, orthographic projection matrix
glViewport(0, 0, (GLsizei)fb_width, (GLsizei)fb_height);

View File

@ -0,0 +1,230 @@
import pybullet as p
import time
#p.connect(p.UDP,"192.168.86.100")
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI)
p.resetSimulation()
meshScale = [.1,.1,.01]
shift = [0,0,0]
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,fileName="marble_cube.obj", rgbaColor=[1,1,1,1], specularColor=[1,1,1], visualFramePosition=shift, meshScale=meshScale)
#collisionShapeId = p.createCollisionShape(shapeType=p.GEOM_MESH, fileName="textures/marble_cube.obj", collisionFramePosition=shift,meshScale=meshScale)
collisionShapeId = -1
uiCube = p.createMultiBody(baseMass=0,baseInertialFramePosition=[0,0,0],baseCollisionShapeIndex=collisionShapeId, baseVisualShapeIndex = visualShapeId, basePosition = [0,1,0], useMaximalCoordinates=True)
textOrn = p.getQuaternionFromEuler([0,0,-1.5707963])
numLines = 1
lines = [-1]*numLines
p.stepSimulation()
#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)]
kitchenObj = p.loadSDF("kitchens/1.sdf")
#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])
p.setJointMotorControl2(pr2_gripper,jointIndex,p.POSITION_CONTROL,targetPosition=0,force=0)
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)
pr2_cid2 = p.createConstraint(pr2_gripper,0,pr2_gripper,2,jointType=p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
p.changeConstraint(pr2_cid2,gearRatio=1, erp=0.5, relativePositionTarget=0.5, maxForce=3)
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])
objects = [p.loadURDF("table/table.urdf", 1.000000,-0.200000,0.000000,0.000000,0.000000,0.707107,0.707107)]
#objects = [p.loadURDF("textures/table2.urdf", 1.000000,-0.200000,0.000000,0.000000,0.000000,0.707107,0.707107)]
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("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)]
#bjects = 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,0,-10)
##show this for 10 seconds
#now = time.time()
#while (time.time() < now+10):
# p.stepSimulation()
p.setRealTimeSimulation(1)
CONTROLLER_ID = 0
POSITION=1
ORIENTATION=2
ANALOG=3
BUTTONS=6
uiControllerId = -1
print("waiting for VR UI controller trigger")
while (uiControllerId<0):
events = p.getVREvents()
for e in (events):
if (e[BUTTONS][33]==p.VR_BUTTON_IS_DOWN):
uiControllerId = e[CONTROLLER_ID]
if (e[BUTTONS][32]==p.VR_BUTTON_IS_DOWN):
uiControllerId = e[CONTROLLER_ID]
print("Using uiControllerId="+str(uiControllerId))
controllerId = -1
print("waiting for VR picking controller trigger")
while (controllerId<0):
events = p.getVREvents()
for e in (events):
if (e[BUTTONS][33]==p.VR_BUTTON_IS_DOWN):
controllerId = e[CONTROLLER_ID]
if (e[BUTTONS][32]==p.VR_BUTTON_IS_DOWN):
controllerId = e[CONTROLLER_ID]
if (controllerId == uiControllerId):
controllerId = -1
print("Using controllerId="+str(controllerId))
once = 1
if (once):
logId = -1#p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "userDebugItems1.json")
print("logId userdebug")
print(logId)
for i in range (numLines):
spacing = 0.01
textPos = [.1-(i+1)*spacing,.1,0.011]
text = "ABCDEFGH\nIJKLMNOPQRSTUVWXYZ\n01234567890abcdefg\n"*10
lines[i] = p.addUserDebugText(text,textColorRGB=[0,0,0], textSize = 0.01, textPosition = textPos,textOrientation = textOrn,parentObjectUniqueId=uiCube, parentLinkIndex = -1)
if (once):
once = 0
if (logId and logId>0):
p.stopStateLogging(logId)
frameNr = 0
objectInfo = ""
pointRay = -1
rayLen = 100
while (1):
frameNr=frameNr+1
for i in range (numLines):
spacing = 0.01
textPos = [.1-(i+1)*spacing,.1,0.011]
text = "Frame:"+str(frameNr)+"\nObject UID:"+objectInfo
textUid = p.addUserDebugText(text,textColorRGB=[0,0,0], textSize = 0.02, textPosition = textPos,textOrientation = textOrn,parentObjectUniqueId=uiCube, parentLinkIndex = -1, replaceItemUniqueId = lines[i])
lines[i] = textUid
#keep the gripper centered/symmetric
b = p.getJointState(pr2_gripper,2)[0]
p.setJointMotorControl2(pr2_gripper, 0, p.POSITION_CONTROL, targetPosition=b, force=3)
events = p.getVREvents()
for e in (events):
if e[CONTROLLER_ID] == uiControllerId:
p.resetBasePositionAndOrientation(uiCube,e[POSITION], e[ORIENTATION])
pos = e[POSITION]
orn = e[ORIENTATION]
lineFrom = pos
mat = p.getMatrixFromQuaternion(orn)
dir = [mat[0],mat[3],mat[6]]
to = [pos[0]+dir[0]*rayLen,pos[1]+dir[1]*rayLen,pos[2]+dir[2]*rayLen]
hit = p.rayTest(lineFrom,to)
oldRay = pointRay
color = [1,1,0]
width = 3
#pointRay = p.addUserDebugLine(lineFrom,to,color,width,lifeTime=1)
#if (oldRay>=0):
# p.removeUserDebugItem(oldRay)
if (hit):
#if (hit[0][0]>=0):
hitObjectUid = hit[0][0]
linkIndex = hit[0][1]
if (hitObjectUid>=0):
objectInfo = str(hitObjectUid)+" Link Index="+str(linkIndex)+"\nBase Name:"+p.getBodyInfo(hitObjectUid)[0].decode()+"\nBody Info:"+p.getBodyInfo(hitObjectUid)[1].decode()
else:
objectInfo="None"
if e[CONTROLLER_ID] == controllerId: # To make sure we only get the value for one of the remotes
#sync the vr pr2 gripper with the vr controller position
p.changeConstraint(pr2_cid, e[POSITION], e[ORIENTATION], maxForce=500)
relPosTarget = 1 - e[ANALOG]
#open/close the gripper, based on analogue
p.changeConstraint(pr2_cid2,gearRatio=1, erp=1, relativePositionTarget=relPosTarget, maxForce=3)

View File

@ -117,8 +117,8 @@ while (controllerId<0):
print("Using controllerId="+str(controllerId))
plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll","_vrSyncPlugin")
#plugin = p.loadPlugin("vrSyncPlugin")
#plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_vrSyncPlugin_vs2010_x64_release.dll","_vrSyncPlugin")
plugin = p.loadPlugin("vrSyncPlugin")
print("PluginId="+str(plugin))
p.executePluginCommand(plugin ,"bla", [controllerId,pr2_cid, pr2_cid2,pr2_gripper],[50,3])

View File

@ -1,3 +1,4 @@
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
from pybullet_envs.bullet.minitaur_gym_env import MinitaurBulletEnv
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv

View File

@ -0,0 +1,101 @@
"""
Classic cart-pole system implemented by Rich Sutton et al.
Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c
"""
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
import logging
import math
import gym
from gym import spaces
from gym.utils import seeding
import numpy as np
import time
import subprocess
import pybullet as p
import pybullet_data
logger = logging.getLogger(__name__)
class CartPoleBulletEnv(gym.Env):
metadata = {
'render.modes': ['human', 'rgb_array'],
'video.frames_per_second' : 50
}
def __init__(self, renders=True):
# start the bullet physics server
self._renders = renders
if (renders):
p.connect(p.GUI)
else:
p.connect(p.DIRECT)
observation_high = np.array([
np.finfo(np.float32).max,
np.finfo(np.float32).max,
np.finfo(np.float32).max,
np.finfo(np.float32).max])
action_high = np.array([0.1])
self.action_space = spaces.Discrete(9)
self.observation_space = spaces.Box(-observation_high, observation_high)
self.theta_threshold_radians = 1
self.x_threshold = 2.4
self._seed()
# self.reset()
self.viewer = None
self._configure()
def _configure(self, display=None):
self.display = display
def _seed(self, seed=None):
self.np_random, seed = seeding.np_random(seed)
return [seed]
def _step(self, action):
p.stepSimulation()
# time.sleep(self.timeStep)
self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2]
theta, theta_dot, x, x_dot = self.state
dv = 0.1
deltav = [-10.*dv,-5.*dv, -2.*dv, -0.1*dv, 0, 0.1*dv, 2.*dv,5.*dv, 10.*dv][action]
p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, targetVelocity=(deltav + self.state[3]))
done = x < -self.x_threshold \
or x > self.x_threshold \
or theta < -self.theta_threshold_radians \
or theta > self.theta_threshold_radians
reward = 1.0
return np.array(self.state), reward, done, {}
def _reset(self):
# print("-----------reset simulation---------------")
p.resetSimulation()
self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0])
self.timeStep = 0.01
p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0)
p.setGravity(0,0, -10)
p.setTimeStep(self.timeStep)
p.setRealTimeSimulation(0)
initialCartPos = self.np_random.uniform(low=-0.5, high=0.5, size=(1,))
initialAngle = self.np_random.uniform(low=-0.5, high=0.5, size=(1,))
p.resetJointState(self.cartpole, 1, initialAngle)
p.resetJointState(self.cartpole, 0, initialCartPos)
self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2]
return np.array(self.state)
def _render(self, mode='human', close=False):
return

View File

@ -155,6 +155,11 @@ if not _OPTIONS["no-enet"] then
"../../examples/MultiThreading/b3Win32ThreadSupport.cpp",
"../../examples/MultiThreading/b3ThreadSupportInterface.cpp",
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
includedirs {
_OPTIONS["python_include_dir"],

View File

@ -3499,11 +3499,12 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj
double lifeTime = 0.f;
int physicsClientId = 0;
int debugItemUniqueId = -1;
int replaceItemUniqueId = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"text", "textPosition", "textColorRGB", "textSize", "lifeTime", "textOrientation", "parentObjectUniqueId", "parentLinkIndex", "physicsClientId", NULL};
static char* kwlist[] = {"text", "textPosition", "textColorRGB", "textSize", "lifeTime", "textOrientation", "parentObjectUniqueId", "parentLinkIndex", "replaceItemUniqueId", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|OddOiii", kwlist, &text, &textPositionObj, &textColorRGBObj, &textSize, &lifeTime, &textOrientationObj, &parentObjectUniqueId, &parentLinkIndex, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "sO|OddOiiii", kwlist, &text, &textPositionObj, &textColorRGBObj, &textSize, &lifeTime, &textOrientationObj, &parentObjectUniqueId, &parentLinkIndex, &replaceItemUniqueId, &physicsClientId))
{
return NULL;
}
@ -3550,6 +3551,11 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj
}
}
if (replaceItemUniqueId>=0)
{
b3UserDebugItemSetReplaceItemUniqueId(commandHandle,replaceItemUniqueId);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);

View File

@ -226,6 +226,10 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../examples/ThirdPartyLibs/stb_image/stb_image.cpp",
}
if (_OPTIONS["enable_static_plugins"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
project ("Test_PhysicsServerDirect")
@ -306,7 +310,9 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../examples/ThirdPartyLibs/stb_image/stb_image.cpp",
}
if (_OPTIONS["enable_static_plugins"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
project ("Test_PhysicsServerInProcessExampleBrowser")
@ -414,6 +420,10 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
"../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../examples/ThirdPartyLibs/stb_image/stb_image.cpp",
}
if (_OPTIONS["enable_static_vr_plugin"]) then
files {"../../examples/SharedMemory/plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if os.is("Linux") then
initX11()
end