Skip to content

Commit

Permalink
improve premake4 build in case X11 headers are missing
Browse files Browse the repository at this point in the history
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);
	}
  • Loading branch information
erwincoumans committed Jul 25, 2020
1 parent 1de2269 commit 1e8f39b
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 17 deletions.
32 changes: 17 additions & 15 deletions build3/findOpenGLGlewGlut.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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 {}
Expand All @@ -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")
Expand All @@ -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

23 changes: 23 additions & 0 deletions examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
13 changes: 12 additions & 1 deletion examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
7 changes: 6 additions & 1 deletion examples/pybullet/examples/video_sync_mp4.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,15 @@
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")

Expand Down

0 comments on commit 1e8f39b

Please sign in to comment.