support changeVisualShape(rgbaColor) through GraphicsServer/Client
support getCameraInfo through GraphicsServer/Client
This commit is contained in:
@@ -109,7 +109,7 @@ public:
|
||||
}
|
||||
case GFX_CMD_SET_VISUALIZER_FLAG:
|
||||
{
|
||||
if (clientCmd.m_visualizerFlagCommand.m_visualizerFlag!=COV_ENABLE_RENDERING)
|
||||
if (clientCmd.m_visualizerFlagCommand.m_visualizerFlag != COV_ENABLE_RENDERING)
|
||||
{
|
||||
//printf("clientCmd.m_visualizerFlag.m_visualizerFlag: %d, clientCmd.m_visualizerFlag.m_enable %d\n",
|
||||
// clientCmd.m_visualizerFlagCommand.m_visualizerFlag, clientCmd.m_visualizerFlagCommand.m_enable);
|
||||
@@ -155,8 +155,8 @@ public:
|
||||
int verticesSlot = 0;
|
||||
int indicesSlot = 1;
|
||||
serverStatusOut.m_type = GFX_CMD_REGISTER_GRAPHICS_SHAPE_FAILED;
|
||||
const float* vertices = (const float*) &m_dataSlots[verticesSlot][0];
|
||||
const int* indices = (const int*) &m_dataSlots[indicesSlot][0];
|
||||
const float* vertices = (const float*)&m_dataSlots[verticesSlot][0];
|
||||
const int* indices = (const int*)&m_dataSlots[indicesSlot][0];
|
||||
int numVertices = clientCmd.m_registerGraphicsShapeCommand.m_numVertices;
|
||||
int numIndices = clientCmd.m_registerGraphicsShapeCommand.m_numIndices;
|
||||
int primitiveType = clientCmd.m_registerGraphicsShapeCommand.m_primitiveType;
|
||||
@@ -176,7 +176,7 @@ public:
|
||||
clientCmd.m_registerGraphicsInstanceCommand.m_scaling);
|
||||
serverStatusOut.m_registerGraphicsInstanceStatus.m_graphicsInstanceId = graphicsInstanceId;
|
||||
serverStatusOut.m_type = GFX_CMD_REGISTER_GRAPHICS_INSTANCE_COMPLETED;
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
case GFX_CMD_SYNCHRONIZE_TRANSFORMS:
|
||||
@@ -198,8 +198,37 @@ public:
|
||||
m_app->m_renderer->removeGraphicsInstance(clientCmd.m_removeGraphicsInstanceCommand.m_graphicsUid);
|
||||
break;
|
||||
}
|
||||
case GFX_CMD_CHANGE_RGBA_COLOR:
|
||||
{
|
||||
m_guiHelper->changeRGBAColor(clientCmd.m_changeRGBAColorCommand.m_graphicsUid, clientCmd.m_changeRGBAColorCommand.m_rgbaColor);
|
||||
break;
|
||||
}
|
||||
case GFX_CMD_GET_CAMERA_INFO:
|
||||
{
|
||||
serverStatusOut.m_type = GFX_CMD_GET_CAMERA_INFO_FAILED;
|
||||
|
||||
if (m_guiHelper->getCameraInfo(
|
||||
&serverStatusOut.m_getCameraInfoStatus.width,
|
||||
&serverStatusOut.m_getCameraInfoStatus.height,
|
||||
serverStatusOut.m_getCameraInfoStatus.viewMatrix,
|
||||
serverStatusOut.m_getCameraInfoStatus.projectionMatrix,
|
||||
serverStatusOut.m_getCameraInfoStatus.camUp,
|
||||
serverStatusOut.m_getCameraInfoStatus.camForward,
|
||||
serverStatusOut.m_getCameraInfoStatus.hor,
|
||||
serverStatusOut.m_getCameraInfoStatus.vert,
|
||||
&serverStatusOut.m_getCameraInfoStatus.yaw,
|
||||
&serverStatusOut.m_getCameraInfoStatus.pitch,
|
||||
&serverStatusOut.m_getCameraInfoStatus.camDist,
|
||||
serverStatusOut.m_getCameraInfoStatus.camTarget))
|
||||
{
|
||||
serverStatusOut.m_type = GFX_CMD_GET_CAMERA_INFO_COMPLETED;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
printf("unsupported command:%d\n", clientCmd.m_type);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
|
||||
@@ -106,6 +106,28 @@ struct GraphicsRemoveInstanceCommand
|
||||
int m_graphicsUid;
|
||||
};
|
||||
|
||||
struct GraphicsChangeRGBAColorCommand
|
||||
{
|
||||
int m_graphicsUid;
|
||||
double m_rgbaColor[4];
|
||||
};
|
||||
|
||||
struct GraphicsGetCameraInfoStatus
|
||||
{
|
||||
int width;
|
||||
int height;
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
float camUp[3];
|
||||
float camForward[3];
|
||||
float hor[3];
|
||||
float vert[3];
|
||||
float yaw;
|
||||
float pitch;
|
||||
float camDist;
|
||||
float camTarget[3];
|
||||
};
|
||||
|
||||
|
||||
struct GraphicsSharedMemoryCommand
|
||||
{
|
||||
@@ -127,6 +149,7 @@ struct GraphicsSharedMemoryCommand
|
||||
struct GraphicsRegisterGraphicsInstanceCommand m_registerGraphicsInstanceCommand;
|
||||
struct GraphicsSyncTransformsCommand m_syncTransformsCommand;
|
||||
struct GraphicsRemoveInstanceCommand m_removeGraphicsInstanceCommand;
|
||||
struct GraphicsChangeRGBAColorCommand m_changeRGBAColorCommand;
|
||||
};
|
||||
};
|
||||
|
||||
@@ -151,6 +174,7 @@ struct GraphicsSharedMemoryStatus
|
||||
struct GraphicsRegisterTextureStatus m_registerTextureStatus;
|
||||
struct GraphicsRegisterGraphicsShapeStatus m_registerGraphicsShapeStatus;
|
||||
struct GraphicsRegisterGraphicsInstanceStatus m_registerGraphicsInstanceStatus;
|
||||
struct GraphicsGetCameraInfoStatus m_getCameraInfoStatus;
|
||||
};
|
||||
};
|
||||
|
||||
|
||||
@@ -20,6 +20,8 @@ enum EnumGraphicsSharedMemoryClientCommand
|
||||
GFX_CMD_SYNCHRONIZE_TRANSFORMS,
|
||||
GFX_CMD_REMOVE_ALL_GRAPHICS_INSTANCES,
|
||||
GFX_CMD_REMOVE_SINGLE_GRAPHICS_INSTANCE,
|
||||
GFX_CMD_CHANGE_RGBA_COLOR,
|
||||
GFX_CMD_GET_CAMERA_INFO,
|
||||
//don't go beyond this command!
|
||||
GFX_CMD_MAX_CLIENT_COMMANDS,
|
||||
};
|
||||
@@ -36,6 +38,8 @@ enum EnumGraphicsSharedMemoryServerStatus
|
||||
GFX_CMD_REGISTER_GRAPHICS_SHAPE_FAILED,
|
||||
GFX_CMD_REGISTER_GRAPHICS_INSTANCE_COMPLETED,
|
||||
GFX_CMD_REGISTER_GRAPHICS_INSTANCE_FAILED,
|
||||
GFX_CMD_GET_CAMERA_INFO_COMPLETED,
|
||||
GFX_CMD_GET_CAMERA_INFO_FAILED,
|
||||
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
||||
GFX_CMD_MAX_SERVER_COMMANDS
|
||||
};
|
||||
|
||||
@@ -240,6 +240,45 @@ void RemoteGUIHelper::createRigidBodyGraphicsObject(btRigidBody* body, const btV
|
||||
printf("createRigidBodyGraphicsObject\n");
|
||||
}
|
||||
|
||||
bool RemoteGUIHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3], float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
|
||||
{
|
||||
GraphicsSharedMemoryCommand* cmd = m_data->getAvailableSharedMemoryCommand();
|
||||
if (cmd)
|
||||
{
|
||||
|
||||
cmd->m_updateFlags = 0;
|
||||
cmd->m_type = GFX_CMD_GET_CAMERA_INFO;
|
||||
m_data->submitClientCommand(*cmd);
|
||||
}
|
||||
const GraphicsSharedMemoryStatus* status = 0;
|
||||
while ((status = m_data->processServerStatus()) == 0)
|
||||
{
|
||||
}
|
||||
if (status->m_type == GFX_CMD_GET_CAMERA_INFO_COMPLETED)
|
||||
{
|
||||
*width = status->m_getCameraInfoStatus.width;
|
||||
*height = status->m_getCameraInfoStatus.height;
|
||||
for (int i = 0; i < 16; i++)
|
||||
{
|
||||
viewMatrix[i] = status->m_getCameraInfoStatus.viewMatrix[i];
|
||||
projectionMatrix[i] = status->m_getCameraInfoStatus.projectionMatrix[i];
|
||||
}
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
camUp[i] = status->m_getCameraInfoStatus.camUp[i];
|
||||
camForward[i] = status->m_getCameraInfoStatus.camForward[i];
|
||||
hor[i] = status->m_getCameraInfoStatus.hor[i];
|
||||
vert[i] = status->m_getCameraInfoStatus.vert[i];
|
||||
camTarget[i] = status->m_getCameraInfoStatus.camTarget[i];
|
||||
}
|
||||
*yaw = status->m_getCameraInfoStatus.yaw;
|
||||
*pitch = status->m_getCameraInfoStatus.pitch;
|
||||
*camDist = status->m_getCameraInfoStatus.camDist;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void RemoteGUIHelper::createCollisionObjectGraphicsObject(btCollisionObject* body, const btVector3& color)
|
||||
{
|
||||
if (body->getUserIndex() < 0)
|
||||
@@ -487,6 +526,22 @@ void RemoteGUIHelper::removeGraphicsInstance(int graphicsUid)
|
||||
}
|
||||
void RemoteGUIHelper::changeRGBAColor(int instanceUid, const double rgbaColor[4])
|
||||
{
|
||||
GraphicsSharedMemoryCommand* cmd = m_data->getAvailableSharedMemoryCommand();
|
||||
if (cmd)
|
||||
{
|
||||
cmd->m_updateFlags = 0;
|
||||
cmd->m_type = GFX_CMD_CHANGE_RGBA_COLOR;
|
||||
cmd->m_changeRGBAColorCommand.m_graphicsUid = instanceUid;
|
||||
for (int i = 0; i < 4; i++)
|
||||
{
|
||||
cmd->m_changeRGBAColorCommand.m_rgbaColor[i] = rgbaColor[i];
|
||||
}
|
||||
m_data->submitClientCommand(*cmd);
|
||||
const GraphicsSharedMemoryStatus* status = 0;
|
||||
while ((status = m_data->processServerStatus()) == 0)
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
||||
Common2dCanvasInterface* RemoteGUIHelper::get2dCanvasInterface()
|
||||
{
|
||||
|
||||
@@ -20,6 +20,8 @@ struct RemoteGUIHelper : public GUIHelperInterface
|
||||
|
||||
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);
|
||||
|
||||
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3], float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const;
|
||||
|
||||
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld);
|
||||
virtual void syncPhysicsToGraphics2(const class btDiscreteDynamicsWorld* rbWorld);
|
||||
virtual void syncPhysicsToGraphics2(const GUISyncPosition* positions, int numPositions);
|
||||
|
||||
@@ -32,7 +32,8 @@ def getRayFromTo(mouseX, mouseY):
|
||||
return rayFrom, rayTo
|
||||
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
cid = p.connect(p.SHARED_MEMORY_GUI)
|
||||
#cid = p.connect(p.GUI)
|
||||
if (cid < 0):
|
||||
p.connect(p.GUI)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
@@ -82,6 +83,7 @@ colors = [[1, 0, 0, 1], [0, 1, 0, 1], [0, 0, 1, 1], [1, 1, 1, 1]]
|
||||
currentColor = 0
|
||||
|
||||
while (1):
|
||||
p.getDebugVisualizerCamera()
|
||||
mouseEvents = p.getMouseEvents()
|
||||
for e in mouseEvents:
|
||||
if ((e[0] == 2) and (e[3] == 0) and (e[4] & p.KEY_WAS_TRIGGERED)):
|
||||
|
||||
@@ -3,7 +3,7 @@ import math
|
||||
import time
|
||||
dt = 1./240.
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.connect(p.SHARED_MEMORY_GUI)
|
||||
p.loadURDF("r2d2.urdf",[0,0,1])
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
Reference in New Issue
Block a user