mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-05 01:50:05 +00:00
create premake/cmake file for Bullet/Extras/obj2sdf
add missing 1.sdf for Bullet/data/kitchens/1.sdf add support for getting keyboard events (pybullet.getKeyboardEvents and b3RobotSimulatorClientAPI::getKeyboardEvents)
This commit is contained in:
parent
255b21a776
commit
34fc2fb589
@ -1,4 +1,4 @@
|
||||
SUBDIRS( Serialize ConvexDecomposition HACD GIMPACTUtils )
|
||||
SUBDIRS( obj2sdf Serialize ConvexDecomposition HACD GIMPACTUtils )
|
||||
|
||||
IF(BUILD_BULLET3)
|
||||
SUBDIRS( InverseDynamics)
|
||||
|
20
Extras/obj2sdf/CMakeLists.txt
Normal file
20
Extras/obj2sdf/CMakeLists.txt
Normal file
@ -0,0 +1,20 @@
|
||||
|
||||
SET(includes
|
||||
.
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
Bullet3Common
|
||||
)
|
||||
|
||||
INCLUDE_DIRECTORIES(${includes})
|
||||
|
||||
ADD_EXECUTABLE(App_obj2sdf
|
||||
obj2sdf.cpp
|
||||
../../examples/Utils/b3ResourcePath.cpp
|
||||
../../examples/Utils/b3ResourcePath.h
|
||||
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
|
||||
)
|
||||
|
@ -8,19 +8,29 @@
|
||||
#include <stdio.h>
|
||||
#include <assert.h>
|
||||
#define ASSERT_EQ(a,b) assert((a)==(b));
|
||||
#include "MinitaurSetup.h"
|
||||
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
|
||||
#include"Wavefront/tiny_obj_loader.h"
|
||||
#include <vector>
|
||||
#include "Bullet3Common/b3FileUtils.h"
|
||||
#include "../Utils/b3ResourcePath.h"
|
||||
#include "Bullet3Common/b3CommandLineArgs.h"
|
||||
|
||||
#define MAX_PATH_LEN 1024
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
const char* fileName = "kitchens/kitchen.obj";
|
||||
|
||||
|
||||
b3CommandLineArgs args(argc,argv);
|
||||
char* fileName;
|
||||
args.GetCmdLineArgument("fileName",fileName);
|
||||
|
||||
printf("fileName = %s\n", fileName);
|
||||
if (fileName==0)
|
||||
{
|
||||
printf("Please use --fileName=\"pathToObj\".");
|
||||
exit(0);
|
||||
}
|
||||
char fileNameWithPath[MAX_PATH_LEN];
|
||||
bool fileFound = (b3ResourcePath::findResourcePath(fileName,fileNameWithPath,MAX_PATH_LEN))>0;
|
||||
bool fileFound = (b3ResourcePath::findResourcePath(fileName,fileNameWithPath,MAX_PATH_LEN))>0;
|
||||
char materialPrefixPath[MAX_PATH_LEN];
|
||||
b3FileUtils::extractPath(fileNameWithPath,materialPrefixPath,MAX_PATH_LEN);
|
||||
|
||||
@ -32,7 +42,7 @@ int main(int argc, char* argv[])
|
||||
FILE* sdfFile = fopen(sdfFileName,"w");
|
||||
if (sdfFile==0)
|
||||
{
|
||||
printf("Fatal: cannot create sdf file %s\n",sdfFileName);
|
||||
printf("Fatal error: cannot create sdf file %s\n",sdfFileName);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
@ -52,7 +62,7 @@ int main(int argc, char* argv[])
|
||||
FILE* f = fopen(objFileName,"w");
|
||||
if (f==0)
|
||||
{
|
||||
printf("Fatal: cannot create part obj file %s\n",objFileName);
|
||||
printf("Fatal error: cannot create part obj file %s\n",objFileName);
|
||||
exit(0);
|
||||
}
|
||||
fprintf(f,"# Exported using automatic converter by Erwin Coumans\n");
|
||||
@ -81,13 +91,16 @@ int main(int argc, char* argv[])
|
||||
}
|
||||
|
||||
fprintf(f,"\n");
|
||||
for (int vn = 0;vn<shape.mesh.normals.size()/3;vn++)
|
||||
int numNormals = int(shape.mesh.normals.size());
|
||||
|
||||
for (int vn = 0;vn<numNormals/3;vn++)
|
||||
{
|
||||
fprintf(f,"vn %f %f %f\n",shape.mesh.normals[vn*3+0],shape.mesh.normals[vn*3+1],shape.mesh.normals[vn*3+2]);
|
||||
}
|
||||
|
||||
fprintf(f,"\n");
|
||||
for (int vt = 0;vt<shape.mesh.texcoords.size()/2;vt++)
|
||||
int numTexCoords = int(shape.mesh.texcoords.size());
|
||||
for (int vt = 0;vt<numTexCoords/2;vt++)
|
||||
{
|
||||
fprintf(f,"vt %f %f\n",shape.mesh.texcoords[vt*2+0],shape.mesh.texcoords[vt*2+1]);
|
||||
}
|
||||
|
18
Extras/obj2sdf/premake4.lua
Normal file
18
Extras/obj2sdf/premake4.lua
Normal file
@ -0,0 +1,18 @@
|
||||
project ("App_obj2sdf")
|
||||
|
||||
language "C++"
|
||||
kind "ConsoleApp"
|
||||
|
||||
includedirs {"../../src",
|
||||
"../../examples/ThirdPartyLibs"}
|
||||
|
||||
|
||||
links{"Bullet3Common"}
|
||||
|
||||
|
||||
files {
|
||||
"obj2sdf.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.cpp",
|
||||
"../../examples/Utils/b3ResourcePath.h",
|
||||
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
|
||||
}
|
@ -6,4 +6,4 @@ include "InverseDynamics"
|
||||
include "Serialize/BulletFileLoader"
|
||||
include "Serialize/BulletWorldImporter"
|
||||
include "Serialize/BulletXmlWorldImporter"
|
||||
|
||||
include "obj2sdf"
|
||||
|
6783
data/kitchens/1.sdf
Normal file
6783
data/kitchens/1.sdf
Normal file
File diff suppressed because it is too large
Load Diff
@ -181,10 +181,12 @@ void MyKeyboardCallback(int key, int state)
|
||||
|
||||
//b3Printf("key=%d, state=%d", key, state);
|
||||
bool handled = false;
|
||||
|
||||
if (gui2 && !handled )
|
||||
if (renderGui)
|
||||
{
|
||||
handled = gui2->keyboardCallback(key, state);
|
||||
if (gui2 && !handled )
|
||||
{
|
||||
handled = gui2->keyboardCallback(key, state);
|
||||
}
|
||||
}
|
||||
|
||||
if (!handled && sCurrentDemo)
|
||||
|
@ -65,10 +65,15 @@ int getSpecialKeyFromVirtualKeycode(int virtualKeyCode)
|
||||
{
|
||||
return virtualKeyCode+32;//todo: fix the ascii A vs a input
|
||||
}
|
||||
if (virtualKeyCode >= '0' && virtualKeyCode <= '9')
|
||||
{
|
||||
return virtualKeyCode;
|
||||
}
|
||||
|
||||
switch (virtualKeyCode)
|
||||
{
|
||||
case VK_RETURN: {keycode = B3G_RETURN; break; };
|
||||
case VK_ESCAPE: {keycode = B3G_ESCAPE; break; };
|
||||
case VK_F1: {keycode = B3G_F1; break;}
|
||||
case VK_F2: {keycode = B3G_F2; break;}
|
||||
case VK_F3: {keycode = B3G_F3; break;}
|
||||
@ -217,6 +222,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam)
|
||||
}
|
||||
case WM_CHAR:
|
||||
{
|
||||
#if 0
|
||||
//skip 'enter' key, it is processed in WM_KEYUP/WM_KEYDOWN
|
||||
int keycode = getAsciiCodeFromVirtualKeycode(wParam);
|
||||
if (keycode < 0)
|
||||
@ -227,6 +233,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam)
|
||||
(*sData->m_keyboardCallback)(wParam, state);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
case WM_SYSKEYDOWN:
|
||||
|
@ -49,17 +49,33 @@ int main(int argc, char* argv[])
|
||||
sim->stepSimulation();
|
||||
}
|
||||
#endif
|
||||
sim->setRealTimeSimulation(true);
|
||||
sim->setRealTimeSimulation(false);
|
||||
|
||||
startTime = clock.getTimeInSeconds();
|
||||
while (clock.getTimeInSeconds()-startTime < simWallClockSeconds)
|
||||
while (sim->canSubmitCommand())
|
||||
{
|
||||
b3Clock::usleep(1000);
|
||||
b3KeyboardEventsData keyEvents;
|
||||
sim->getKeyboardEvents(&keyEvents);
|
||||
if (keyEvents.m_numKeyboardEvents)
|
||||
{
|
||||
|
||||
printf("num key events = %d]\n", keyEvents.m_numKeyboardEvents);
|
||||
//m_keyState is a flag combination of eButtonIsDown,eButtonTriggered, eButtonReleased
|
||||
for (int i=0;i<keyEvents.m_numKeyboardEvents;i++)
|
||||
{
|
||||
printf("keyEvent[%d].m_keyCode = %d, state = %d\n", i,keyEvents.m_keyboardEvents[i].m_keyCode,keyEvents.m_keyboardEvents[i].m_keyState);
|
||||
}
|
||||
}
|
||||
b3Clock::usleep(1000*1000);
|
||||
}
|
||||
|
||||
printf("sim->disconnect\n");
|
||||
|
||||
sim->disconnect();
|
||||
|
||||
printf("delete sim\n");
|
||||
delete sim;
|
||||
|
||||
printf("exit\n");
|
||||
|
||||
}
|
||||
|
||||
|
@ -177,7 +177,16 @@ void b3RobotSimulatorClientAPI::resetSimulation()
|
||||
}
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(
|
||||
m_data->m_physicsClientHandle, b3InitResetSimulationCommand(m_data->m_physicsClientHandle));
|
||||
m_data->m_physicsClientHandle, b3InitResetSimulationCommand(m_data->m_physicsClientHandle));
|
||||
}
|
||||
|
||||
bool b3RobotSimulatorClientAPI::canSubmitCommand() const
|
||||
{
|
||||
if (!isConnected())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return (b3CanSubmitCommand(m_data->m_physicsClientHandle));
|
||||
}
|
||||
|
||||
void b3RobotSimulatorClientAPI::stepSimulation()
|
||||
@ -190,8 +199,7 @@ void b3RobotSimulatorClientAPI::stepSimulation()
|
||||
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
b3Assert(b3CanSubmitCommand(m_data->m_physicsClientHandle));
|
||||
if (b3CanSubmitCommand(m_data->m_physicsClientHandle))
|
||||
if (b3CanSubmitCommand(m_data->m_physicsClientHandle))
|
||||
{
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitStepSimulationCommand(m_data->m_physicsClientHandle));
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
@ -740,6 +748,38 @@ void b3RobotSimulatorClientAPI::configureDebugVisualizer(b3ConfigureDebugVisuali
|
||||
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
|
||||
}
|
||||
|
||||
void b3RobotSimulatorClientAPI::getVREvents(b3VREventsData* vrEventsData)
|
||||
{
|
||||
vrEventsData->m_numControllerEvents = 0;
|
||||
vrEventsData->m_controllerEvents = 0;
|
||||
if (!isConnected())
|
||||
{
|
||||
b3Warning("Not connected");
|
||||
return;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(m_data->m_physicsClientHandle);
|
||||
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
|
||||
b3GetVREventsData(m_data->m_physicsClientHandle, vrEventsData);
|
||||
}
|
||||
|
||||
void b3RobotSimulatorClientAPI::getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData)
|
||||
{
|
||||
keyboardEventsData->m_numKeyboardEvents = 0;
|
||||
keyboardEventsData->m_keyboardEvents = 0;
|
||||
if (!isConnected())
|
||||
{
|
||||
b3Warning("Not connected");
|
||||
return;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3RequestKeyboardEventsCommandInit(m_data->m_physicsClientHandle);
|
||||
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
|
||||
b3GetKeyboardEventsData(m_data->m_physicsClientHandle,keyboardEventsData);
|
||||
|
||||
}
|
||||
|
||||
|
||||
int b3RobotSimulatorClientAPI::startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray<int>& objectUniqueIds)
|
||||
{
|
||||
int loggingUniqueId = -1;
|
||||
|
@ -167,6 +167,8 @@ public:
|
||||
|
||||
void stepSimulation();
|
||||
|
||||
bool canSubmitCommand() const;
|
||||
|
||||
void setRealTimeSimulation(bool enableRealTimeSimulation);
|
||||
|
||||
void setGravity(const b3Vector3& gravityAcceleration);
|
||||
@ -186,6 +188,9 @@ public:
|
||||
int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray<int>& objectUniqueIds);
|
||||
void stopStateLogging(int stateLoggerUniqueId);
|
||||
|
||||
void getVREvents(b3VREventsData* vrEventsData);
|
||||
void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData);
|
||||
|
||||
};
|
||||
|
||||
#endif //B3_ROBOT_SIMULATOR_CLIENT_API_H
|
||||
|
@ -58,6 +58,8 @@ public:
|
||||
|
||||
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData) = 0;
|
||||
|
||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0;
|
||||
|
||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits) = 0;
|
||||
|
||||
virtual void setTimeOut(double timeOutInSeconds) = 0;
|
||||
|
@ -2493,6 +2493,33 @@ int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int o
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||
b3Assert(cl);
|
||||
b3Assert(cl->canSubmitCommand());
|
||||
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||
b3Assert(command);
|
||||
|
||||
command->m_type = CMD_REQUEST_KEYBOARD_EVENTS_DATA;
|
||||
command->m_updateFlags = 0;
|
||||
|
||||
return (b3SharedMemoryCommandHandle)command;
|
||||
}
|
||||
|
||||
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
if (cl)
|
||||
{
|
||||
cl->getCachedKeyboardEvents(keyboardEventsData);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||
|
@ -350,6 +350,9 @@ int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double
|
||||
int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]);
|
||||
int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
|
||||
|
||||
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
|
||||
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);
|
||||
|
||||
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient);
|
||||
int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
|
||||
int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
|
||||
|
@ -44,6 +44,7 @@ struct PhysicsClientSharedMemoryInternalData {
|
||||
btAlignedObjectArray<b3OverlappingObject> m_cachedOverlappingObjects;
|
||||
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
|
||||
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
||||
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
||||
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
||||
|
||||
btAlignedObjectArray<int> m_bodyIdsRequestInfo;
|
||||
@ -773,6 +774,20 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
break;
|
||||
}
|
||||
|
||||
case CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED:
|
||||
{
|
||||
if (m_data->m_verboseOutput)
|
||||
{
|
||||
b3Printf("Request keyboard events completed");
|
||||
}
|
||||
m_data->m_cachedKeyboardEvents.resize(serverCmd.m_sendKeyboardEvents.m_numKeyboardEvents);
|
||||
for (int i=0;i<serverCmd.m_sendKeyboardEvents.m_numKeyboardEvents;i++)
|
||||
{
|
||||
m_data->m_cachedKeyboardEvents[i] = serverCmd.m_sendKeyboardEvents.m_keyboardEvents[i];
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case CMD_REQUEST_AABB_OVERLAP_COMPLETED:
|
||||
{
|
||||
if (m_data->m_verboseOutput)
|
||||
@ -1110,7 +1125,17 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
}
|
||||
|
||||
bool PhysicsClientSharedMemory::canSubmitCommand() const {
|
||||
return (m_data->m_isConnected && !m_data->m_waitingForServer);
|
||||
if (m_data->m_isConnected && !m_data->m_waitingForServer)
|
||||
{
|
||||
if (m_data->m_testBlock1->m_magicId == SHARED_MEMORY_MAGIC_NUMBER)
|
||||
{
|
||||
return true;
|
||||
} else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
struct SharedMemoryCommand* PhysicsClientSharedMemory::getAvailableSharedMemoryCommand() {
|
||||
@ -1177,6 +1202,13 @@ void PhysicsClientSharedMemory::getCachedVREvents(struct b3VREventsData* vrEvent
|
||||
&m_data->m_cachedVREvents[0] : 0;
|
||||
}
|
||||
|
||||
void PhysicsClientSharedMemory::getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData)
|
||||
{
|
||||
keyboardEventsData->m_numKeyboardEvents = m_data->m_cachedKeyboardEvents.size();
|
||||
keyboardEventsData->m_keyboardEvents = keyboardEventsData->m_numKeyboardEvents?
|
||||
&m_data->m_cachedKeyboardEvents[0] : 0;
|
||||
}
|
||||
|
||||
void PhysicsClientSharedMemory::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
||||
{
|
||||
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
||||
|
@ -67,6 +67,8 @@ public:
|
||||
|
||||
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
|
||||
|
||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||
|
||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||
|
||||
virtual void setTimeOut(double timeOutInSeconds);
|
||||
|
@ -175,8 +175,8 @@ struct UdpNetworkedInternalData
|
||||
printf("A packet of length %lu containing '%s' was "
|
||||
"received from %s on channel %u.\n",
|
||||
m_event.packet->dataLength,
|
||||
m_event.packet->data,
|
||||
m_event.peer->data,
|
||||
(char*)m_event.packet->data,
|
||||
(char*)m_event.peer->data,
|
||||
m_event.channelID);
|
||||
}
|
||||
/* Clean up the packet now that we're done using it.
|
||||
@ -186,7 +186,7 @@ struct UdpNetworkedInternalData
|
||||
break;
|
||||
|
||||
case ENET_EVENT_TYPE_DISCONNECT:
|
||||
printf("%s disconnected.\n", m_event.peer->data);
|
||||
printf("%s disconnected.\n", (char*)m_event.peer->data);
|
||||
|
||||
break;
|
||||
default:
|
||||
@ -230,8 +230,8 @@ struct UdpNetworkedInternalData
|
||||
printf("A packet of length %lu containing '%s' was "
|
||||
"received from %s on channel %u.\n",
|
||||
m_event.packet->dataLength,
|
||||
m_event.packet->data,
|
||||
m_event.peer->data,
|
||||
(char*)m_event.packet->data,
|
||||
(char*)m_event.peer->data,
|
||||
m_event.channelID);
|
||||
}
|
||||
|
||||
@ -271,7 +271,7 @@ struct UdpNetworkedInternalData
|
||||
}
|
||||
case ENET_EVENT_TYPE_DISCONNECT:
|
||||
{
|
||||
printf("%s disconnected.\n", m_event.peer->data);
|
||||
printf("%s disconnected.\n", (char*)m_event.peer->data);
|
||||
|
||||
break;
|
||||
}
|
||||
|
@ -52,6 +52,8 @@ struct PhysicsDirectInternalData
|
||||
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
|
||||
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
||||
|
||||
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
||||
|
||||
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
||||
|
||||
PhysicsCommandProcessorInterface* m_commandProcessor;
|
||||
@ -667,10 +669,23 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
||||
{
|
||||
b3Printf("Request VR Events completed");
|
||||
}
|
||||
m_data->m_cachedVREvents.clear();
|
||||
m_data->m_cachedVREvents.resize(serverCmd.m_sendVREvents.m_numVRControllerEvents);
|
||||
for (int i=0;i< serverCmd.m_sendVREvents.m_numVRControllerEvents;i++)
|
||||
{
|
||||
m_data->m_cachedVREvents.push_back(serverCmd.m_sendVREvents.m_controllerEvents[i]);
|
||||
m_data->m_cachedVREvents[i] = serverCmd.m_sendVREvents.m_controllerEvents[i];
|
||||
}
|
||||
break;
|
||||
}
|
||||
case CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED:
|
||||
{
|
||||
if (m_data->m_verboseOutput)
|
||||
{
|
||||
b3Printf("Request keyboard events completed");
|
||||
}
|
||||
m_data->m_cachedKeyboardEvents.resize(serverCmd.m_sendKeyboardEvents.m_numKeyboardEvents);
|
||||
for (int i=0;i<serverCmd.m_sendKeyboardEvents.m_numKeyboardEvents;i++)
|
||||
{
|
||||
m_data->m_cachedKeyboardEvents[i] = serverCmd.m_sendKeyboardEvents.m_keyboardEvents[i];
|
||||
}
|
||||
break;
|
||||
}
|
||||
@ -1031,6 +1046,13 @@ void PhysicsDirect::getCachedVREvents(struct b3VREventsData* vrEventsData)
|
||||
&m_data->m_cachedVREvents[0] : 0;
|
||||
}
|
||||
|
||||
void PhysicsDirect::getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData)
|
||||
{
|
||||
keyboardEventsData->m_numKeyboardEvents = m_data->m_cachedKeyboardEvents.size();
|
||||
keyboardEventsData->m_keyboardEvents = keyboardEventsData->m_numKeyboardEvents?
|
||||
&m_data->m_cachedKeyboardEvents[0] : 0;
|
||||
}
|
||||
|
||||
void PhysicsDirect::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
||||
{
|
||||
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
||||
|
@ -88,6 +88,8 @@ public:
|
||||
|
||||
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
|
||||
|
||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||
|
||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||
|
||||
//the following APIs are for internal use for visualization:
|
||||
|
@ -160,6 +160,11 @@ void PhysicsLoopBack::getCachedVREvents(struct b3VREventsData* vrEventsData)
|
||||
return m_data->m_physicsClient->getCachedVREvents(vrEventsData);
|
||||
}
|
||||
|
||||
void PhysicsLoopBack::getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData)
|
||||
{
|
||||
return m_data->m_physicsClient->getCachedKeyboardEvents(keyboardEventsData);
|
||||
}
|
||||
|
||||
void PhysicsLoopBack::getCachedOverlappingObjects(struct b3AABBOverlapData* overlappingObjects)
|
||||
{
|
||||
return m_data->m_physicsClient->getCachedOverlappingObjects(overlappingObjects);
|
||||
|
@ -72,6 +72,8 @@ public:
|
||||
|
||||
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
|
||||
|
||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||
|
||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||
|
||||
virtual void setTimeOut(double timeOutInSeconds);
|
||||
|
@ -48,7 +48,7 @@ bool gResetSimulation = 0;
|
||||
int gVRTrackingObjectUniqueId = -1;
|
||||
btTransform gVRTrackingObjectTr = btTransform::getIdentity();
|
||||
|
||||
int gMaxNumCmdPer1ms = 100;//experiment: add some delay to avoid threads starving other threads
|
||||
int gMaxNumCmdPer1ms = 10;//experiment: add some delay to avoid threads starving other threads
|
||||
int gCreateObjectSimVR = -1;
|
||||
int gEnableKukaControl = 0;
|
||||
btVector3 gVRTeleportPos1(0,0,0);
|
||||
@ -823,6 +823,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
bool m_hasGround;
|
||||
|
||||
b3VRControllerEvent m_vrEvents[MAX_VR_CONTROLLERS];
|
||||
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
||||
|
||||
btMultiBodyFixedConstraint* m_gripperRigidbodyFixed;
|
||||
btMultiBody* m_gripperMultiBody;
|
||||
@ -1932,6 +1933,42 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
hasStatus = true;
|
||||
break;
|
||||
};
|
||||
|
||||
case CMD_REQUEST_KEYBOARD_EVENTS_DATA:
|
||||
{
|
||||
serverStatusOut.m_sendKeyboardEvents.m_numKeyboardEvents = m_data->m_keyboardEvents.size();
|
||||
if (serverStatusOut.m_sendKeyboardEvents.m_numKeyboardEvents>MAX_KEYBOARD_EVENTS)
|
||||
{
|
||||
serverStatusOut.m_sendKeyboardEvents.m_numKeyboardEvents = MAX_KEYBOARD_EVENTS;
|
||||
}
|
||||
for (int i=0;i<serverStatusOut.m_sendKeyboardEvents.m_numKeyboardEvents;i++)
|
||||
{
|
||||
serverStatusOut.m_sendKeyboardEvents.m_keyboardEvents[i] = m_data->m_keyboardEvents[i];
|
||||
}
|
||||
|
||||
btAlignedObjectArray<b3KeyboardEvent> events;
|
||||
|
||||
//remove out-of-date events
|
||||
for (int i=0;i<m_data->m_keyboardEvents.size();i++)
|
||||
{
|
||||
b3KeyboardEvent event = m_data->m_keyboardEvents[i];
|
||||
if (event.m_keyState & eButtonIsDown)
|
||||
{
|
||||
event.m_keyState = eButtonIsDown;
|
||||
events.push_back(event);
|
||||
}
|
||||
}
|
||||
m_data->m_keyboardEvents.resize(events.size());
|
||||
for (int i=0;i<events.size();i++)
|
||||
{
|
||||
m_data->m_keyboardEvents[i] = events[i];
|
||||
}
|
||||
|
||||
serverStatusOut.m_type = CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED;
|
||||
hasStatus = true;
|
||||
break;
|
||||
};
|
||||
|
||||
case CMD_REQUEST_RAY_CAST_INTERSECTIONS:
|
||||
{
|
||||
btVector3 rayFromWorld(clientCmd.m_requestRaycastIntersections.m_rayFromPosition[0],
|
||||
@ -5050,7 +5087,7 @@ void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTime
|
||||
m_data->m_allowRealTimeSimulation = enableRealTimeSim;
|
||||
}
|
||||
|
||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents)
|
||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents,const struct b3KeyboardEvent* keyEvents, int numKeyEvents)
|
||||
{
|
||||
//update m_vrEvents
|
||||
for (int i=0;i<numVREvents;i++)
|
||||
@ -5090,6 +5127,31 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
|
||||
}
|
||||
}
|
||||
|
||||
for (int i=0;i<numKeyEvents;i++)
|
||||
{
|
||||
const b3KeyboardEvent& event = keyEvents[i];
|
||||
bool found = false;
|
||||
//search a matching one first, otherwise add new event
|
||||
for (int e=0;e<m_data->m_keyboardEvents.size();e++)
|
||||
{
|
||||
if (event.m_keyCode == m_data->m_keyboardEvents[e].m_keyCode)
|
||||
{
|
||||
m_data->m_keyboardEvents[e].m_keyState |= event.m_keyState;
|
||||
if (event.m_keyState & eButtonIsDown)
|
||||
{
|
||||
m_data->m_keyboardEvents[e].m_keyState |= eButtonIsDown;
|
||||
} else
|
||||
{
|
||||
m_data->m_keyboardEvents[e].m_keyState &= ~eButtonIsDown;
|
||||
}
|
||||
found=true;
|
||||
}
|
||||
}
|
||||
if (!found)
|
||||
{
|
||||
m_data->m_keyboardEvents.push_back(event);
|
||||
}
|
||||
}
|
||||
if (gResetSimulation)
|
||||
{
|
||||
resetSimulation();
|
||||
|
@ -96,7 +96,7 @@ public:
|
||||
//logging of object states (position etc)
|
||||
void logObjectStates(btScalar timeStep);
|
||||
|
||||
void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents);
|
||||
void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
||||
void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
void applyJointDamping(int bodyUniqueId);
|
||||
|
||||
|
@ -255,9 +255,11 @@ struct MotionArgs
|
||||
btAlignedObjectArray<MyMouseCommand> m_mouseCommands;
|
||||
|
||||
b3VRControllerEvent m_vrControllerEvents[MAX_VR_CONTROLLERS];
|
||||
|
||||
b3VRControllerEvent m_sendVrControllerEvents[MAX_VR_CONTROLLERS];
|
||||
|
||||
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
||||
btAlignedObjectArray<b3KeyboardEvent> m_sendKeyEvents;
|
||||
|
||||
PhysicsServerSharedMemory* m_physicsServerPtr;
|
||||
b3AlignedObjectArray<b3Vector3> m_positions;
|
||||
|
||||
@ -408,10 +410,33 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
|
||||
}
|
||||
}
|
||||
|
||||
args->m_sendKeyEvents.resize(args->m_keyboardEvents.size());
|
||||
for (int i=0;i<args->m_keyboardEvents.size();i++)
|
||||
{
|
||||
args->m_sendKeyEvents[i] = args->m_keyboardEvents[i];
|
||||
if (args->m_keyboardEvents[i].m_keyState&eButtonReleased)
|
||||
{
|
||||
args->m_keyboardEvents[i].m_keyState = 0;
|
||||
} else
|
||||
{
|
||||
args->m_keyboardEvents[i].m_keyState &= ~eButtonTriggered;
|
||||
}
|
||||
}
|
||||
//remove the 'released' events
|
||||
for (int i=args->m_keyboardEvents.size()-1;i>=0;i--)
|
||||
{
|
||||
if (args->m_keyboardEvents[i].m_keyState==0)
|
||||
{
|
||||
args->m_keyboardEvents.removeAtIndex(i);
|
||||
}
|
||||
}
|
||||
|
||||
b3KeyboardEvent* keyEvents = args->m_sendKeyEvents.size()? &args->m_sendKeyEvents[0] : 0;
|
||||
|
||||
args->m_csGUI->unlock();
|
||||
{
|
||||
BT_PROFILE("stepSimulationRealTime");
|
||||
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers);
|
||||
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers, keyEvents, args->m_sendKeyEvents.size());
|
||||
}
|
||||
deltaTimeInSeconds = 0;
|
||||
|
||||
@ -1086,6 +1111,59 @@ public:
|
||||
return false;
|
||||
}
|
||||
virtual bool keyboardCallback(int key, int state){
|
||||
|
||||
//printf("key=%d, state=%d\n", key,state);
|
||||
{
|
||||
int keyIndex = -1;
|
||||
//is already there?
|
||||
for (int i=0;i<m_args[0].m_keyboardEvents.size();i++)
|
||||
{
|
||||
if (m_args[0].m_keyboardEvents[i].m_keyCode == key)
|
||||
{
|
||||
keyIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (state)
|
||||
{
|
||||
b3KeyboardEvent ev;
|
||||
ev.m_keyCode = key;
|
||||
ev.m_keyState = eButtonIsDown+eButtonTriggered;
|
||||
m_args[0].m_csGUI->lock();
|
||||
if (keyIndex>=0)
|
||||
{
|
||||
if (0==(m_args[0].m_keyboardEvents[keyIndex].m_keyState & eButtonIsDown))
|
||||
{
|
||||
m_args[0].m_keyboardEvents[keyIndex] = ev;
|
||||
}
|
||||
} else
|
||||
{
|
||||
m_args[0].m_keyboardEvents.push_back(ev);
|
||||
}
|
||||
m_args[0].m_csGUI->unlock();
|
||||
} else
|
||||
{
|
||||
m_args[0].m_csGUI->lock();
|
||||
b3KeyboardEvent ev;
|
||||
ev.m_keyCode = key;
|
||||
ev.m_keyState = eButtonReleased;
|
||||
if (keyIndex>=0)
|
||||
{
|
||||
m_args[0].m_keyboardEvents[keyIndex]=ev;
|
||||
} else
|
||||
{
|
||||
m_args[0].m_keyboardEvents.push_back(ev);
|
||||
}
|
||||
m_args[0].m_csGUI->unlock();
|
||||
}
|
||||
}
|
||||
/*printf("m_args[0].m_keyboardEvents.size()=%d\n", m_args[0].m_keyboardEvents.size());
|
||||
for (int i=0;i<m_args[0].m_keyboardEvents.size();i++)
|
||||
{
|
||||
printf("key[%d]=%d state = %d\n",i,m_args[0].m_keyboardEvents[i].m_keyCode,m_args[0].m_keyboardEvents[i].m_keyState);
|
||||
}
|
||||
*/
|
||||
if (key=='w' && state)
|
||||
{
|
||||
gVRTeleportPos1[0]+=0.1;
|
||||
|
@ -225,9 +225,9 @@ void PhysicsServerSharedMemory::releaseSharedMemory()
|
||||
}
|
||||
|
||||
|
||||
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents)
|
||||
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents)
|
||||
{
|
||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec,vrEvents, numVREvents);
|
||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec,vrEvents, numVREvents, keyEvents,numKeyEvents);
|
||||
}
|
||||
|
||||
void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||
|
@ -26,7 +26,7 @@ public:
|
||||
|
||||
virtual void processClientCommands();
|
||||
|
||||
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents);
|
||||
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
||||
|
||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
|
||||
|
@ -608,6 +608,12 @@ struct SendVREvents
|
||||
b3VRControllerEvent m_controllerEvents[MAX_VR_CONTROLLERS];
|
||||
};
|
||||
|
||||
struct SendKeyboardEvents
|
||||
{
|
||||
int m_numKeyboardEvents;
|
||||
b3KeyboardEvent m_keyboardEvents[MAX_KEYBOARD_EVENTS];
|
||||
};
|
||||
|
||||
enum eVRCameraEnums
|
||||
{
|
||||
VR_CAMERA_ROOT_POSITION=1,
|
||||
@ -764,6 +770,7 @@ struct SharedMemoryStatus
|
||||
struct UserDebugDrawResultArgs m_userDebugDrawArgs;
|
||||
struct b3UserConstraint m_userConstraintResultArgs;
|
||||
struct SendVREvents m_sendVREvents;
|
||||
struct SendKeyboardEvents m_sendKeyboardEvents;
|
||||
struct SendRaycastHits m_raycastHits;
|
||||
struct StateLoggingResultArgs m_stateLoggingResultArgs;
|
||||
|
||||
|
@ -53,6 +53,7 @@ enum EnumSharedMemoryClientCommand
|
||||
CMD_SYNC_BODY_INFO,
|
||||
CMD_STATE_LOGGING,
|
||||
CMD_CONFIGURE_OPENGL_VISUALIZER,
|
||||
CMD_REQUEST_KEYBOARD_EVENTS_DATA,
|
||||
//don't go beyond this command!
|
||||
CMD_MAX_CLIENT_COMMANDS,
|
||||
|
||||
@ -130,7 +131,8 @@ enum EnumSharedMemoryServerStatus
|
||||
CMD_STATE_LOGGING_COMPLETED,
|
||||
CMD_STATE_LOGGING_START_COMPLETED,
|
||||
CMD_STATE_LOGGING_FAILED,
|
||||
|
||||
CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED,
|
||||
CMD_REQUEST_KEYBOARD_EVENTS_DATA_FAILED,
|
||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||
CMD_MAX_SERVER_COMMANDS
|
||||
};
|
||||
@ -251,6 +253,7 @@ enum b3VREventType
|
||||
#define MAX_VR_BUTTONS 64
|
||||
#define MAX_VR_CONTROLLERS 8
|
||||
#define MAX_RAY_HITS 128
|
||||
#define MAX_KEYBOARD_EVENTS 256
|
||||
|
||||
enum b3VRButtonInfo
|
||||
{
|
||||
@ -280,6 +283,18 @@ struct b3VREventsData
|
||||
};
|
||||
|
||||
|
||||
struct b3KeyboardEvent
|
||||
{
|
||||
int m_keyCode;//ascii
|
||||
int m_keyState;// see b3VRButtonInfo
|
||||
};
|
||||
|
||||
struct b3KeyboardEventsData
|
||||
{
|
||||
int m_numKeyboardEvents;
|
||||
struct b3KeyboardEvent* m_keyboardEvents;
|
||||
};
|
||||
|
||||
struct b3ContactPointData
|
||||
{
|
||||
//todo: expose some contact flags, such as telling which fields below are valid
|
||||
|
@ -2899,6 +2899,45 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
|
||||
|
||||
}
|
||||
|
||||
static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
struct b3KeyboardEventsData keyboardEventsData;
|
||||
PyObject* keyEventsObj = 0;
|
||||
int i=0;
|
||||
|
||||
static char *kwlist[] = { "physicsClientId", NULL };
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist,&physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
commandHandle = b3RequestKeyboardEventsCommandInit(sm);
|
||||
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
b3GetKeyboardEventsData(sm,&keyboardEventsData);
|
||||
|
||||
keyEventsObj = PyDict_New();
|
||||
|
||||
for (i=0;i<keyboardEventsData.m_numKeyboardEvents;i++)
|
||||
{
|
||||
PyObject* keyObj = PyLong_FromLong(keyboardEventsData.m_keyboardEvents[i].m_keyCode);
|
||||
PyObject* valObj = PyLong_FromLong(keyboardEventsData.m_keyboardEvents[i].m_keyState);
|
||||
PyDict_SetItem(keyEventsObj, keyObj, valObj);
|
||||
}
|
||||
return keyEventsObj;
|
||||
|
||||
}
|
||||
|
||||
static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
@ -5185,6 +5224,10 @@ static PyMethodDef SpamMethods[] = {
|
||||
"Set properties of the VR Camera such as its root transform "
|
||||
"for teleporting or to track objects (camera inside a vehicle for example)."
|
||||
},
|
||||
{ "getKeyboardEvents", (PyCFunction)pybullet_getKeyboardEvents, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get Keyboard events, keycode and state (KEY_IS_DOWN, KEY_WAS_TRIGGER, KEY_WAS_RELEASED)"
|
||||
},
|
||||
|
||||
{ "startStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS,
|
||||
"Start logging of state, such as robot base position, orientation, joint positions etc. "
|
||||
"Specify loggingType (STATE_LOG_MINITAUR, STATE_LOG_GENERIC_ROBOT, STATE_LOG_VR_CONTROLLERS etc), "
|
||||
@ -5209,6 +5252,43 @@ static PyMethodDef SpamMethods[] = {
|
||||
{NULL, NULL, 0, NULL} /* Sentinel */
|
||||
};
|
||||
|
||||
///copied from CommonWindowInterface.h
|
||||
|
||||
|
||||
enum {
|
||||
B3G_ESCAPE = 27,
|
||||
B3G_F1 = 0xff00,
|
||||
B3G_F2,
|
||||
B3G_F3,
|
||||
B3G_F4,
|
||||
B3G_F5,
|
||||
B3G_F6,
|
||||
B3G_F7,
|
||||
B3G_F8,
|
||||
B3G_F9,
|
||||
B3G_F10,
|
||||
B3G_F11,
|
||||
B3G_F12,
|
||||
B3G_F13,
|
||||
B3G_F14,
|
||||
B3G_F15,
|
||||
B3G_LEFT_ARROW,
|
||||
B3G_RIGHT_ARROW,
|
||||
B3G_UP_ARROW,
|
||||
B3G_DOWN_ARROW,
|
||||
B3G_PAGE_UP,
|
||||
B3G_PAGE_DOWN,
|
||||
B3G_END,
|
||||
B3G_HOME,
|
||||
B3G_INSERT,
|
||||
B3G_DELETE,
|
||||
B3G_BACKSPACE,
|
||||
B3G_SHIFT,
|
||||
B3G_CONTROL,
|
||||
B3G_ALT,
|
||||
B3G_RETURN
|
||||
};
|
||||
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
static struct PyModuleDef moduledef = {
|
||||
PyModuleDef_HEAD_INIT, "pybullet", /* m_name */
|
||||
@ -5280,6 +5360,10 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS);
|
||||
PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS);
|
||||
|
||||
PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown);
|
||||
PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered);
|
||||
PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased);
|
||||
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_MINITAUR", STATE_LOGGING_MINITAUR);
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT);
|
||||
PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS);
|
||||
@ -5287,8 +5371,38 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);
|
||||
PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME);
|
||||
PyModule_AddIntConstant(m,"B3G_F1",B3G_F1);
|
||||
PyModule_AddIntConstant(m,"B3G_F2",B3G_F2);
|
||||
PyModule_AddIntConstant(m,"B3G_F3",B3G_F3);
|
||||
PyModule_AddIntConstant(m,"B3G_F4",B3G_F4);
|
||||
PyModule_AddIntConstant(m,"B3G_F5",B3G_F5);
|
||||
PyModule_AddIntConstant(m,"B3G_F6",B3G_F6);
|
||||
PyModule_AddIntConstant(m,"B3G_F7",B3G_F7);
|
||||
PyModule_AddIntConstant(m,"B3G_F8",B3G_F8);
|
||||
PyModule_AddIntConstant(m,"B3G_F9",B3G_F9);
|
||||
PyModule_AddIntConstant(m,"B3G_F10",B3G_F10);
|
||||
PyModule_AddIntConstant(m,"B3G_F11",B3G_F11);
|
||||
PyModule_AddIntConstant(m,"B3G_F12",B3G_F12);
|
||||
PyModule_AddIntConstant(m,"B3G_F13",B3G_F13);
|
||||
PyModule_AddIntConstant(m,"B3G_F14",B3G_F14);
|
||||
PyModule_AddIntConstant(m,"B3G_F15",B3G_F15);
|
||||
PyModule_AddIntConstant(m,"B3G_LEFT_ARROW",B3G_LEFT_ARROW);
|
||||
PyModule_AddIntConstant(m,"B3G_RIGHT_ARROW",B3G_RIGHT_ARROW);
|
||||
PyModule_AddIntConstant(m,"B3G_UP_ARROW",B3G_UP_ARROW);
|
||||
PyModule_AddIntConstant(m,"B3G_DOWN_ARROW",B3G_DOWN_ARROW);
|
||||
PyModule_AddIntConstant(m,"B3G_PAGE_UP",B3G_PAGE_UP);
|
||||
PyModule_AddIntConstant(m,"B3G_PAGE_DOWN",B3G_PAGE_DOWN);
|
||||
PyModule_AddIntConstant(m,"B3G_END",B3G_END);
|
||||
PyModule_AddIntConstant(m,"B3G_HOME",B3G_HOME);
|
||||
PyModule_AddIntConstant(m,"B3G_INSERT",B3G_INSERT);
|
||||
PyModule_AddIntConstant(m,"B3G_DELETE",B3G_DELETE);
|
||||
PyModule_AddIntConstant(m,"B3G_BACKSPACE", B3G_BACKSPACE);
|
||||
PyModule_AddIntConstant(m,"B3G_SHIFT", B3G_SHIFT);
|
||||
PyModule_AddIntConstant(m,"B3G_CONTROL", B3G_CONTROL);
|
||||
PyModule_AddIntConstant(m,"B3G_ALT", B3G_ALT);
|
||||
PyModule_AddIntConstant(m,"B3G_RETURN", B3G_RETURN);
|
||||
|
||||
|
||||
|
||||
|
||||
SpamError = PyErr_NewException("pybullet.error", NULL, NULL);
|
||||
Py_INCREF(SpamError);
|
||||
|
Loading…
Reference in New Issue
Block a user