Expose a better API to allow any render engine to be used for the physics simulation when loading URDF/SDF files.

See bullet3/examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.h
Give the kuka_iiwa/model.urdf some blue color, not just orange, to mimick the original a bit better
Preparation for the CMD_CAMERA_IMAGE_COMPLETED command, to expose a virtual camera to the robotics API
This commit is contained in:
erwin coumans
2016-05-19 18:37:15 -07:00
parent f4775c360f
commit 2fc0358750
23 changed files with 575 additions and 437 deletions

View File

@@ -235,6 +235,16 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
break;
}
case CMD_REQUEST_CAMERA_IMAGE_DATA:
{
///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
//void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight);
//void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
break;
}
case CMD_CREATE_BOX_COLLISION_SHAPE:
{
b3SharedMemoryCommandHandle commandHandle = b3CreateBoxShapeCommandInit(m_physicsClientHandle);
@@ -429,6 +439,7 @@ void PhysicsClientExample::createButtons()
m_guiHelper->getParameterInterface()->removeAllParameters();
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
if (m_options!=eCLIENTEXAMPLE_SERVER)
@@ -551,6 +562,16 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
{
//b3Printf("bla\n");
}
if (statusType ==CMD_CAMERA_IMAGE_COMPLETED)
{
b3Printf("Camera image OK\n");
}
if (statusType == CMD_CAMERA_IMAGE_FAILED)
{
b3Printf("Camera image FAILED\n");
}
if (statusType == CMD_URDF_LOADING_COMPLETED)
{
int bodyIndex = b3GetStatusBodyIndex(status);

View File

@@ -416,6 +416,18 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
break;
}
case CMD_CAMERA_IMAGE_COMPLETED:
{
b3Printf("Camera image OK\n");
break;
}
case CMD_CAMERA_IMAGE_FAILED:
{
b3Printf("Camera image FAILED\n");
break;
}
default: {
b3Error("Unknown server status\n");

View File

@@ -4,6 +4,7 @@
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
#include "../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h"
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
@@ -691,7 +692,9 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
return false;
}
BulletURDFImporter u2b(m_data->m_guiHelper);
DefaultVisualShapeConverter visualConverter(m_data->m_guiHelper);
BulletURDFImporter u2b(m_data->m_guiHelper, &visualConverter);
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
@@ -964,7 +967,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
case CMD_REQUEST_CAMERA_IMAGE_DATA:
{
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED;
hasStatus = true;
break;
}

View File

@@ -49,7 +49,9 @@ enum EnumSharedMemoryServerStatus
CMD_DEBUG_LINES_OVERFLOW_FAILED,
CMD_DESIRED_STATE_RECEIVED_COMPLETED,
CMD_STEP_FORWARD_SIMULATION_COMPLETED,
CMD_RESET_SIMULATION_COMPLETED,
CMD_RESET_SIMULATION_COMPLETED,
CMD_CAMERA_IMAGE_COMPLETED,
CMD_CAMERA_IMAGE_FAILED,
CMD_INVALID_STATUS,
CMD_MAX_SERVER_COMMANDS
};

View File

@@ -46,9 +46,9 @@ files {
"../Importers/ImportURDFDemo/MyMultiBodyCreator.h",
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../Importers/ImportURDFDemo/BulletUrdfImporter.h",
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp",
"../Importers/ImportURDFDemo/DefaultVisualShapeConverter.h",
"../Importers/ImportURDFDemo/UrdfParser.cpp",
"../Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../Importers/ImportURDFDemo/BulletUrdfImporter.h",
"../Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../Importers/ImportURDFDemo/UrdfParser.cpp",
"../Importers/ImportURDFDemo/UrdfParser.h",