Quick first prototype/test to integrate pybullet into Unity,
see readme.txt for details.
This commit is contained in:
3113
examples/pybullet/unity3d/autogen/NativeMethods.cs
Normal file
3113
examples/pybullet/unity3d/autogen/NativeMethods.cs
Normal file
File diff suppressed because it is too large
Load Diff
86
examples/pybullet/unity3d/examples/NewBehaviourScript.cs
Normal file
86
examples/pybullet/unity3d/examples/NewBehaviourScript.cs
Normal file
@@ -0,0 +1,86 @@
|
||||
using System.Collections;
|
||||
using System.Collections.Generic;
|
||||
using UnityEngine;
|
||||
using UnityEngine.UI;
|
||||
using System.Runtime.InteropServices;
|
||||
using System;
|
||||
|
||||
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
|
||||
|
||||
|
||||
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")]
|
||||
static extern int Add(int a, int b);
|
||||
|
||||
[DllImport("TestCppPlug.dll")]
|
||||
static extern int CallMe(Action<int> action);
|
||||
|
||||
[DllImport("TestCppPlug.dll")]
|
||||
static extern IntPtr CreateSharedAPI(int id);
|
||||
|
||||
[DllImport("TestCppPlug.dll")]
|
||||
static extern int GetMyIdPlusTen(IntPtr api);
|
||||
|
||||
[DllImport("TestCppPlug.dll")]
|
||||
static extern void DeleteSharedAPI(IntPtr api);
|
||||
|
||||
private void IWasCalled(int value)
|
||||
{
|
||||
text.text = value.ToString();
|
||||
}
|
||||
|
||||
Text text;
|
||||
IntPtr sharedAPI;
|
||||
IntPtr pybullet;
|
||||
|
||||
// Use this for initialization
|
||||
void Start () {
|
||||
text = GetComponent<Text>();
|
||||
CallMe(IWasCalled);
|
||||
sharedAPI = CreateSharedAPI(30);
|
||||
|
||||
IntPtr pybullet = b3ConnectSharedMemory(12347);
|
||||
IntPtr cmd = b3InitResetSimulationCommand(pybullet);
|
||||
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||
cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf");
|
||||
status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||
//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();//
|
||||
//text.text = Add(4, 5).ToString();
|
||||
text.text = UnityEngine.Random.Range(0f, 1f).ToString();// GetMyIdPlusTen(sharedAPI).ToString();
|
||||
}
|
||||
|
||||
void OnDestroy()
|
||||
{
|
||||
|
||||
DeleteSharedAPI(sharedAPI);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,12 @@
|
||||
fileFormatVersion: 2
|
||||
guid: 6197b3a0389e92c47b7d8698e5f61f06
|
||||
timeCreated: 1505961790
|
||||
licenseType: Free
|
||||
MonoImporter:
|
||||
serializedVersion: 2
|
||||
defaultReferences: []
|
||||
executionOrder: 0
|
||||
icon: {instanceID: 0}
|
||||
userData:
|
||||
assetBundleName:
|
||||
assetBundleVariant:
|
||||
33
examples/pybullet/unity3d/readme.txt
Normal file
33
examples/pybullet/unity3d/readme.txt
Normal file
@@ -0,0 +1,33 @@
|
||||
Quick prototype to connect Unity 3D to pybullet
|
||||
|
||||
Generate C# Native Methods using the Microsoft PInvoke Signature Toolkit:
|
||||
|
||||
sigimp.exe /lang:cs e:\develop\bullet3\examples\SharedMemory\PhysicsClientC_API.h
|
||||
|
||||
Add some #define B3_SHARED_API __declspec(dllexport) to the exported methods,
|
||||
replace [3], [4], [16] by [] to get sigimp.exe working.
|
||||
|
||||
This generates autogen/NativeMethods.cs
|
||||
|
||||
Then put pybullet.dll in the right location, so Unity finds it.
|
||||
|
||||
NewBehaviourScript.cs is a 1 evening prototype that works within Unity 3D:
|
||||
Create a connection to pybullet, reset the world, load a urdf at startup.
|
||||
Step the simulation each Update.
|
||||
|
||||
Now the real work can start, converting Unity objects to pybullet,
|
||||
pybullet robots to Unity, synchronizing the transforms each Update.
|
||||
|
||||
void Start () {
|
||||
IntPtr pybullet = b3ConnectSharedMemory(12347);
|
||||
IntPtr cmd = b3InitResetSimulationCommand(pybullet);
|
||||
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||
cmd = b3LoadUrdfCommandInit(pybullet, "plane.urdf");
|
||||
status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||
}
|
||||
|
||||
void Update ()
|
||||
{
|
||||
IntPtr cmd = b3InitStepSimulationCommand(pybullet);
|
||||
IntPtr status = b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
|
||||
}
|
||||
Reference in New Issue
Block a user