Add shared memory API for setting shadow and light source distance.
This commit is contained in:
@@ -89,10 +89,10 @@ protected:
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 1.233281;
|
||||
float pitch = 193;
|
||||
float yaw = 25;
|
||||
float targetPos[3]={0.103042,-0.469102,0.631005};//-3,2.8,-2.5};
|
||||
float dist = 4;
|
||||
float pitch = 193;
|
||||
float yaw = 25;
|
||||
float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
|
||||
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:
|
||||
{
|
||||
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
|
||||
double startPosX = 0;
|
||||
static double startPosY = 0;
|
||||
@@ -481,6 +481,22 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
}
|
||||
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:
|
||||
{
|
||||
b3Error("Unknown buttonId");
|
||||
@@ -556,6 +572,7 @@ void PhysicsClientExample::createButtons()
|
||||
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
|
||||
createButton("Load SDF",CMD_LOAD_SDF, 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("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
||||
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
||||
|
||||
Reference in New Issue
Block a user