PyBullet / BulletRobotics: prepare for pdControlPlugin and collisionFilterPlugin
Split examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.* and move to examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp and examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
This commit is contained in:
@@ -1,7 +1,7 @@
|
||||
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_tinyRendererPlugin_vs2010_x64_debug.dll","_tinyRendererPlugin")
|
||||
plugin = p.loadPlugin("d:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll","_testPlugin")
|
||||
print("plugin=",plugin)
|
||||
p.loadURDF("r2d2.urdf")
|
||||
|
||||
|
||||
10
examples/pybullet/examples/testPlugin.py
Normal file
10
examples/pybullet/examples/testPlugin.py
Normal file
@@ -0,0 +1,10 @@
|
||||
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
plugin = p.loadPlugin("D:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll","_testPlugin")
|
||||
print("plugin=",plugin)
|
||||
p.executePluginCommand(plugin ,"r2d2.urdf", [1,2,3],[50.0,3.3])
|
||||
|
||||
while (1):
|
||||
p.getCameraImage(320,200)
|
||||
p.stepSimulation()
|
||||
Reference in New Issue
Block a user