Update pybullet autogenerated C# bindings, with very basic example script that runs inside Unity 3D

This commit is contained in:
erwincoumans
2017-09-29 07:47:31 -07:00
parent 4dca5b3ef5
commit dd2c7af2b2
3 changed files with 701 additions and 551 deletions

View File

@@ -70,7 +70,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_0.stl"/> <mesh filename="meshes/link_0.obj"/>
</geometry> </geometry>
<material name="Grey"/> <material name="Grey"/>
</visual> </visual>
@@ -99,7 +99,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_1.stl"/> <mesh filename="meshes/link_1.obj"/>
</geometry> </geometry>
<material name="Blue"/> <material name="Blue"/>
</visual> </visual>
@@ -128,7 +128,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_2.stl"/> <mesh filename="meshes/link_2.obj"/>
</geometry> </geometry>
<material name="Blue"/> <material name="Blue"/>
</visual> </visual>
@@ -157,7 +157,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_3.stl"/> <mesh filename="meshes/link_3.obj"/>
</geometry> </geometry>
<material name="Orange"/> <material name="Orange"/>
</visual> </visual>
@@ -186,7 +186,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_4.stl"/> <mesh filename="meshes/link_4.obj"/>
</geometry> </geometry>
<material name="Blue"/> <material name="Blue"/>
</visual> </visual>
@@ -215,7 +215,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_5.stl"/> <mesh filename="meshes/link_5.obj"/>
</geometry> </geometry>
<material name="Blue"/> <material name="Blue"/>
</visual> </visual>
@@ -244,7 +244,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_6.stl"/> <mesh filename="meshes/link_6.obj"/>
</geometry> </geometry>
<material name="Orange"/> <material name="Orange"/>
</visual> </visual>
@@ -273,7 +273,7 @@
<visual> <visual>
<origin rpy="0 0 0" xyz="0 0 0"/> <origin rpy="0 0 0" xyz="0 0 0"/>
<geometry> <geometry>
<mesh filename="meshes/link_7.stl"/> <mesh filename="meshes/link_7.obj"/>
</geometry> </geometry>
<material name="Grey"/> <material name="Grey"/>
</visual> </visual>

File diff suppressed because it is too large Load Diff

View File

@@ -10,25 +10,8 @@ using System;
public class NewBehaviourScript : MonoBehaviour { public class NewBehaviourScript : MonoBehaviour {
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3ConnectSharedMemory")]
public static extern System.IntPtr b3ConnectSharedMemory(int key);
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3CreateInProcessPhysicsServerAndConnect")]
public static extern System.IntPtr b3CreateInProcessPhysicsServerAndConnect(int argc, ref System.IntPtr argv);
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitStepSimulationCommand")]
public static extern System.IntPtr b3InitStepSimulationCommand(IntPtr physClient);
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3LoadUrdfCommandInit")]
public static extern System.IntPtr b3LoadUrdfCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string urdfFileName);
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3InitResetSimulationCommand")]
public static extern System.IntPtr b3InitResetSimulationCommand(IntPtr physClient);
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint = "b3SubmitClientCommandAndWaitStatus")]
public static extern System.IntPtr b3SubmitClientCommandAndWaitStatus(IntPtr physClient, IntPtr commandHandle);
[DllImport("TestCppPlug.dll")] [DllImport("TestCppPlug.dll")]
static extern int Add(int a, int b); static extern int Add(int a, int b);
@@ -60,27 +43,45 @@ public class NewBehaviourScript : MonoBehaviour {
CallMe(IWasCalled); CallMe(IWasCalled);
sharedAPI = CreateSharedAPI(30); sharedAPI = CreateSharedAPI(30);
IntPtr pybullet = b3ConnectSharedMemory(12347); pybullet = NativeMethods.b3ConnectPhysicsDirect();// SharedMemory(12347);
IntPtr cmd = b3InitResetSimulationCommand(pybullet); IntPtr cmd = NativeMethods.b3InitResetSimulationCommand(pybullet);
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf"); int numBodies = NativeMethods.b3GetNumBodies(pybullet);
status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd); cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf");
status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
EnumSharedMemoryServerStatus statusType = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status);
if (statusType == EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED)
{
numBodies = NativeMethods.b3GetNumBodies(pybullet);
text.text = numBodies.ToString();
if (numBodies > 0)
{
//b3BodyInfo info=new b3BodyInfo();
//NativeMethods.b3GetBodyInfo(pybullet, 0, ref info );
//text.text = info.m_baseName;
}
}
//IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr); //IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr);
} }
// Update is called once per frame
void Update () {
IntPtr cmd = b3InitStepSimulationCommand(pybullet);
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
//System.IO.Directory.GetCurrentDirectory().ToString();// // Update is called once per frame
//text.text = Add(4, 5).ToString(); void Update () {
text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString(); //if (pybullet != IntPtr.Zero)
{
IntPtr cmd = NativeMethods.b3InitStepSimulationCommand(pybullet);
IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
//text.text = System.IO.Directory.GetCurrentDirectory().ToString();
//text.text = Add(4, 5).ToString();
//text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString();
}
} }
void OnDestroy() void OnDestroy()
{ {
NativeMethods.b3DisconnectSharedMemory(pybullet);
DeleteSharedAPI(sharedAPI);
} }
} }