summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <erwin.coumans@gmail.com>2020-07-24 18:09:13 -0700
committerErwin Coumans <erwin.coumans@gmail.com>2020-07-24 18:09:13 -0700
commit1e8f39b492b579a78ad9d275c7f46b0d3b298403 (patch)
treeae0031908404231839e9a1c15dd533b95201416c
parent1de2269b6e5da3697a1dcfcfd616c1743e04b4ac (diff)
downloadbullet3-1e8f39b492b579a78ad9d275c7f46b0d3b298403.tar.gz
improve premake4 build in case X11 headers are missing
improve video_sync_mp4.py example allow to create a heightfield from file or programmatically in C++ robotics api. Example: { b3RobotSimulatorCreateCollisionShapeArgs shapeArgs; shapeArgs.m_shapeType = GEOM_HEIGHTFIELD; bool useFile = true; if (useFile) { shapeArgs.m_fileName = "D:/dev/bullet3/data/heightmaps/gimp_overlay_out.png"; shapeArgs.m_meshScale.setValue(.05, .05, 1); } else { shapeArgs.m_numHeightfieldColumns = 256; shapeArgs.m_numHeightfieldRows = 256; shapeArgs.m_meshScale.setValue(.05, .05, 1); shapeArgs.m_heightfieldData.resize(shapeArgs.m_numHeightfieldRows * shapeArgs.m_numHeightfieldColumns); double heightPerturbationRange = 0.05; for (int j = 0; j<int(shapeArgs.m_numHeightfieldColumns / 2); j++) { for (int i = 0; i < (int(shapeArgs.m_numHeightfieldRows / 2)); i++) { double height = ((double)rand() / (RAND_MAX)) * heightPerturbationRange; shapeArgs.m_heightfieldData[2 * i + 2 * j * shapeArgs.m_numHeightfieldRows] = height; shapeArgs.m_heightfieldData[2 * i + 1 + 2 * j * shapeArgs.m_numHeightfieldRows] = height; shapeArgs.m_heightfieldData[2 * i + (2 * j + 1) * shapeArgs.m_numHeightfieldRows] = height; shapeArgs.m_heightfieldData[2 * i + 1 + (2 * j + 1) * shapeArgs.m_numHeightfieldRows] = height; } } } int shape = sim->createCollisionShape(shapeArgs.m_shapeType, shapeArgs); b3RobotSimulatorCreateMultiBodyArgs bodyArgs; bodyArgs.m_baseCollisionShapeIndex = shape; int groundId = sim->createMultiBody(bodyArgs); int texId = sim->loadTexture(shapeArgs.m_fileName); b3RobotSimulatorChangeVisualShapeArgs args; args.m_objectUniqueId = groundId; args.m_linkIndex = -1; args.m_textureUniqueId = texId; sim->changeVisualShape(args); }
-rw-r--r--build3/findOpenGLGlewGlut.lua32
-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, 17 deletions
diff --git a/build3/findOpenGLGlewGlut.lua b/build3/findOpenGLGlewGlut.lua
index 5d53a25d9..189f5f5cd 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 initGlew()
configuration {}
@@ -63,8 +78,9 @@
if os.is("Linux") then
configuration{"Linux"}
+ initX11()
if _OPTIONS["enable_system_glx"] then --# and (os.isdir("/usr/include") and os.isfile("/usr/include/GL/glx.h")) then
- links{"X11","pthread"}
+ links{"pthread"}
print("Using system GL/glx.h")
else
print("Using glad_glx")
@@ -86,18 +102,4 @@
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
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")