Add shared memory API for setting shadow and light source distance.
This commit is contained in:
@@ -1256,6 +1256,24 @@ void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle
|
|||||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR;
|
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command);
|
||||||
|
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||||
|
command->m_requestPixelDataArguments.m_lightDistance = lightDistance;
|
||||||
|
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command);
|
||||||
|
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||||
|
command->m_requestPixelDataArguments.m_hasShadow = hasShadow;
|
||||||
|
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW;
|
||||||
|
}
|
||||||
|
|
||||||
void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16])
|
void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16])
|
||||||
{
|
{
|
||||||
b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
|
b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
|
||||||
|
|||||||
@@ -98,6 +98,8 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command,
|
|||||||
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
|
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
|
||||||
void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]);
|
void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]);
|
||||||
void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]);
|
void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]);
|
||||||
|
void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance);
|
||||||
|
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow);
|
||||||
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
|
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
|
||||||
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
||||||
|
|
||||||
|
|||||||
@@ -89,10 +89,10 @@ protected:
|
|||||||
|
|
||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1.233281;
|
float dist = 4;
|
||||||
float pitch = 193;
|
float pitch = 193;
|
||||||
float yaw = 25;
|
float yaw = 25;
|
||||||
float targetPos[3]={0.103042,-0.469102,0.631005};//-3,2.8,-2.5};
|
float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -242,7 +242,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
{
|
{
|
||||||
case CMD_LOAD_URDF:
|
case CMD_LOAD_URDF:
|
||||||
{
|
{
|
||||||
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "torus/torus_with_separate_plane.urdf");
|
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf");
|
||||||
//setting the initial position, orientation and other arguments are optional
|
//setting the initial position, orientation and other arguments are optional
|
||||||
double startPosX = 0;
|
double startPosX = 0;
|
||||||
static double startPosY = 0;
|
static double startPosY = 0;
|
||||||
@@ -481,6 +481,22 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case CMD_SET_SHADOW:
|
||||||
|
{
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||||
|
float viewMatrix[16];
|
||||||
|
float projectionMatrix[16];
|
||||||
|
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||||
|
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||||
|
|
||||||
|
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
|
||||||
|
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
|
||||||
|
bool hasShadow = true;
|
||||||
|
b3RequestCameraImageSetShadow(commandHandle, hasShadow);
|
||||||
|
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
b3Error("Unknown buttonId");
|
b3Error("Unknown buttonId");
|
||||||
@@ -556,6 +572,7 @@ void PhysicsClientExample::createButtons()
|
|||||||
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
|
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
|
||||||
createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
|
createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
|
||||||
createButton("Save World",CMD_SAVE_WORLD, isTrigger);
|
createButton("Save World",CMD_SAVE_WORLD, isTrigger);
|
||||||
|
createButton("Set Shadow",CMD_SET_SHADOW, isTrigger);
|
||||||
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
|
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
|
||||||
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
||||||
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
||||||
|
|||||||
@@ -1425,6 +1425,16 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
{
|
{
|
||||||
m_data->m_visualConverter.setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]);
|
m_data->m_visualConverter.setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) != 0)
|
||||||
|
{
|
||||||
|
m_data->m_visualConverter.setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0)
|
||||||
|
{
|
||||||
|
m_data->m_visualConverter.setShadow(clientCmd.m_requestPixelDataArguments.m_hasShadow);
|
||||||
|
}
|
||||||
|
|
||||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -140,6 +140,8 @@ struct RequestPixelDataArgs
|
|||||||
int m_pixelHeight;
|
int m_pixelHeight;
|
||||||
float m_lightDirection[3];
|
float m_lightDirection[3];
|
||||||
float m_lightColor[3];
|
float m_lightColor[3];
|
||||||
|
float m_lightDistance;
|
||||||
|
bool m_hasShadow;
|
||||||
};
|
};
|
||||||
|
|
||||||
enum EnumRequestPixelDataUpdateFlags
|
enum EnumRequestPixelDataUpdateFlags
|
||||||
@@ -148,6 +150,8 @@ enum EnumRequestPixelDataUpdateFlags
|
|||||||
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2,
|
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2,
|
||||||
REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4,
|
REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4,
|
||||||
REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8,
|
REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8,
|
||||||
|
REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE=16,
|
||||||
|
REQUEST_PIXEL_ARGS_SET_SHADOW=32,
|
||||||
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
|
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -40,6 +40,7 @@ enum EnumSharedMemoryClientCommand
|
|||||||
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
||||||
CMD_UPDATE_VISUAL_SHAPE,
|
CMD_UPDATE_VISUAL_SHAPE,
|
||||||
CMD_LOAD_TEXTURE,
|
CMD_LOAD_TEXTURE,
|
||||||
|
CMD_SET_SHADOW,
|
||||||
CMD_USER_DEBUG_DRAW,
|
CMD_USER_DEBUG_DRAW,
|
||||||
|
|
||||||
//don't go beyond this command!
|
//don't go beyond this command!
|
||||||
|
|||||||
@@ -90,7 +90,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB),
|
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB),
|
||||||
m_hasLightDirection(false),
|
m_hasLightDirection(false),
|
||||||
m_hasLightColor(false),
|
m_hasLightColor(false),
|
||||||
m_hasShadow(true)
|
m_hasShadow(false)
|
||||||
{
|
{
|
||||||
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
||||||
m_shadowBuffer.resize(m_swWidth*m_swHeight);
|
m_shadowBuffer.resize(m_swWidth*m_swHeight);
|
||||||
|
|||||||
Reference in New Issue
Block a user