summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorerwincoumans <erwincoumans@google.com>2020-07-24 18:11:10 -0700
committerGitHub <noreply@github.com>2020-07-24 18:11:10 -0700
commit579115cf9f8c0790e527081fecefcec5735c865e (patch)
tree6e11bef805dc28fbd7321024d264d1827c4e8452
parent1685aae597e152431aa626a1af7ea15075981a1c (diff)
parentf5cdd6e015e59bb39e8bfbcd3a20f4f156581190 (diff)
downloadbullet3-579115cf9f8c0790e527081fecefcec5735c865e.tar.gz
Merge pull request #2953 from erwincoumans/master
improve premake4 build in case X11 headers are missing
-rw-r--r--build3/findOpenGLGlewGlut.lua18
-rw-r--r--examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp23
-rw-r--r--examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h13
-rw-r--r--examples/pybullet/examples/video_sync_mp4.py7
4 files changed, 58 insertions, 3 deletions
diff --git a/build3/findOpenGLGlewGlut.lua b/build3/findOpenGLGlewGlut.lua
index bf8866dec..0a3eb4e59 100644
--- a/build3/findOpenGLGlewGlut.lua
+++ b/build3/findOpenGLGlewGlut.lua
@@ -43,6 +43,21 @@
configuration{}
end
+ function initX11()
+ if os.is("Linux") then
+ if _OPTIONS["enable_system_x11"] and (os.isdir("/usr/include") and os.isfile("/usr/include/X11/X.h")) then
+ links{"X11","pthread"}
+ else
+ print("No X11/X.h found, using dynamic loading of X11")
+ includedirs {
+ projectRootDir .. "examples/ThirdPartyLibs/optionalX11"
+ }
+ defines {"DYNAMIC_LOAD_X11_FUNCTIONS"}
+ links {"dl","pthread"}
+ end
+ end
+ end
+
function initX11()
if os.is("Linux") then
@@ -79,7 +94,7 @@
if os.is("Linux") then
configuration{"Linux"}
- initX11()
+ initX11()
if _OPTIONS["enable_system_glx"] then --# and (os.isdir("/usr/include") and os.isfile("/usr/include/GL/glx.h")) then
links{"pthread"}
print("Using system GL/glx.h")
@@ -103,3 +118,4 @@
configuration{}
end
+
diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
index e7de912e6..f2777e129 100644
--- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
+++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
@@ -2309,6 +2309,29 @@ int b3RobotSimulatorClientAPI_NoDirect::createCollisionShape(int shapeType, stru
scalarToDouble3(args.m_meshScale, meshScale);
shapeIndex = b3CreateCollisionShapeAddMesh(command, args.m_fileName, meshScale);
}
+ if (shapeType == GEOM_HEIGHTFIELD)
+ {
+ double meshScale[3];
+ scalarToDouble3(args.m_meshScale, meshScale);
+ if (args.m_fileName)
+ {
+ shapeIndex = b3CreateCollisionShapeAddHeightfield(command, args.m_fileName, meshScale, args.m_heightfieldTextureScaling);
+ }
+ else
+ {
+ if (args.m_heightfieldData.size() && args.m_numHeightfieldRows>0 && args.m_numHeightfieldColumns>0)
+ {
+ shapeIndex = b3CreateCollisionShapeAddHeightfield2(sm, command, meshScale, args.m_heightfieldTextureScaling,
+ &args.m_heightfieldData[0],
+ args.m_numHeightfieldRows,
+ args.m_numHeightfieldColumns,
+ args.m_replaceHeightfieldIndex);
+ }
+ }
+
+
+ }
+
if (shapeType == GEOM_PLANE)
{
double planeConstant = 0;
diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
index 5de719669..5c8f9e2ff 100644
--- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
+++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
@@ -471,12 +471,23 @@ struct b3RobotSimulatorCreateCollisionShapeArgs
btVector3 m_meshScale;
btVector3 m_planeNormal;
int m_flags;
+
+ double m_heightfieldTextureScaling;
+ btAlignedObjectArray<float> m_heightfieldData;
+ int m_numHeightfieldRows;
+ int m_numHeightfieldColumns;
+ int m_replaceHeightfieldIndex;
+
b3RobotSimulatorCreateCollisionShapeArgs()
: m_shapeType(-1),
m_radius(0.5),
m_height(1),
m_fileName(NULL),
- m_flags(0)
+ m_flags(0),
+ m_heightfieldTextureScaling(1),
+ m_numHeightfieldRows(0),
+ m_numHeightfieldColumns(0),
+ m_replaceHeightfieldIndex(-1)
{
m_halfExtents.m_floats[0] = 1;
m_halfExtents.m_floats[1] = 1;
diff --git a/examples/pybullet/examples/video_sync_mp4.py b/examples/pybullet/examples/video_sync_mp4.py
index 3859de538..754101744 100644
--- a/examples/pybullet/examples/video_sync_mp4.py
+++ b/examples/pybullet/examples/video_sync_mp4.py
@@ -2,10 +2,15 @@ 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="--mp4=\"test.mp4\" --mp4fps=240")
+p.connect(p.GUI, options="--width=1920 --height=1080 --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")