use explicit size for name, to avoid issue converting/marshalling data to C#

example to call b3VisualShapeInformation from C# and marshall b3VisualShapeData (after loadURDF)
See examples\pybullet\unity3d\examples\NewBehaviourScript.cs
This commit is contained in:
erwincoumans
2017-10-03 18:01:53 -07:00
parent 9577875fe9
commit 1b03871b4d
7 changed files with 79 additions and 89 deletions

View File

@@ -425,13 +425,13 @@ public enum b3JointInfoFlags {
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
public struct b3JointInfo {
/// char*
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
public string m_linkName;
/// char*
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
public string m_jointName;
/// int
@@ -531,13 +531,13 @@ public struct b3UserConstraint {
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
public struct b3BodyInfo {
/// char*
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
public string m_baseName;
/// char*
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
public string m_bodyName;
}
@@ -624,8 +624,7 @@ public struct b3CameraImageData {
public int m_pixelHeight;
/// char*
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
public string m_rgbColorData;
public System.IntPtr m_rgbColorData;
/// float*
public System.IntPtr m_depthValues;
@@ -1444,7 +1443,7 @@ public static extern int b3GetBodyUniqueId(IntPtr physClient, int serialIndex)
///bodyUniqueId: int
///info: b3BodyInfo*
[System.Runtime.InteropServices.DllImportAttribute("pybullet_vs2010_x64_release.dll", EntryPoint="b3GetBodyInfo")]
public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ;
public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ;
/// Return Type: int

View File

@@ -10,29 +10,7 @@ using System;
public class NewBehaviourScript : MonoBehaviour {
[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;
@@ -40,48 +18,76 @@ public class NewBehaviourScript : MonoBehaviour {
// Use this for initialization
void Start () {
text = GetComponent<Text>();
CallMe(IWasCalled);
sharedAPI = CreateSharedAPI(30);
pybullet = NativeMethods.b3ConnectPhysicsDirect();// SharedMemory(12347);
pybullet = NativeMethods.b3ConnectPhysicsDirect();// NativeMethods.b3ConnectSharedMemory(NativeConstants.SHARED_MEMORY_KEY);
IntPtr cmd = NativeMethods.b3InitResetSimulationCommand(pybullet);
IntPtr status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
int numBodies = NativeMethods.b3GetNumBodies(pybullet);
cmd = NativeMethods.b3LoadUrdfCommandInit(pybullet, "plane.urdf");
status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
EnumSharedMemoryServerStatus statusType = (EnumSharedMemoryServerStatus)NativeMethods.b3GetStatusType(status);
if (statusType == EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED)
if (statusType == (EnumSharedMemoryServerStatus)EnumSharedMemoryServerStatus.CMD_URDF_LOADING_COMPLETED)
{
numBodies = NativeMethods.b3GetNumBodies(pybullet);
text.text = numBodies.ToString();
cmd = NativeMethods.b3InitRequestVisualShapeInformation(pybullet, 0);
status = NativeMethods.b3SubmitClientCommandAndWaitStatus(pybullet, cmd);
statusType = (EnumSharedMemoryServerStatus) NativeMethods.b3GetStatusType(status);
if (statusType == (EnumSharedMemoryServerStatus)EnumSharedMemoryServerStatus.CMD_VISUAL_SHAPE_INFO_COMPLETED)
{
b3VisualShapeInformation visuals = new b3VisualShapeInformation();
NativeMethods.b3GetVisualShapeInformation(pybullet, ref visuals);
System.Console.WriteLine("visuals.m_numVisualShapes=" + visuals.m_numVisualShapes);
System.IntPtr visualPtr = visuals.m_visualShapeData;
for (int s = 0; s < visuals.m_numVisualShapes; s++)
{
b3VisualShapeData visual = (b3VisualShapeData)Marshal.PtrToStructure(visualPtr, typeof(b3VisualShapeData));
visualPtr = new IntPtr(visualPtr.ToInt64()+(Marshal.SizeOf(typeof(b3VisualShapeData))));
double x = visual.m_dimensions[0];
double y = visual.m_dimensions[1];
double z = visual.m_dimensions[2];
System.Console.WriteLine("visual.m_visualGeometryType = " + visual.m_visualGeometryType);
System.Console.WriteLine("visual.m_dimensions" + x + "," + y + "," + z);
if (visual.m_visualGeometryType == (int)eUrdfGeomTypes.GEOM_MESH)
{
System.Console.WriteLine("visual.m_meshAssetFileName=" + visual.m_meshAssetFileName);
text.text = visual.m_meshAssetFileName;
}
}
}
if (numBodies > 0)
{
//b3BodyInfo info=new b3BodyInfo();
//NativeMethods.b3GetBodyInfo(pybullet, 0, ref info );
//text.text = info.m_baseName;
b3BodyInfo info=new b3BodyInfo();
NativeMethods.b3GetBodyInfo(pybullet, 0, ref info );
text.text = info.m_baseName;
}
}
//IntPtr clientPtr = b3CreateInProcessPhysicsServerAndConnect(0, ref ptr);
}
// Update is called once per frame
void Update () {
//if (pybullet != IntPtr.Zero)
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()
{
NativeMethods.b3DisconnectSharedMemory(pybullet);
if (pybullet != IntPtr.Zero)
{
NativeMethods.b3DisconnectSharedMemory(pybullet);
}
}
}