Allow to load a urdf file in the testplugin.cpp, as first quick test, example pybullet script:
import pybullet as p
p.connect(p.GUI)
pluginUid = p.loadPlugin("E:/develop/bullet3/bin/pybullet_testplugin_vs2010_x64_debug.dll")
commandUid = 0
argument = "plane.urdf"
p.executePluginCommand(pluginUid,commandUid,argument)
p.unloadPlugin(pluginUid)
This commit is contained in:
@@ -1,7 +1,7 @@
|
||||
|
||||
#include "testplugin.h"
|
||||
#include "../../SharedMemoryPublic.h"
|
||||
|
||||
#include "../b3PluginContext.h"
|
||||
#include <stdio.h>
|
||||
|
||||
B3_SHARED_API int initPlugin()
|
||||
@@ -10,10 +10,24 @@ B3_SHARED_API int initPlugin()
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
B3_SHARED_API int executePluginCommand(const char* arguments)
|
||||
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context)
|
||||
{
|
||||
printf("arguments:%s\n",arguments);
|
||||
return 42;
|
||||
printf("arguments:%s\n",context->m_arguments);
|
||||
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType = -1;
|
||||
int bodyUniqueId = -1;
|
||||
|
||||
b3SharedMemoryCommandHandle command =
|
||||
b3LoadUrdfCommandInit(context->m_physClient, context->m_arguments);
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(context->m_physClient, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType == CMD_URDF_LOADING_COMPLETED)
|
||||
{
|
||||
bodyUniqueId = b3GetStatusBodyIndex(statusHandle);
|
||||
}
|
||||
return bodyUniqueId;
|
||||
}
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user