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

@@ -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;
}