Merge pull request #1196 from erwincoumans/master
allow to disable/enable default keyboard shortcuts , pybullet.getMouseEvents, fix in obj2sdf, improve getCameraImage
This commit is contained in:
@@ -40,7 +40,11 @@ int main(int argc, char* argv[])
|
|||||||
b3CommandLineArgs args(argc,argv);
|
b3CommandLineArgs args(argc,argv);
|
||||||
char* fileName;
|
char* fileName;
|
||||||
args.GetCmdLineArgument("fileName",fileName);
|
args.GetCmdLineArgument("fileName",fileName);
|
||||||
|
if (fileName==0)
|
||||||
|
{
|
||||||
|
printf("required --fileName=\"name\"");
|
||||||
|
exit(0);
|
||||||
|
}
|
||||||
std::string matLibName = StripExtension(fileName);
|
std::string matLibName = StripExtension(fileName);
|
||||||
|
|
||||||
printf("fileName = %s\n", fileName);
|
printf("fileName = %s\n", fileName);
|
||||||
|
|||||||
@@ -130,6 +130,10 @@ static bool renderGrid = true;
|
|||||||
bool renderGui = true;
|
bool renderGui = true;
|
||||||
static bool enable_experimental_opencl = false;
|
static bool enable_experimental_opencl = false;
|
||||||
|
|
||||||
|
static bool gEnableDefaultKeyboardShortcuts = true;
|
||||||
|
static bool gEnableDefaultMousePicking = true;
|
||||||
|
|
||||||
|
|
||||||
int gDebugDrawFlags = 0;
|
int gDebugDrawFlags = 0;
|
||||||
static bool pauseSimulation=false;
|
static bool pauseSimulation=false;
|
||||||
static bool singleStepSimulation = false;
|
static bool singleStepSimulation = false;
|
||||||
@@ -200,7 +204,7 @@ void MyKeyboardCallback(int key, int state)
|
|||||||
//if (handled)
|
//if (handled)
|
||||||
// return;
|
// return;
|
||||||
|
|
||||||
//if (s_window && s_window->isModifierKeyPressed(B3G_CONTROL))
|
if (gEnableDefaultKeyboardShortcuts)
|
||||||
{
|
{
|
||||||
if (key=='a' && state)
|
if (key=='a' && state)
|
||||||
{
|
{
|
||||||
@@ -376,6 +380,15 @@ void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
|
|||||||
renderGrid = enable;
|
renderGrid = enable;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_KEYBOARD_SHORTCUTS)
|
||||||
|
{
|
||||||
|
gEnableDefaultKeyboardShortcuts = enable;
|
||||||
|
}
|
||||||
|
if (flag == COV_ENABLE_MOUSE_PICKING)
|
||||||
|
{
|
||||||
|
gEnableDefaultMousePicking = enable;
|
||||||
|
}
|
||||||
|
|
||||||
if (flag == COV_ENABLE_WIREFRAME)
|
if (flag == COV_ENABLE_WIREFRAME)
|
||||||
{
|
{
|
||||||
visualWireframe = enable;
|
visualWireframe = enable;
|
||||||
|
|||||||
@@ -62,6 +62,8 @@ public:
|
|||||||
|
|
||||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0;
|
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData) = 0;
|
||||||
|
|
||||||
|
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData) = 0;
|
||||||
|
|
||||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits) = 0;
|
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits) = 0;
|
||||||
|
|
||||||
virtual void setTimeOut(double timeOutInSeconds) = 0;
|
virtual void setTimeOut(double timeOutInSeconds) = 0;
|
||||||
|
|||||||
@@ -3208,6 +3208,31 @@ void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3Keyboard
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient)
|
||||||
|
{
|
||||||
|
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||||
|
b3Assert(cl);
|
||||||
|
b3Assert(cl->canSubmitCommand());
|
||||||
|
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||||
|
b3Assert(command);
|
||||||
|
|
||||||
|
command->m_type = CMD_REQUEST_MOUSE_EVENTS_DATA;
|
||||||
|
command->m_updateFlags = 0;
|
||||||
|
|
||||||
|
return (b3SharedMemoryCommandHandle)command;
|
||||||
|
}
|
||||||
|
|
||||||
|
void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData)
|
||||||
|
{
|
||||||
|
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||||
|
if (cl)
|
||||||
|
{
|
||||||
|
cl->getCachedMouseEvents(mouseEventsData);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name)
|
b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -433,6 +433,10 @@ int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, i
|
|||||||
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
|
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
|
||||||
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);
|
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);
|
||||||
|
|
||||||
|
b3SharedMemoryCommandHandle b3RequestMouseEventsCommandInit(b3PhysicsClientHandle physClient);
|
||||||
|
void b3GetMouseEventsData(b3PhysicsClientHandle physClient, struct b3MouseEventsData* mouseEventsData);
|
||||||
|
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient);
|
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient);
|
||||||
int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
|
int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
|
||||||
int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
|
int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
|
||||||
|
|||||||
@@ -46,6 +46,8 @@ struct PhysicsClientSharedMemoryInternalData {
|
|||||||
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
|
btAlignedObjectArray<b3VisualShapeData> m_cachedVisualShapes;
|
||||||
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
||||||
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
||||||
|
btAlignedObjectArray<b3MouseEvent> m_cachedMouseEvents;
|
||||||
|
|
||||||
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
||||||
|
|
||||||
btAlignedObjectArray<int> m_bodyIdsRequestInfo;
|
btAlignedObjectArray<int> m_bodyIdsRequestInfo;
|
||||||
@@ -876,6 +878,21 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED:
|
||||||
|
{
|
||||||
|
B3_PROFILE("CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED");
|
||||||
|
if (m_data->m_verboseOutput)
|
||||||
|
{
|
||||||
|
b3Printf("Request mouse events completed");
|
||||||
|
}
|
||||||
|
m_data->m_cachedMouseEvents.resize(serverCmd.m_sendMouseEvents.m_numMouseEvents);
|
||||||
|
for (int i=0;i<serverCmd.m_sendMouseEvents.m_numMouseEvents;i++)
|
||||||
|
{
|
||||||
|
m_data->m_cachedMouseEvents[i] = serverCmd.m_sendMouseEvents.m_mouseEvents[i];
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case CMD_REQUEST_AABB_OVERLAP_COMPLETED:
|
case CMD_REQUEST_AABB_OVERLAP_COMPLETED:
|
||||||
{
|
{
|
||||||
B3_PROFILE("CMD_REQUEST_AABB_OVERLAP_COMPLETED");
|
B3_PROFILE("CMD_REQUEST_AABB_OVERLAP_COMPLETED");
|
||||||
@@ -1393,6 +1410,14 @@ void PhysicsClientSharedMemory::getCachedKeyboardEvents(struct b3KeyboardEventsD
|
|||||||
&m_data->m_cachedKeyboardEvents[0] : 0;
|
&m_data->m_cachedKeyboardEvents[0] : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PhysicsClientSharedMemory::getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData)
|
||||||
|
{
|
||||||
|
mouseEventsData->m_numMouseEvents = m_data->m_cachedMouseEvents.size();
|
||||||
|
mouseEventsData->m_mouseEvents = mouseEventsData->m_numMouseEvents?
|
||||||
|
&m_data->m_cachedMouseEvents[0] : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void PhysicsClientSharedMemory::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
void PhysicsClientSharedMemory::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
||||||
{
|
{
|
||||||
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
||||||
|
|||||||
@@ -72,6 +72,8 @@ public:
|
|||||||
|
|
||||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||||
|
|
||||||
|
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData);
|
||||||
|
|
||||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||||
|
|
||||||
virtual void setTimeOut(double timeOutInSeconds);
|
virtual void setTimeOut(double timeOutInSeconds);
|
||||||
|
|||||||
@@ -40,7 +40,7 @@ public:
|
|||||||
virtual ~CommandProcessorInterface(){}
|
virtual ~CommandProcessorInterface(){}
|
||||||
|
|
||||||
virtual void syncPhysicsToGraphics()=0;
|
virtual void syncPhysicsToGraphics()=0;
|
||||||
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents)=0;
|
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)=0;
|
||||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0;
|
virtual void enableRealTimeSimulation(bool enableRealTimeSim)=0;
|
||||||
virtual bool isRealTimeSimulationEnabled() const=0;
|
virtual bool isRealTimeSimulationEnabled() const=0;
|
||||||
|
|
||||||
|
|||||||
@@ -54,6 +54,7 @@ struct PhysicsDirectInternalData
|
|||||||
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
btAlignedObjectArray<b3VRControllerEvent> m_cachedVREvents;
|
||||||
|
|
||||||
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
btAlignedObjectArray<b3KeyboardEvent> m_cachedKeyboardEvents;
|
||||||
|
btAlignedObjectArray<b3MouseEvent> m_cachedMouseEvents;
|
||||||
|
|
||||||
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
btAlignedObjectArray<b3RayHitInfo> m_raycastHits;
|
||||||
|
|
||||||
@@ -699,6 +700,21 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED:
|
||||||
|
{
|
||||||
|
B3_PROFILE("CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED");
|
||||||
|
if (m_data->m_verboseOutput)
|
||||||
|
{
|
||||||
|
b3Printf("Request mouse events completed");
|
||||||
|
}
|
||||||
|
m_data->m_cachedMouseEvents.resize(serverCmd.m_sendMouseEvents.m_numMouseEvents);
|
||||||
|
for (int i=0;i<serverCmd.m_sendMouseEvents.m_numMouseEvents;i++)
|
||||||
|
{
|
||||||
|
m_data->m_cachedMouseEvents[i] = serverCmd.m_sendMouseEvents.m_mouseEvents[i];
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
case CMD_REQUEST_INTERNAL_DATA_COMPLETED:
|
case CMD_REQUEST_INTERNAL_DATA_COMPLETED:
|
||||||
{
|
{
|
||||||
if (serverCmd.m_numDataStreamBytes)
|
if (serverCmd.m_numDataStreamBytes)
|
||||||
@@ -1159,6 +1175,14 @@ void PhysicsDirect::getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboar
|
|||||||
&m_data->m_cachedKeyboardEvents[0] : 0;
|
&m_data->m_cachedKeyboardEvents[0] : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PhysicsDirect::getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData)
|
||||||
|
{
|
||||||
|
mouseEventsData->m_numMouseEvents = m_data->m_cachedMouseEvents.size();
|
||||||
|
mouseEventsData->m_mouseEvents = mouseEventsData->m_numMouseEvents?
|
||||||
|
&m_data->m_cachedMouseEvents[0] : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void PhysicsDirect::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
void PhysicsDirect::getCachedRaycastHits(struct b3RaycastInformation* raycastHits)
|
||||||
{
|
{
|
||||||
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
raycastHits->m_numRayHits = m_data->m_raycastHits.size();
|
||||||
|
|||||||
@@ -95,6 +95,8 @@ public:
|
|||||||
|
|
||||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||||
|
|
||||||
|
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData);
|
||||||
|
|
||||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||||
|
|
||||||
//the following APIs are for internal use for visualization:
|
//the following APIs are for internal use for visualization:
|
||||||
|
|||||||
@@ -190,6 +190,11 @@ void PhysicsLoopBack::getCachedKeyboardEvents(struct b3KeyboardEventsData* keybo
|
|||||||
return m_data->m_physicsClient->getCachedKeyboardEvents(keyboardEventsData);
|
return m_data->m_physicsClient->getCachedKeyboardEvents(keyboardEventsData);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PhysicsLoopBack::getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData)
|
||||||
|
{
|
||||||
|
return m_data->m_physicsClient->getCachedMouseEvents(mouseEventsData);
|
||||||
|
}
|
||||||
|
|
||||||
void PhysicsLoopBack::getCachedOverlappingObjects(struct b3AABBOverlapData* overlappingObjects)
|
void PhysicsLoopBack::getCachedOverlappingObjects(struct b3AABBOverlapData* overlappingObjects)
|
||||||
{
|
{
|
||||||
return m_data->m_physicsClient->getCachedOverlappingObjects(overlappingObjects);
|
return m_data->m_physicsClient->getCachedOverlappingObjects(overlappingObjects);
|
||||||
|
|||||||
@@ -76,6 +76,8 @@ public:
|
|||||||
|
|
||||||
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
|
||||||
|
|
||||||
|
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData);
|
||||||
|
|
||||||
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
|
||||||
|
|
||||||
virtual void setTimeOut(double timeOutInSeconds);
|
virtual void setTimeOut(double timeOutInSeconds);
|
||||||
|
|||||||
@@ -1153,7 +1153,8 @@ struct PhysicsServerCommandProcessorInternalData
|
|||||||
|
|
||||||
|
|
||||||
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
||||||
|
btAlignedObjectArray<b3MouseEvent> m_mouseEvents;
|
||||||
|
|
||||||
CommandLogger* m_commandLogger;
|
CommandLogger* m_commandLogger;
|
||||||
CommandLogPlayback* m_logPlayback;
|
CommandLogPlayback* m_logPlayback;
|
||||||
|
|
||||||
@@ -2774,6 +2775,27 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
break;
|
break;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
case CMD_REQUEST_MOUSE_EVENTS_DATA:
|
||||||
|
{
|
||||||
|
|
||||||
|
serverStatusOut.m_sendMouseEvents.m_numMouseEvents = m_data->m_mouseEvents.size();
|
||||||
|
if (serverStatusOut.m_sendMouseEvents.m_numMouseEvents>MAX_MOUSE_EVENTS)
|
||||||
|
{
|
||||||
|
serverStatusOut.m_sendMouseEvents.m_numMouseEvents = MAX_MOUSE_EVENTS;
|
||||||
|
}
|
||||||
|
for (int i=0;i<serverStatusOut.m_sendMouseEvents.m_numMouseEvents;i++)
|
||||||
|
{
|
||||||
|
serverStatusOut.m_sendMouseEvents.m_mouseEvents[i] = m_data->m_mouseEvents[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
m_data->m_mouseEvents.resize(0);
|
||||||
|
serverStatusOut.m_type = CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED;
|
||||||
|
hasStatus = true;
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
case CMD_REQUEST_KEYBOARD_EVENTS_DATA:
|
case CMD_REQUEST_KEYBOARD_EVENTS_DATA:
|
||||||
{
|
{
|
||||||
//BT_PROFILE("CMD_REQUEST_KEYBOARD_EVENTS_DATA");
|
//BT_PROFILE("CMD_REQUEST_KEYBOARD_EVENTS_DATA");
|
||||||
@@ -3066,9 +3088,29 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
m_data->m_visualConverter.render();
|
SharedMemoryStatus tmpCmd = serverStatusOut;
|
||||||
|
bool result = this->m_data->m_guiHelper->getCameraInfo(
|
||||||
|
&tmpCmd.m_visualizerCameraResultArgs.m_width,
|
||||||
|
&tmpCmd.m_visualizerCameraResultArgs.m_height,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_viewMatrix,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_projectionMatrix,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_camUp,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_camForward,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_horizontal,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_vertical,
|
||||||
|
&tmpCmd.m_visualizerCameraResultArgs.m_yaw,
|
||||||
|
&tmpCmd.m_visualizerCameraResultArgs.m_pitch,
|
||||||
|
&tmpCmd.m_visualizerCameraResultArgs.m_dist,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_target);
|
||||||
|
if (result)
|
||||||
|
{
|
||||||
|
m_data->m_visualConverter.render(tmpCmd.m_visualizerCameraResultArgs.m_viewMatrix,
|
||||||
|
tmpCmd.m_visualizerCameraResultArgs.m_projectionMatrix);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
m_data->m_visualConverter.render();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,
|
m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,
|
||||||
@@ -7012,7 +7054,7 @@ bool PhysicsServerCommandProcessor::isRealTimeSimulationEnabled() const
|
|||||||
return m_data->m_allowRealTimeSimulation;
|
return m_data->m_allowRealTimeSimulation;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents,const struct b3KeyboardEvent* keyEvents, int numKeyEvents)
|
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
|
||||||
{
|
{
|
||||||
m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
|
m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
|
||||||
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
for (int i=0;i<m_data->m_stateLoggers.size();i++)
|
||||||
@@ -7024,6 +7066,41 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
for (int ii=0;ii<numMouseEvents;ii++)
|
||||||
|
{
|
||||||
|
const b3MouseEvent& event = mouseEvents[ii];
|
||||||
|
bool found = false;
|
||||||
|
//search a matching one first, otherwise add new event
|
||||||
|
for (int e=0;e<m_data->m_mouseEvents.size();e++)
|
||||||
|
{
|
||||||
|
if (event.m_eventType == m_data->m_mouseEvents[e].m_eventType)
|
||||||
|
{
|
||||||
|
if (event.m_eventType == MOUSE_MOVE_EVENT)
|
||||||
|
{
|
||||||
|
m_data->m_mouseEvents[e].m_mousePosX = event.m_mousePosX;
|
||||||
|
m_data->m_mouseEvents[e].m_mousePosY = event.m_mousePosY;
|
||||||
|
found = true;
|
||||||
|
} else
|
||||||
|
if ((event.m_eventType == MOUSE_BUTTON_EVENT) && event.m_buttonIndex == m_data->m_mouseEvents[e].m_buttonIndex)
|
||||||
|
{
|
||||||
|
m_data->m_mouseEvents[e].m_buttonState |= event.m_buttonState;
|
||||||
|
if (event.m_buttonState & eButtonIsDown)
|
||||||
|
{
|
||||||
|
m_data->m_mouseEvents[e].m_buttonState |= eButtonIsDown;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
m_data->m_mouseEvents[e].m_buttonState &= ~eButtonIsDown;
|
||||||
|
}
|
||||||
|
found = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (!found)
|
||||||
|
{
|
||||||
|
m_data->m_mouseEvents.push_back(event);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
for (int i=0;i<numKeyEvents;i++)
|
for (int i=0;i<numKeyEvents;i++)
|
||||||
{
|
{
|
||||||
const b3KeyboardEvent& event = keyEvents[i];
|
const b3KeyboardEvent& event = keyEvents[i];
|
||||||
|
|||||||
@@ -94,7 +94,8 @@ public:
|
|||||||
void logObjectStates(btScalar timeStep);
|
void logObjectStates(btScalar timeStep);
|
||||||
void processCollisionForces(btScalar timeStep);
|
void processCollisionForces(btScalar timeStep);
|
||||||
|
|
||||||
virtual void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents);
|
||||||
|
|
||||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||||
virtual bool isRealTimeSimulationEnabled() const;
|
virtual bool isRealTimeSimulationEnabled() const;
|
||||||
|
|
||||||
|
|||||||
@@ -30,6 +30,9 @@ bool gEnableUpdateDebugDrawLines = true;
|
|||||||
static int gCamVisualizerWidth = 320;
|
static int gCamVisualizerWidth = 320;
|
||||||
static int gCamVisualizerHeight = 240;
|
static int gCamVisualizerHeight = 240;
|
||||||
|
|
||||||
|
static bool gEnableDefaultKeyboardShortcuts = true;
|
||||||
|
static bool gEnableDefaultMousePicking = true;
|
||||||
|
|
||||||
|
|
||||||
//extern btVector3 gLastPickPos;
|
//extern btVector3 gLastPickPos;
|
||||||
btVector3 gVRTeleportPosLocal(0,0,0);
|
btVector3 gVRTeleportPosLocal(0,0,0);
|
||||||
@@ -212,7 +215,8 @@ struct MotionArgs
|
|||||||
|
|
||||||
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
|
||||||
btAlignedObjectArray<b3KeyboardEvent> m_sendKeyEvents;
|
btAlignedObjectArray<b3KeyboardEvent> m_sendKeyEvents;
|
||||||
|
btAlignedObjectArray<b3MouseEvent> m_allMouseEvents;
|
||||||
|
btAlignedObjectArray<b3MouseEvent> m_sendMouseEvents;
|
||||||
PhysicsServerSharedMemory* m_physicsServerPtr;
|
PhysicsServerSharedMemory* m_physicsServerPtr;
|
||||||
b3AlignedObjectArray<b3Vector3> m_positions;
|
b3AlignedObjectArray<b3Vector3> m_positions;
|
||||||
|
|
||||||
@@ -389,8 +393,52 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
|
|||||||
b3KeyboardEvent* keyEvents = args->m_sendKeyEvents.size()? &args->m_sendKeyEvents[0] : 0;
|
b3KeyboardEvent* keyEvents = args->m_sendKeyEvents.size()? &args->m_sendKeyEvents[0] : 0;
|
||||||
|
|
||||||
args->m_csGUI->unlock();
|
args->m_csGUI->unlock();
|
||||||
|
|
||||||
|
args->m_csGUI->lock();
|
||||||
|
if (gEnableDefaultMousePicking)
|
||||||
{
|
{
|
||||||
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers, keyEvents, args->m_sendKeyEvents.size());
|
for (int i = 0; i < args->m_mouseCommands.size(); i++)
|
||||||
|
{
|
||||||
|
switch (args->m_mouseCommands[i].m_type)
|
||||||
|
{
|
||||||
|
case MyMouseMove:
|
||||||
|
{
|
||||||
|
args->m_physicsServerPtr->movePickedBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
||||||
|
break;
|
||||||
|
};
|
||||||
|
case MyMouseButtonDown:
|
||||||
|
{
|
||||||
|
args->m_physicsServerPtr->pickBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case MyMouseButtonUp:
|
||||||
|
{
|
||||||
|
args->m_physicsServerPtr->removePickingConstraint();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
args->m_sendMouseEvents.resize(args->m_allMouseEvents.size());
|
||||||
|
for (int i=0;i<args->m_allMouseEvents.size();i++)
|
||||||
|
{
|
||||||
|
args->m_sendMouseEvents[i] = args->m_allMouseEvents[i];
|
||||||
|
}
|
||||||
|
b3MouseEvent* mouseEvents = args->m_sendMouseEvents.size()? &args->m_sendMouseEvents[0] : 0;
|
||||||
|
|
||||||
|
args->m_allMouseEvents.clear();
|
||||||
|
args->m_mouseCommands.clear();
|
||||||
|
args->m_csGUI->unlock();
|
||||||
|
|
||||||
|
|
||||||
|
{
|
||||||
|
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers, keyEvents, args->m_sendKeyEvents.size(), mouseEvents, args->m_sendMouseEvents.size());
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
if (gEnableUpdateDebugDrawLines)
|
if (gEnableUpdateDebugDrawLines)
|
||||||
@@ -405,35 +453,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
args->m_csGUI->lock();
|
|
||||||
for (int i = 0; i < args->m_mouseCommands.size(); i++)
|
|
||||||
{
|
|
||||||
switch (args->m_mouseCommands[i].m_type)
|
|
||||||
{
|
|
||||||
case MyMouseMove:
|
|
||||||
{
|
|
||||||
args->m_physicsServerPtr->movePickedBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
|
||||||
break;
|
|
||||||
};
|
|
||||||
case MyMouseButtonDown:
|
|
||||||
{
|
|
||||||
args->m_physicsServerPtr->pickBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case MyMouseButtonUp:
|
|
||||||
{
|
|
||||||
args->m_physicsServerPtr->removePickingConstraint();
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
default:
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
args->m_mouseCommands.clear();
|
|
||||||
args->m_csGUI->unlock();
|
|
||||||
|
|
||||||
{
|
{
|
||||||
args->m_physicsServerPtr->processClientCommands();
|
args->m_physicsServerPtr->processClientCommands();
|
||||||
@@ -1282,6 +1302,16 @@ public:
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
b3MouseEvent event;
|
||||||
|
event.m_buttonState = 0;
|
||||||
|
event.m_buttonIndex = -1;
|
||||||
|
event.m_mousePosX = x;
|
||||||
|
event.m_mousePosY = y;
|
||||||
|
event.m_eventType = MOUSE_MOVE_EVENT;
|
||||||
|
m_args[0].m_csGUI->lock();
|
||||||
|
m_args[0].m_allMouseEvents.push_back(event);
|
||||||
|
m_args[0].m_csGUI->unlock();
|
||||||
|
|
||||||
btVector3 rayTo = getRayTo(int(x), int(y));
|
btVector3 rayTo = getRayTo(int(x), int(y));
|
||||||
btVector3 rayFrom;
|
btVector3 rayFrom;
|
||||||
renderer->getActiveCamera()->getCameraPosition(rayFrom);
|
renderer->getActiveCamera()->getCameraPosition(rayFrom);
|
||||||
@@ -1311,6 +1341,22 @@ public:
|
|||||||
|
|
||||||
CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
|
CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
|
||||||
|
|
||||||
|
b3MouseEvent event;
|
||||||
|
event.m_buttonIndex = button;
|
||||||
|
event.m_mousePosX = x;
|
||||||
|
event.m_mousePosY = y;
|
||||||
|
event.m_eventType = MOUSE_BUTTON_EVENT;
|
||||||
|
if (state)
|
||||||
|
{
|
||||||
|
event.m_buttonState = eButtonIsDown + eButtonTriggered;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
event.m_buttonState = eButtonReleased;
|
||||||
|
}
|
||||||
|
|
||||||
|
m_args[0].m_csGUI->lock();
|
||||||
|
m_args[0].m_allMouseEvents.push_back(event);
|
||||||
|
m_args[0].m_csGUI->unlock();
|
||||||
|
|
||||||
if (state==1)
|
if (state==1)
|
||||||
{
|
{
|
||||||
@@ -1415,50 +1461,52 @@ public:
|
|||||||
|
|
||||||
btVector3 VRTeleportPos =this->m_physicsServer.getVRTeleportPosition();
|
btVector3 VRTeleportPos =this->m_physicsServer.getVRTeleportPosition();
|
||||||
|
|
||||||
if (key=='w' && state)
|
if (gEnableDefaultKeyboardShortcuts)
|
||||||
{
|
{
|
||||||
VRTeleportPos[0]+=shift;
|
if (key=='w' && state)
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
{
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
VRTeleportPos[0]+=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='s' && state)
|
||||||
|
{
|
||||||
|
VRTeleportPos[0]-=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='a' && state)
|
||||||
|
{
|
||||||
|
VRTeleportPos[1]-=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='d' && state)
|
||||||
|
{
|
||||||
|
VRTeleportPos[1]+=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='q' && state)
|
||||||
|
{
|
||||||
|
VRTeleportPos[2]+=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='e' && state)
|
||||||
|
{
|
||||||
|
VRTeleportPos[2]-=shift;
|
||||||
|
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
|
if (key=='z' && state)
|
||||||
|
{
|
||||||
|
gVRTeleportRotZ+=shift;
|
||||||
|
btQuaternion VRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
||||||
|
m_physicsServer.setVRTeleportOrientation(VRTeleportOrn);
|
||||||
|
saveCurrentSettingsVR(VRTeleportPos);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (key=='s' && state)
|
|
||||||
{
|
|
||||||
VRTeleportPos[0]-=shift;
|
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
if (key=='a' && state)
|
|
||||||
{
|
|
||||||
VRTeleportPos[1]-=shift;
|
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
if (key=='d' && state)
|
|
||||||
{
|
|
||||||
VRTeleportPos[1]+=shift;
|
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
if (key=='q' && state)
|
|
||||||
{
|
|
||||||
VRTeleportPos[2]+=shift;
|
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
if (key=='e' && state)
|
|
||||||
{
|
|
||||||
VRTeleportPos[2]-=shift;
|
|
||||||
m_physicsServer.setVRTeleportPosition(VRTeleportPos);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
if (key=='z' && state)
|
|
||||||
{
|
|
||||||
gVRTeleportRotZ+=shift;
|
|
||||||
btQuaternion VRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
|
||||||
m_physicsServer.setVRTeleportOrientation(VRTeleportOrn);
|
|
||||||
saveCurrentSettingsVR(VRTeleportPos);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
@@ -1514,8 +1562,22 @@ public:
|
|||||||
m_physicsServer.enableRealTimeSimulation(true);
|
m_physicsServer.enableRealTimeSimulation(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (args.CheckCmdLineFlag("disableDefaultKeyboardShortcuts"))
|
||||||
|
{
|
||||||
|
gEnableDefaultKeyboardShortcuts = false;
|
||||||
|
}
|
||||||
|
if (args.CheckCmdLineFlag("enableDefaultKeyboardShortcuts"))
|
||||||
|
{
|
||||||
|
gEnableDefaultKeyboardShortcuts = true;
|
||||||
|
}
|
||||||
|
if (args.CheckCmdLineFlag("disableDefaultMousePicking"))
|
||||||
|
{
|
||||||
|
gEnableDefaultMousePicking = false;
|
||||||
|
}
|
||||||
|
if (args.CheckCmdLineFlag("enableDefaultMousePicking"))
|
||||||
|
{
|
||||||
|
gEnableDefaultMousePicking = true;
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -1797,6 +1859,16 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
gEnableRendering = (enable!=0);
|
gEnableRendering = (enable!=0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_KEYBOARD_SHORTCUTS)
|
||||||
|
{
|
||||||
|
gEnableDefaultKeyboardShortcuts = (enable!=0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (flag == COV_ENABLE_MOUSE_PICKING)
|
||||||
|
{
|
||||||
|
gEnableDefaultMousePicking = (enable!=0);
|
||||||
|
}
|
||||||
|
|
||||||
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable);
|
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable);
|
||||||
m_multiThreadedHelper->mainThreadRelease();
|
m_multiThreadedHelper->mainThreadRelease();
|
||||||
break;
|
break;
|
||||||
|
|||||||
@@ -226,9 +226,9 @@ void PhysicsServerSharedMemory::releaseSharedMemory()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents)
|
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents)
|
||||||
{
|
{
|
||||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec,vrEvents, numVREvents, keyEvents,numKeyEvents);
|
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec,vrEvents, numVREvents, keyEvents,numKeyEvents,mouseEvents, numMouseEvents);
|
||||||
}
|
}
|
||||||
|
|
||||||
void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim)
|
void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||||
|
|||||||
@@ -27,7 +27,7 @@ public:
|
|||||||
|
|
||||||
virtual void processClientCommands();
|
virtual void processClientCommands();
|
||||||
|
|
||||||
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
|
virtual void stepSimulationRealTime(double dtInSec,const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents);
|
||||||
|
|
||||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||||
virtual bool isRealTimeSimulationEnabled() const;
|
virtual bool isRealTimeSimulationEnabled() const;
|
||||||
|
|||||||
@@ -721,6 +721,11 @@ struct SendKeyboardEvents
|
|||||||
b3KeyboardEvent m_keyboardEvents[MAX_KEYBOARD_EVENTS];
|
b3KeyboardEvent m_keyboardEvents[MAX_KEYBOARD_EVENTS];
|
||||||
};
|
};
|
||||||
|
|
||||||
|
struct SendMouseEvents
|
||||||
|
{
|
||||||
|
int m_numMouseEvents;
|
||||||
|
b3MouseEvent m_mouseEvents[MAX_MOUSE_EVENTS];
|
||||||
|
};
|
||||||
|
|
||||||
enum eVRCameraEnums
|
enum eVRCameraEnums
|
||||||
{
|
{
|
||||||
@@ -931,7 +936,6 @@ struct SharedMemoryCommand
|
|||||||
struct b3CreateVisualShapeArgs m_createVisualShapeArgs;
|
struct b3CreateVisualShapeArgs m_createVisualShapeArgs;
|
||||||
struct b3CreateMultiBodyArgs m_createMultiBodyArgs;
|
struct b3CreateMultiBodyArgs m_createMultiBodyArgs;
|
||||||
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
|
struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs;
|
||||||
|
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -1001,6 +1005,8 @@ struct SharedMemoryStatus
|
|||||||
struct b3CreateVisualShapeResultArgs m_createVisualShapeResultArgs;
|
struct b3CreateVisualShapeResultArgs m_createVisualShapeResultArgs;
|
||||||
struct b3CreateMultiBodyResultArgs m_createMultiBodyResultArgs;
|
struct b3CreateMultiBodyResultArgs m_createMultiBodyResultArgs;
|
||||||
struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs;
|
struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs;
|
||||||
|
struct SendMouseEvents m_sendMouseEvents;
|
||||||
|
|
||||||
};
|
};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -66,6 +66,7 @@ enum EnumSharedMemoryClientCommand
|
|||||||
CMD_CREATE_VISUAL_SHAPE,
|
CMD_CREATE_VISUAL_SHAPE,
|
||||||
CMD_CREATE_MULTI_BODY,
|
CMD_CREATE_MULTI_BODY,
|
||||||
CMD_REQUEST_COLLISION_INFO,
|
CMD_REQUEST_COLLISION_INFO,
|
||||||
|
CMD_REQUEST_MOUSE_EVENTS_DATA,
|
||||||
//don't go beyond this command!
|
//don't go beyond this command!
|
||||||
CMD_MAX_CLIENT_COMMANDS,
|
CMD_MAX_CLIENT_COMMANDS,
|
||||||
|
|
||||||
@@ -159,6 +160,7 @@ enum EnumSharedMemoryServerStatus
|
|||||||
CMD_CREATE_MULTI_BODY_COMPLETED,
|
CMD_CREATE_MULTI_BODY_COMPLETED,
|
||||||
CMD_REQUEST_COLLISION_INFO_COMPLETED,
|
CMD_REQUEST_COLLISION_INFO_COMPLETED,
|
||||||
CMD_REQUEST_COLLISION_INFO_FAILED,
|
CMD_REQUEST_COLLISION_INFO_FAILED,
|
||||||
|
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
|
||||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||||
CMD_MAX_SERVER_COMMANDS
|
CMD_MAX_SERVER_COMMANDS
|
||||||
};
|
};
|
||||||
@@ -325,7 +327,7 @@ enum b3VREventType
|
|||||||
#define MAX_RAY_INTERSECTION_BATCH_SIZE 256
|
#define MAX_RAY_INTERSECTION_BATCH_SIZE 256
|
||||||
#define MAX_RAY_HITS MAX_RAY_INTERSECTION_BATCH_SIZE
|
#define MAX_RAY_HITS MAX_RAY_INTERSECTION_BATCH_SIZE
|
||||||
#define MAX_KEYBOARD_EVENTS 256
|
#define MAX_KEYBOARD_EVENTS 256
|
||||||
|
#define MAX_MOUSE_EVENTS 256
|
||||||
|
|
||||||
|
|
||||||
enum b3VRButtonInfo
|
enum b3VRButtonInfo
|
||||||
@@ -384,6 +386,28 @@ struct b3KeyboardEventsData
|
|||||||
struct b3KeyboardEvent* m_keyboardEvents;
|
struct b3KeyboardEvent* m_keyboardEvents;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
enum eMouseEventTypeEnums
|
||||||
|
{
|
||||||
|
MOUSE_MOVE_EVENT=1,
|
||||||
|
MOUSE_BUTTON_EVENT=2,
|
||||||
|
};
|
||||||
|
|
||||||
|
struct b3MouseEvent
|
||||||
|
{
|
||||||
|
int m_eventType;
|
||||||
|
float m_mousePosX;
|
||||||
|
float m_mousePosY;
|
||||||
|
int m_buttonIndex;
|
||||||
|
int m_buttonState;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct b3MouseEventsData
|
||||||
|
{
|
||||||
|
int m_numMouseEvents;
|
||||||
|
struct b3MouseEvent* m_mouseEvents;
|
||||||
|
};
|
||||||
|
|
||||||
struct b3ContactPointData
|
struct b3ContactPointData
|
||||||
{
|
{
|
||||||
//todo: expose some contact flags, such as telling which fields below are valid
|
//todo: expose some contact flags, such as telling which fields below are valid
|
||||||
@@ -531,6 +555,8 @@ enum b3ConfigureDebugVisualizerEnum
|
|||||||
COV_ENABLE_VR_RENDER_CONTROLLERS,
|
COV_ENABLE_VR_RENDER_CONTROLLERS,
|
||||||
COV_ENABLE_RENDERING,
|
COV_ENABLE_RENDERING,
|
||||||
COV_ENABLE_SYNC_RENDERING_INTERNAL,
|
COV_ENABLE_SYNC_RENDERING_INTERNAL,
|
||||||
|
COV_ENABLE_KEYBOARD_SHORTCUTS,
|
||||||
|
COV_ENABLE_MOUSE_PICKING,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum b3AddUserDebugItemEnum
|
enum b3AddUserDebugItemEnum
|
||||||
|
|||||||
@@ -3996,6 +3996,50 @@ static PyObject* pybullet_getKeyboardEvents(PyObject* self, PyObject* args, PyOb
|
|||||||
return keyEventsObj;
|
return keyEventsObj;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static PyObject* pybullet_getMouseEvents(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
|
{
|
||||||
|
b3SharedMemoryCommandHandle commandHandle;
|
||||||
|
int physicsClientId = 0;
|
||||||
|
b3PhysicsClientHandle sm = 0;
|
||||||
|
struct b3MouseEventsData mouseEventsData;
|
||||||
|
PyObject* mouseEventsObj = 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 = b3RequestMouseEventsCommandInit(sm);
|
||||||
|
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||||
|
b3GetMouseEventsData(sm, &mouseEventsData);
|
||||||
|
|
||||||
|
mouseEventsObj = PyTuple_New(mouseEventsData.m_numMouseEvents);
|
||||||
|
|
||||||
|
for (i = 0; i < mouseEventsData.m_numMouseEvents; i++)
|
||||||
|
{
|
||||||
|
PyObject* mouseEventObj = PyTuple_New(5);
|
||||||
|
PyTuple_SetItem(mouseEventObj,0, PyInt_FromLong(mouseEventsData.m_mouseEvents[i].m_eventType));
|
||||||
|
PyTuple_SetItem(mouseEventObj,1, PyFloat_FromDouble(mouseEventsData.m_mouseEvents[i].m_mousePosX));
|
||||||
|
PyTuple_SetItem(mouseEventObj,2, PyFloat_FromDouble(mouseEventsData.m_mouseEvents[i].m_mousePosY));
|
||||||
|
PyTuple_SetItem(mouseEventObj,3, PyInt_FromLong(mouseEventsData.m_mouseEvents[i].m_buttonIndex));
|
||||||
|
PyTuple_SetItem(mouseEventObj,4, PyInt_FromLong(mouseEventsData.m_mouseEvents[i].m_buttonState));
|
||||||
|
PyTuple_SetItem(mouseEventsObj,i,mouseEventObj);
|
||||||
|
|
||||||
|
}
|
||||||
|
return mouseEventsObj;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject* keywds)
|
static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
{
|
{
|
||||||
b3SharedMemoryCommandHandle commandHandle;
|
b3SharedMemoryCommandHandle commandHandle;
|
||||||
@@ -6756,7 +6800,10 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
"Set properties of the VR Camera such as its root transform "
|
"Set properties of the VR Camera such as its root transform "
|
||||||
"for teleporting or to track objects (camera inside a vehicle for example)."},
|
"for teleporting or to track objects (camera inside a vehicle for example)."},
|
||||||
{"getKeyboardEvents", (PyCFunction)pybullet_getKeyboardEvents, METH_VARARGS | METH_KEYWORDS,
|
{"getKeyboardEvents", (PyCFunction)pybullet_getKeyboardEvents, METH_VARARGS | METH_KEYWORDS,
|
||||||
"Get Keyboard events, keycode and state (KEY_IS_DOWN, KEY_WAS_TRIGGER, KEY_WAS_RELEASED)"},
|
"Get keyboard events, keycode and state (KEY_IS_DOWN, KEY_WAS_TRIGGERED, KEY_WAS_RELEASED)"},
|
||||||
|
|
||||||
|
{"getMouseEvents", (PyCFunction)pybullet_getMouseEvents, METH_VARARGS | METH_KEYWORDS,
|
||||||
|
"Get mouse events, event type and button state (KEY_IS_DOWN, KEY_WAS_TRIGGERED, KEY_WAS_RELEASED)"},
|
||||||
|
|
||||||
{"startStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS,
|
{"startStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS,
|
||||||
"Start logging of state, such as robot base position, orientation, joint positions etc. "
|
"Start logging of state, such as robot base position, orientation, joint positions etc. "
|
||||||
@@ -6923,6 +6970,8 @@ initpybullet(void)
|
|||||||
PyModule_AddIntConstant(m, "COV_ENABLE_VR_TELEPORTING", COV_ENABLE_VR_TELEPORTING);
|
PyModule_AddIntConstant(m, "COV_ENABLE_VR_TELEPORTING", COV_ENABLE_VR_TELEPORTING);
|
||||||
PyModule_AddIntConstant(m, "COV_ENABLE_RENDERING", COV_ENABLE_RENDERING);
|
PyModule_AddIntConstant(m, "COV_ENABLE_RENDERING", COV_ENABLE_RENDERING);
|
||||||
PyModule_AddIntConstant(m, "COV_ENABLE_VR_RENDER_CONTROLLERS", COV_ENABLE_VR_RENDER_CONTROLLERS);
|
PyModule_AddIntConstant(m, "COV_ENABLE_VR_RENDER_CONTROLLERS", COV_ENABLE_VR_RENDER_CONTROLLERS);
|
||||||
|
PyModule_AddIntConstant(m, "COV_ENABLE_KEYBOARD_SHORTCUTS", COV_ENABLE_KEYBOARD_SHORTCUTS);
|
||||||
|
PyModule_AddIntConstant(m, "COV_ENABLE_MOUSE_PICKING", COV_ENABLE_MOUSE_PICKING);
|
||||||
|
|
||||||
|
|
||||||
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
||||||
|
|||||||
2
setup.py
2
setup.py
@@ -419,7 +419,7 @@ else:
|
|||||||
|
|
||||||
setup(
|
setup(
|
||||||
name = 'pybullet',
|
name = 'pybullet',
|
||||||
version='1.1.7',
|
version='1.1.8',
|
||||||
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
|
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
|
||||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||||
url='https://github.com/bulletphysics/bullet3',
|
url='https://github.com/bulletphysics/bullet3',
|
||||||
|
|||||||
Reference in New Issue
Block a user