Merge pull request #1518 from erwincoumans/master

small refactor of LinkVisualShapesConverter / TinyRendererVisualShape…
This commit is contained in:
erwincoumans 2018-01-17 14:30:17 -08:00 committed by GitHub
commit 3e873feac0
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
42 changed files with 688 additions and 283 deletions

View File

@ -10,8 +10,8 @@ INCLUDE_DIRECTORIES(
SET(BulletRobotics_SRCS
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp

View File

@ -143,11 +143,10 @@ SET(BulletExampleBrowser_SRCS
../TinyRenderer/tgaimage.cpp
../TinyRenderer/our_gl.cpp
../TinyRenderer/TinyRenderer.cpp
../SharedMemory/TinyRendererVisualShapeConverter.cpp
../SharedMemory/TinyRendererVisualShapeConverter.h
../SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../SharedMemory/IKTrajectoryHelper.cpp
../SharedMemory/IKTrajectoryHelper.h
../SharedMemory/PhysicsServer.cpp
../SharedMemory/PhysicsClientSharedMemory.cpp
../SharedMemory/PhysicsClientSharedMemory_C_API.cpp

View File

@ -110,8 +110,8 @@ project "App_BulletExampleBrowser"
"../SharedMemory/PhysicsServerCommandProcessor.cpp",
"../SharedMemory/PhysicsServerCommandProcessor.h",
"../SharedMemory/b3PluginManager.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../SharedMemory/TinyRendererVisualShapeConverter.h",
"../SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../SharedMemory/SharedMemoryCommands.h",
"../SharedMemory/SharedMemoryPublic.h",
"../MultiThreading/MultiThreadingExample.cpp",

View File

@ -21,7 +21,7 @@
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
#include "../ImportMeshUtility/b3ImportMeshUtility.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionShapes/btCompoundShape.h"
#include "BulletCollision/CollisionShapes/btStaticPlaneShape.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
@ -184,7 +184,7 @@ struct MyMJCFDefaults
struct BulletMJCFImporterInternalData
{
GUIHelperInterface* m_guiHelper;
struct LinkVisualShapesConverter* m_customVisualShapesConverter;
struct UrdfRenderingInterface* m_customVisualShapesConverter;
char m_pathPrefix[1024];
std::string m_sourceFileName; // with path
@ -1419,7 +1419,7 @@ struct BulletMJCFImporterInternalData
};
BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, int flags)
BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, int flags)
{
m_data = new BulletMJCFImporterInternalData();
m_data->m_guiHelper = helper;
@ -2277,7 +2277,7 @@ void BulletMJCFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex,
if (m_data->m_customVisualShapesConverter)
{
const UrdfLink* link = m_data->getLink(m_data->m_activeModel, urdfIndex);
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,inertialFrame, link, 0, colObj, objectIndex);
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,inertialFrame, link, 0, colObj->getBroadphaseHandle()->getUid(), objectIndex);
}
}

View File

@ -2,7 +2,7 @@
#define BULLET_MJCF_IMPORTER_H
#include "../ImportURDFDemo/URDFImporterInterface.h"
#include "../ImportURDFDemo/LinkVisualShapesConverter.h"
#include "../ImportURDFDemo/UrdfRenderingInterface.h"
struct MJCFErrorLogger
@ -27,7 +27,7 @@ class BulletMJCFImporter : public URDFImporterInterface
void convertURDFToVisualShapeInternal(const struct UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<struct GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MJCFURDFTexture>& texturesOut) const;
public:
BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, int flags);
BulletMJCFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, int flags);
virtual ~BulletMJCFImporter();
virtual bool parseMJCFString(const char* xmlString, MJCFErrorLogger* logger);

View File

@ -51,7 +51,7 @@ ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
mutable btAlignedObjectArray<btTriangleMesh*> m_allocatedMeshInterfaces;
btHashMap<btHashPtr, UrdfCollision> m_bulletCollisionShape2UrdfCollision;
LinkVisualShapesConverter* m_customVisualShapesConverter;
UrdfRenderingInterface* m_customVisualShapesConverter;
bool m_enableTinyRenderer;
int m_flags;
@ -82,7 +82,7 @@ void BulletURDFImporter::printTree()
// btAssert(0);
}
BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling, int flags)
BulletURDFImporter::BulletURDFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, double globalScaling, int flags)
{
m_data = new BulletURDFInternalData;
m_data->setGlobalScaling(globalScaling);
@ -1248,7 +1248,7 @@ void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex,
UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex);
if (linkPtr)
{
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, *linkPtr, &model, colObj, bodyUniqueId);
m_data->m_customVisualShapesConverter->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, *linkPtr, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId);
}
}
}

View File

@ -3,7 +3,7 @@
#include "URDFImporterInterface.h"
#include "LinkVisualShapesConverter.h"
#include "UrdfRenderingInterface.h"
struct BulletURDFTexture
{
@ -23,7 +23,7 @@ class BulletURDFImporter : public URDFImporterInterface
public:
BulletURDFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter, double globalScaling=1, int flags=0);
BulletURDFImporter(struct GUIHelperInterface* helper, UrdfRenderingInterface* customConverter, double globalScaling=1, int flags=0);
virtual ~BulletURDFImporter();

View File

@ -1,17 +0,0 @@
#ifndef LINK_VISUAL_SHAPES_CONVERTER_H
#define LINK_VISUAL_SHAPES_CONVERTER_H
struct UrdfLink;
struct UrdfModel;
class btTransform;
class btCollisionObject;
struct LinkVisualShapesConverter
{
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, class btCollisionObject* colShape, int objectIndex) =0;
virtual void removeVisualShape(class btCollisionObject* colObj)=0;
};
#endif //LINK_VISUAL_SHAPES_CONVERTER_H

View File

@ -4,7 +4,6 @@
#include <string>
///See audio_source element in http://sdformat.org/spec?ver=1.6&elem=link
struct SDFAudioSource
{

View File

@ -566,7 +566,9 @@ void ConvertURDF2BulletInternal(
}
} else
{
//u2b.convertLinkVisualShapes2(urdfLinkIndex,urdfIndex,pathPrefix,localInertialFrame,compoundShape);
int mbLinkIndex =cache.getMbIndexFromUrdfIndex(urdfLinkIndex);
//u2b.convertLinkVisualShapes2(mbLinkIndex, urdfLinkIndex, pathPrefix, localInertialFrame, col, u2b.getBodyUniqueId());
u2b.convertLinkVisualShapes2(-1,urdfLinkIndex,pathPrefix,localInertialFrame,linkRigidBody,u2b.getBodyUniqueId());
}
}

View File

@ -1,6 +1,7 @@
#ifndef URDF_JOINT_TYPES_H
#define URDF_JOINT_TYPES_H
#include "LinearMath/btScalar.h"
enum UrdfJointTypes
{
@ -11,7 +12,6 @@ enum UrdfJointTypes
URDFPlanarJoint,
URDFFixedJoint,
};
#include "LinearMath/btScalar.h"
enum URDF_LinkContactFlags
{

View File

@ -6,9 +6,9 @@
#include "LinearMath/btHashMap.h"
#include "URDFJointTypes.h"
#include "SDFAudioTypes.h"
#include <string>
#define btArray btAlignedObjectArray
#include <string>
struct ErrorLogger
{

View File

@ -0,0 +1,96 @@
#ifndef URDF_RENDERING_INTERFACE_H
#define URDF_RENDERING_INTERFACE_H
///UrdfLink and UrdfModel are the main URDF structures to define a robot
struct UrdfLink;
struct UrdfModel;
///btTransform is a position and 3x3 matrix, as defined in Bullet/src/LinearMath/btTransform
class btTransform;
///UrdfRenderingInterface is a simple rendering interface, mainly for URDF-based robots.
///There is an implementation in
///bullet3\examples\SharedMemory\plugins\tinyRendererPlugin\TinyRendererVisualShapeConverter.cpp
struct UrdfRenderingInterface
{
///given a URDF link, convert all visual shapes into internal renderer (loading graphics meshes, textures etc)
///use the shapeUid as a unique identified to remove it
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex) =0;
///remove a visual shapes, based on the shape unique id (shapeUid)
virtual void removeVisualShape(int shapeUid)=0;
///update the world transform + scaling of the visual shape, using the shapeUid
virtual void syncTransform(int shapeUid, const class btTransform& worldTransform, const class btVector3& localScaling)=0;
///return the number of visual shapes, for a particular body unique id
virtual int getNumVisualShapes(int bodyUniqueId)=0;
///return the visual shape information, for a particular body unique id and 'shape index'
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData)=0;
///change the RGBA color for a body unique id and link index
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, const double rgbaColor[4])=0;
///pick the up-axis, either Y (1) or Z (2)
virtual void setUpAxis(int axis)=0;
///compute the view matrix based on those parameters
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)=0;
///clear the render buffer with a particular color.
virtual void clearBuffers(struct TGAColor& clearColor)=0;
///remove all visual shapes.
virtual void resetAll()=0;
///return the frame buffer width and height for the renderer
virtual void getWidthAndHeight(int& width, int& height)=0;
///set the frame buffer width and height for the renderer
virtual void setWidthAndHeight(int width, int height)=0;
///set the light direction, in world coordinates
virtual void setLightDirection(float x, float y, float z)=0;
///set the ambient light color, in world coordinates
virtual void setLightColor(float x, float y, float z)=0;
///set the light distance
virtual void setLightDistance(float dist)=0;
///set the light ambient coefficient
virtual void setLightAmbientCoeff(float ambientCoeff)=0;
///set the light diffuse coefficient
virtual void setLightDiffuseCoeff(float diffuseCoeff)=0;
///set the light specular coefficient
virtual void setLightSpecularCoeff(float specularCoeff)=0;
///enable or disable rendering of shadows
virtual void setShadow(bool hasShadow)=0;
///some undocumented flags for experimentation (todo: document)
virtual void setFlags(int flags)=0;
///provide the image pixels as a part of a stream.
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)=0;
///render an image, using some arbitraty view and projection matrix
virtual void render()=0;
///render an image using the provided view and projection matrix
virtual void render(const float viewMat[16], const float projMat[16])=0;
///load a texture from file, in png or other popular/supported format
virtual int loadTextureFile(const char* filename)=0;
///register a texture using an in-memory pixel buffer of a given width and height
virtual int registerTexture(unsigned char* texels, int width, int height)=0;
///select a given texture for some visual shape.
virtual void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)=0;
};
#endif //LINK_VISUAL_SHAPES_CONVERTER_H

View File

@ -17,8 +17,8 @@ SET(RobotSimulator_SRCS
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp

View File

@ -32,8 +32,8 @@ myfiles =
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../../examples/TinyRenderer/geometry.cpp",
"../../examples/TinyRenderer/model.cpp",
"../../examples/TinyRenderer/tgaimage.cpp",

View File

@ -36,9 +36,9 @@ SET(SharedMemory_SRCS
SharedMemoryCommandProcessor.h
PhysicsServerCommandProcessor.cpp
PhysicsServerCommandProcessor.h
TinyRendererVisualShapeConverter.cpp
TinyRendererVisualShapeConverter.h
SharedMemoryCommands.h
plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
SharedMemoryCommands.h
SharedMemoryPublic.h
b3PluginManager.cpp
../TinyRenderer/geometry.cpp

View File

@ -5,7 +5,7 @@
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
#include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
#include "TinyRendererVisualShapeConverter.h"
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
@ -47,6 +47,12 @@
#include "plugins/vrSyncPlugin/vrSyncPlugin.h"
#endif
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
#include "plugins/tinyRendererPlugin/tinyRendererPlugin.h"
#endif
#ifdef B3_ENABLE_TINY_AUDIO
#include "../TinyAudio/b3SoundEngine.h"
#endif
@ -1564,7 +1570,7 @@ struct PhysicsServerCommandProcessorInternalData
btVector3 m_hitPos;
btScalar m_oldPickingDist;
bool m_prevCanSleep;
TinyRendererVisualShapeConverter m_visualConverter;
#ifdef B3_ENABLE_TINY_AUDIO
b3SoundEngine m_soundEngine;
#endif
@ -1598,14 +1604,16 @@ struct PhysicsServerCommandProcessorInternalData
m_pickingMultiBodyPoint2Point(0)
{
{
//register static plugins:
#ifdef STATIC_LINK_VR_PLUGIN
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0);
m_pluginManager.registerStaticLinkedPlugin("vrSyncPlugin", initPlugin_vrSyncPlugin, exitPlugin_vrSyncPlugin, executePluginCommand_vrSyncPlugin,preTickPluginCallback_vrSyncPlugin,0,0);
#endif //STATIC_LINK_VR_PLUGIN
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin,0,0,getRenderInterface_tinyRendererPlugin);
m_pluginManager.selectPluginRenderer(renderPluginId);
#endif
}
m_vrControllerEvents.init();
@ -2120,7 +2128,10 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
//UrdfVisual vis;
//link.m_visualArray.push_back(vis);
//UrdfLink*const* linkPtr = model.m_links.getAtIndex(urdfIndex);
m_data->m_visualConverter.convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, &link, &model, colObj, bodyUniqueId);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->convertVisualShapes(linkIndex,pathPrefix,localInertiaFrame, &link, &model, colObj->getBroadphaseHandle()->getUid(), bodyUniqueId);
}
}
virtual void setBodyUniqueId(int bodyId)
{
@ -2704,7 +2715,7 @@ bool PhysicsServerCommandProcessor::loadMjcf(const char* fileName, char* bufferS
m_data->m_sdfRecentLoadedBodies.clear();
BulletMJCFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, flags);
BulletMJCFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), flags);
bool useFixedBase = false;
MyMJCFLogger2 logger;
@ -2727,7 +2738,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
m_data->m_sdfRecentLoadedBodies.clear();
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling, flags);
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
bool forceFixedBase = false;
@ -2759,7 +2770,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling, flags);
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
@ -3076,15 +3087,21 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
if ((clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) &&
(clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0)
{
m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
clientCmd.m_requestPixelDataArguments.m_pixelHeight);
}
}
int flags = 0;
if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_FLAGS)
{
flags = clientCmd.m_requestPixelDataArguments.m_flags;
}
m_data->m_visualConverter.setFlags(flags);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->setFlags(flags);
}
int numTotalPixels = width*height;
int numRemainingPixels = numTotalPixels - startPixelIndex;
@ -3158,82 +3175,92 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
}
if (!handled)
{
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
if (m_data->m_pluginManager.getRenderInterface())
{
// printf("-------------------------------\nRendering\n");
if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
{
// printf("-------------------------------\nRendering\n");
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) != 0)
{
m_data->m_visualConverter.setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) != 0)
{
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!=0));
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) != 0)
{
m_data->m_visualConverter.setLightAmbientCoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) != 0)
{
m_data->m_visualConverter.setLightDiffuseCoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) != 0)
{
m_data->m_visualConverter.setLightSpecularCoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
{
m_data->m_visualConverter.render(
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
} else
{
b3OpenGLVisualizerCameraInfo tmpCamResult;
bool result = this->m_data->m_guiHelper->getCameraInfo(
&tmpCamResult.m_width,
&tmpCamResult.m_height,
tmpCamResult.m_viewMatrix,
tmpCamResult.m_projectionMatrix,
tmpCamResult.m_camUp,
tmpCamResult.m_camForward,
tmpCamResult.m_horizontal,
tmpCamResult.m_vertical,
&tmpCamResult.m_yaw,
&tmpCamResult.m_pitch,
&tmpCamResult.m_dist,
tmpCamResult.m_target);
if (result)
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) != 0)
{
m_data->m_visualConverter.render(tmpCamResult.m_viewMatrix,
tmpCamResult.m_projectionMatrix);
m_data->m_pluginManager.getRenderInterface()->setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) != 0)
{
m_data->m_pluginManager.getRenderInterface()->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_pluginManager.getRenderInterface()->setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0)
{
m_data->m_pluginManager.getRenderInterface()->setShadow((clientCmd.m_requestPixelDataArguments.m_hasShadow!=0));
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) != 0)
{
m_data->m_pluginManager.getRenderInterface()->setLightAmbientCoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) != 0)
{
m_data->m_pluginManager.getRenderInterface()->setLightDiffuseCoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) != 0)
{
m_data->m_pluginManager.getRenderInterface()->setLightSpecularCoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff);
}
for (int i=0;i<m_data->m_dynamicsWorld->getNumCollisionObjects();i++)
{
const btCollisionObject* colObj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
m_data->m_pluginManager.getRenderInterface()->syncTransform(colObj->getBroadphaseHandle()->getUid(),colObj->getWorldTransform(),colObj->getCollisionShape()->getLocalScaling());
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
{
m_data->m_pluginManager.getRenderInterface()->render(
clientCmd.m_requestPixelDataArguments.m_viewMatrix,
clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
} else
{
m_data->m_visualConverter.render();
b3OpenGLVisualizerCameraInfo tmpCamResult;
bool result = this->m_data->m_guiHelper->getCameraInfo(
&tmpCamResult.m_width,
&tmpCamResult.m_height,
tmpCamResult.m_viewMatrix,
tmpCamResult.m_projectionMatrix,
tmpCamResult.m_camUp,
tmpCamResult.m_camForward,
tmpCamResult.m_horizontal,
tmpCamResult.m_vertical,
&tmpCamResult.m_yaw,
&tmpCamResult.m_pitch,
&tmpCamResult.m_dist,
tmpCamResult.m_target);
if (result)
{
m_data->m_pluginManager.getRenderInterface()->render(tmpCamResult.m_viewMatrix,tmpCamResult.m_projectionMatrix);
} else
{
m_data->m_pluginManager.getRenderInterface()->render();
}
}
}
}
m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->copyCameraImageData(pixelRGBA,numRequestedPixels,
depthBuffer,numRequestedPixels,
segmentationMaskBuffer, numRequestedPixels,
startPixelIndex,&width,&height,&numPixelsCopied);
}
m_data->m_guiHelper->debugDisplayCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,
clientCmd.m_requestPixelDataArguments.m_projectionMatrix,pixelRGBA,numRequestedPixels,
@ -3869,7 +3896,7 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
serverStatusOut.m_type = CMD_CREATE_VISUAL_SHAPE_FAILED;
double globalScaling = 1.f;
int flags=0;
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter, globalScaling, flags);
BulletURDFImporter u2b(m_data->m_guiHelper, m_data->m_pluginManager.getRenderInterface(), globalScaling, flags);
u2b.setEnableTinyRenderer(m_data->m_enableTinyRenderer);
btTransform localInertiaFrame;
localInertiaFrame.setIdentity();
@ -6505,7 +6532,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS)
{
m_data->m_dynamicsWorld->getDispatchInfo().m_deterministicOverlappingPairs = clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs;
m_data->m_dynamicsWorld->getDispatchInfo().m_deterministicOverlappingPairs = (clientCmd.m_physSimParamArgs.m_deterministicOverlappingPairs!=0);
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
{
@ -7430,7 +7457,10 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
if (bodyHandle->m_multiBody->getBaseCollider())
{
m_data->m_visualConverter.removeVisualShape(bodyHandle->m_multiBody->getBaseCollider());
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_multiBody->getBaseCollider()->getBroadphaseHandle()->getUid());
}
m_data->m_dynamicsWorld->removeCollisionObject(bodyHandle->m_multiBody->getBaseCollider());
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
m_data->m_guiHelper->removeGraphicsInstance(graphicsIndex);
@ -7440,7 +7470,10 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
if (bodyHandle->m_multiBody->getLink(link).m_collider)
{
m_data->m_visualConverter.removeVisualShape(bodyHandle->m_multiBody->getLink(link).m_collider);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_multiBody->getLink(link).m_collider->getBroadphaseHandle()->getUid());
}
m_data->m_dynamicsWorld->removeCollisionObject(bodyHandle->m_multiBody->getLink(link).m_collider);
int graphicsIndex = bodyHandle->m_multiBody->getLink(link).m_collider->getUserIndex();
m_data->m_guiHelper->removeGraphicsInstance(graphicsIndex);
@ -7457,7 +7490,10 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
}
if (bodyHandle->m_rigidBody)
{
m_data->m_visualConverter.removeVisualShape(bodyHandle->m_rigidBody);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->removeVisualShape(bodyHandle->m_rigidBody->getBroadphaseHandle()->getUid());
}
serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId;
if (m_data->m_pickedConstraint && m_data->m_pickedBody==bodyHandle->m_rigidBody)
@ -8372,24 +8408,27 @@ bool PhysicsServerCommandProcessor::processRequestVisualShapeInfoCommand(const s
serverCmd.m_type = CMD_VISUAL_SHAPE_INFO_FAILED;
//retrieve the visual shape information for a specific body
int totalNumVisualShapes = m_data->m_visualConverter.getNumVisualShapes(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId);
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
b3VisualShapeData* visualShapeStoragePtr = (b3VisualShapeData*)bufferServerToClient;
if (m_data->m_pluginManager.getRenderInterface())
{
int totalNumVisualShapes = m_data->m_pluginManager.getRenderInterface()->getNumVisualShapes(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId);
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
b3VisualShapeData* visualShapeStoragePtr = (b3VisualShapeData*)bufferServerToClient;
int remain = totalNumVisualShapes - clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
int shapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
int remain = totalNumVisualShapes - clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
int shapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
int success = m_data->m_visualConverter.getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId,
shapeIndex,
visualShapeStoragePtr);
if (success) {
serverCmd.m_sendVisualShapeArgs.m_numRemainingVisualShapes = remain-1;
serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied = 1;
serverCmd.m_sendVisualShapeArgs.m_startingVisualShapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
serverCmd.m_sendVisualShapeArgs.m_bodyUniqueId = clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId;
serverCmd.m_numDataStreamBytes = sizeof(b3VisualShapeData)*serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied;
serverCmd.m_type = CMD_VISUAL_SHAPE_INFO_COMPLETED;
int success = m_data->m_pluginManager.getRenderInterface()->getVisualShapesData(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId,
shapeIndex,
visualShapeStoragePtr);
if (success) {
serverCmd.m_sendVisualShapeArgs.m_numRemainingVisualShapes = remain-1;
serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied = 1;
serverCmd.m_sendVisualShapeArgs.m_startingVisualShapeIndex = clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
serverCmd.m_sendVisualShapeArgs.m_bodyUniqueId = clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId;
serverCmd.m_numDataStreamBytes = sizeof(b3VisualShapeData)*serverCmd.m_sendVisualShapeArgs.m_numVisualShapesCopied;
serverCmd.m_type = CMD_VISUAL_SHAPE_INFO_COMPLETED;
}
}
return hasStatus;
}
@ -8412,7 +8451,10 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
{
if (texHandle)
{
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, texHandle->m_tinyRendererTextureId);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, texHandle->m_tinyRendererTextureId);
}
}
}
}
@ -8441,7 +8483,10 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
{
m_data->m_visualConverter.changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR)
@ -8467,7 +8512,10 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
{
m_data->m_visualConverter.changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR)
@ -8493,7 +8541,10 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
{
m_data->m_visualConverter.changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR)
@ -8550,7 +8601,11 @@ bool PhysicsServerCommandProcessor::processLoadTextureCommand(const struct Share
texH->m_tinyRendererTextureId = -1;
texH->m_openglTextureId = -1;
int uid = m_data->m_visualConverter.loadTextureFile(relativeFileName);
int uid = -1;
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->loadTextureFile(relativeFileName);
}
if(uid>=0)
{
texH->m_tinyRendererTextureId = uid;
@ -9519,7 +9574,10 @@ void PhysicsServerCommandProcessor::resetSimulation()
}
if (m_data)
{
m_data->m_visualConverter.resetAll();
if (m_data->m_pluginManager.getRenderInterface())
{
m_data->m_pluginManager.getRenderInterface()->resetAll();
}
for (int i = 0; i < m_data->m_savedStates.size(); i++)
{
delete m_data->m_savedStates[i].m_bulletFile;

View File

@ -5,7 +5,8 @@
///increase the SHARED_MEMORY_MAGIC_NUMBER whenever incompatible changes are made in the structures
///my convention is year/month/day/rev
#define SHARED_MEMORY_MAGIC_NUMBER 201801080
#define SHARED_MEMORY_MAGIC_NUMBER 201801170
//#define SHARED_MEMORY_MAGIC_NUMBER 201801080
//#define SHARED_MEMORY_MAGIC_NUMBER 201801010
//#define SHARED_MEMORY_MAGIC_NUMBER 201710180
//#define SHARED_MEMORY_MAGIC_NUMBER 201710050

View File

@ -1,63 +0,0 @@
#ifndef TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
#define TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
#include "../Importers/ImportURDFDemo/LinkVisualShapesConverter.h"
struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
{
struct TinyRendererVisualShapeConverterInternalData* m_data;
TinyRendererVisualShapeConverter();
virtual ~TinyRendererVisualShapeConverter();
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, class btCollisionObject* colShape, int objectIndex);
virtual int getNumVisualShapes(int bodyUniqueId);
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, const double rgbaColor[4]);
virtual void removeVisualShape(class btCollisionObject* colObj);
void setUpAxis(int axis);
void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
void clearBuffers(struct TGAColor& clearColor);
void resetAll();
void getWidthAndHeight(int& width, int& height);
void setWidthAndHeight(int width, int height);
void setLightDirection(float x, float y, float z);
void setLightColor(float x, float y, float z);
void setLightDistance(float dist);
void setLightAmbientCoeff(float ambientCoeff);
void setLightDiffuseCoeff(float diffuseCoeff);
void setLightSpecularCoeff(float specularCoeff);
void setShadow(bool hasShadow);
void setFlags(int flags);
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
void render();
void render(const float viewMat[16], const float projMat[16]);
int loadTextureFile(const char* filename);
int registerTexture(unsigned char* texels, int width, int height);
void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
};
#endif //TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H

View File

@ -39,8 +39,10 @@ struct b3Plugin
PFN_TICK m_preTickFunc;
PFN_TICK m_postTickFunc;
PFN_GET_RENDER_INTERFACE m_getRendererFunc;
void* m_userPointer;
b3Plugin()
:m_pluginHandle(0),
m_ownsPluginHandle(false),
@ -50,6 +52,7 @@ struct b3Plugin
m_executeCommandFunc(0),
m_preTickFunc(0),
m_postTickFunc(0),
m_getRendererFunc(0),
m_userPointer(0)
{
}
@ -66,6 +69,7 @@ struct b3Plugin
m_preTickFunc = 0;
m_postTickFunc = 0;
m_userPointer = 0;
m_getRendererFunc = 0;
}
};
@ -79,6 +83,12 @@ struct b3PluginManagerInternalData
b3AlignedObjectArray<b3KeyboardEvent> m_keyEvents;
b3AlignedObjectArray<b3VRControllerEvent> m_vrEvents;
b3AlignedObjectArray<b3MouseEvent> m_mouseEvents;
int m_activeRendererPluginUid;
b3PluginManagerInternalData()
:m_activeRendererPluginUid(-1)
{
}
};
b3PluginManager::b3PluginManager(class PhysicsCommandProcessorInterface* physSdk)
@ -151,12 +161,14 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
std::string executePluginCommandStr = std::string("executePluginCommand") + postFix;
std::string preTickPluginCallbackStr = std::string("preTickPluginCallback") + postFix;
std::string postTickPluginCallback = std::string("postTickPluginCallback") + postFix;
std::string getRendererStr = std::string("getRenderInterface") + postFix;
plugin->m_initFunc = (PFN_INIT)B3_DYNLIB_IMPORT(pluginHandle, initStr.c_str());
plugin->m_exitFunc = (PFN_EXIT)B3_DYNLIB_IMPORT(pluginHandle, exitStr.c_str());
plugin->m_executeCommandFunc = (PFN_EXECUTE)B3_DYNLIB_IMPORT(pluginHandle, executePluginCommandStr.c_str());
plugin->m_preTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, preTickPluginCallbackStr.c_str());
plugin->m_postTickFunc = (PFN_TICK)B3_DYNLIB_IMPORT(pluginHandle, postTickPluginCallback.c_str());
plugin->m_getRendererFunc = (PFN_GET_RENDER_INTERFACE)B3_DYNLIB_IMPORT(pluginHandle, getRendererStr.c_str());
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
{
@ -201,6 +213,17 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
pluginUniqueId = -1;
}
}
//for now, automatically select the loaded plugin as active renderer. If wanted, we can add some 'select' mechanism.
if (pluginUniqueId>=0)
{
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
if (plugin && plugin->m_getRendererFunc)
{
selectPluginRenderer(pluginUniqueId);
}
}
return pluginUniqueId;
}
@ -275,11 +298,10 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
}
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc)
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc)
{
b3Plugin orgPlugin;
int pluginUniqueId = m_data->m_plugins.allocHandle();
b3PluginHandle* pluginHandle = m_data->m_plugins.getHandle(pluginUniqueId);
@ -291,10 +313,12 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
pluginHandle->m_initFunc = initFunc;
pluginHandle->m_preTickFunc = preTickFunc;
pluginHandle->m_postTickFunc = postTickFunc;
pluginHandle->m_getRendererFunc = getRendererFunc;
pluginHandle->m_pluginHandle = 0;
pluginHandle->m_pluginPath = pluginPath;
pluginHandle->m_userPointer = 0;
m_data->m_pluginMap.insert(pluginPath, pluginHandle);
{
@ -313,3 +337,34 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
}
return pluginUniqueId;
}
void b3PluginManager::selectPluginRenderer(int pluginUniqueId)
{
m_data->m_activeRendererPluginUid = pluginUniqueId;
}
UrdfRenderingInterface* b3PluginManager::getRenderInterface()
{
UrdfRenderingInterface* renderer = 0;
if (m_data->m_activeRendererPluginUid>=0)
{
b3PluginHandle* plugin = m_data->m_plugins.getHandle(m_data->m_activeRendererPluginUid);
if (plugin)
{
b3PluginContext context;
context.m_userPointer = plugin->m_userPointer;
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
context.m_numMouseEvents = 0;
context.m_mouseEvents = 0;
context.m_numKeyEvents = 0;
context.m_keyEvents = 0;
context.m_numVRControllerEvents = 0;
context.m_vrControllerEvents = 0;
renderer = plugin->m_getRendererFunc(&context);
}
}
return renderer;
}

View File

@ -17,11 +17,13 @@ class b3PluginManager
int executePluginCommand(int pluginUniqueId, const struct b3PluginArguments* arguments);
void addEvents(const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents, const struct b3MouseEvent* mouseEvents, int numMouseEvents);
void clearEvents();
void tickPlugins(double timeStep, bool isPreTick);
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc);
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc);
void selectPluginRenderer(int pluginUniqueId);
UrdfRenderingInterface* getRenderInterface();
};
#endif //B3_PLUGIN_MANAGER_H

View File

@ -30,6 +30,10 @@ extern "C" {
typedef B3_API_ENTRY void (B3_API_CALL * PFN_EXIT)(struct b3PluginContext* context);
typedef B3_API_ENTRY int (B3_API_CALL * PFN_EXECUTE)(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
typedef B3_API_ENTRY int (B3_API_CALL * PFN_TICK)(struct b3PluginContext* context);
typedef B3_API_ENTRY struct UrdfRenderingInterface* (B3_API_CALL * PFN_GET_RENDER_INTERFACE)(struct b3PluginContext* context);
#ifdef __cplusplus
}
#endif

View File

@ -9,7 +9,7 @@ struct b3PluginContext
//plugin can modify the m_userPointer to store persistent object pointer (class or struct instance etc)
void* m_userPointer;
const struct b3VRControllerEvent* m_vrControllerEvents;
int m_numVRControllerEvents;
const struct b3KeyboardEvent* m_keyEvents;

View File

@ -13,10 +13,10 @@ B3_SHARED_API int initPlugin(struct b3PluginContext* context);
B3_SHARED_API void exitPlugin(struct b3PluginContext* context);
B3_SHARED_API int executePluginCommand(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
//preTickPluginCallback and postTickPluginCallback are optional.
//all the APIs below are optional
B3_SHARED_API int preTickPluginCallback(struct b3PluginContext* context);
B3_SHARED_API int postTickPluginCallback(struct b3PluginContext* context);
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface(struct b3PluginContext* context);
#ifdef __cplusplus

View File

@ -49,6 +49,14 @@ struct TinyRendererObjectArray
btAlignedObjectArray< TinyRenderObjectData*> m_renderObjects;
int m_objectUniqueId;
int m_linkIndex;
btTransform m_worldTransform;
btVector3 m_localScaling;
TinyRendererObjectArray()
{
m_worldTransform.setIdentity();
m_localScaling.setValue(1,1,1);
}
};
#define START_WIDTH 640
@ -57,7 +65,7 @@ struct TinyRendererObjectArray
struct TinyRendererVisualShapeConverterInternalData
{
btHashMap<btHashPtr,TinyRendererObjectArray*> m_swRenderInstances;
btHashMap<btHashInt,TinyRendererObjectArray*> m_swRenderInstances;
btAlignedObjectArray<b3VisualShapeData> m_visualShapes;
@ -542,7 +550,7 @@ static btVector4 sColors[4] =
void TinyRendererVisualShapeConverter::convertVisualShapes(
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
const UrdfLink* linkPtr, const UrdfModel* model,
class btCollisionObject* colObj, int bodyUniqueId)
int shapeUid, int bodyUniqueId)
{
btAssert(linkPtr); // TODO: remove if (not doing it now, because diff will be 50+ lines)
if (linkPtr)
@ -579,15 +587,16 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
int colorIndex = colObj? colObj->getBroadphaseHandle()->getUid() & 3 : 0;
int colorIndex = linkIndex;//colObj? colObj->getBroadphaseHandle()->getUid() & 3 : 0;
if (colorIndex<0)
colorIndex=0;
btVector4 color;
color = sColors[colorIndex];
float rgbaColor[4] = {color[0],color[1],color[2],color[3]};
if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE)
{
color.setValue(1,1,1,1);
}
//if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE)
//{
// color.setValue(1,1,1,1);
//}
if (model)
{
if (useVisual)
@ -618,12 +627,12 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
}
}
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[colObj];
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[shapeUid];
if (visualsPtr==0)
{
m_data->m_swRenderInstances.insert(colObj,new TinyRendererObjectArray);
m_data->m_swRenderInstances.insert(shapeUid,new TinyRendererObjectArray);
}
visualsPtr = m_data->m_swRenderInstances[colObj];
visualsPtr = m_data->m_swRenderInstances[shapeUid];
btAssert(visualsPtr);
TinyRendererObjectArray* visuals = *visualsPtr;
@ -822,6 +831,19 @@ void TinyRendererVisualShapeConverter::render()
render(viewMat,projMat);
}
void TinyRendererVisualShapeConverter::syncTransform(int shapeUid, const btTransform& worldTransform, const btVector3& localScaling)
{
TinyRendererObjectArray** renderObjPtr = m_data->m_swRenderInstances[shapeUid];
if (renderObjPtr)
{
TinyRendererObjectArray* renderObj = *renderObjPtr;
renderObj->m_worldTransform = worldTransform;
renderObj->m_localScaling = localScaling;
}
}
void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
{
//clear the color buffer
@ -902,11 +924,6 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
continue;//can this ever happen?
TinyRendererObjectArray* visualArray = *visualArrayPtr;
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n);
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
for (int v=0;v<visualArray->m_renderObjects.size();v++)
{
@ -914,7 +931,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
//sync the object transform
const btTransform& tr = colObj->getWorldTransform();
const btTransform& tr = visualArray->m_worldTransform;
tr.getOpenGLMatrix(modelMat);
for (int i=0;i<4;i++)
@ -927,7 +944,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
}
}
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_localScaling = visualArray->m_localScaling;
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
@ -946,10 +963,6 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
continue;//can this ever happen?
TinyRendererObjectArray* visualArray = *visualArrayPtr;
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n);
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
for (int v=0;v<visualArray->m_renderObjects.size();v++)
{
@ -958,7 +971,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
//sync the object transform
const btTransform& tr = colObj->getWorldTransform();
const btTransform& tr = visualArray->m_worldTransform;
tr.getOpenGLMatrix(modelMat);
for (int i=0;i<4;i++)
@ -971,7 +984,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
}
}
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_localScaling = visualArray->m_localScaling;
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
@ -1096,9 +1109,9 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
}
}
void TinyRendererVisualShapeConverter::removeVisualShape(class btCollisionObject* colObj)
void TinyRendererVisualShapeConverter::removeVisualShape(int shapeUid)
{
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances[colObj];
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances[shapeUid];
if (ptrptr && *ptrptr)
{
TinyRendererObjectArray* ptr = *ptrptr;
@ -1110,7 +1123,7 @@ void TinyRendererVisualShapeConverter::removeVisualShape(class btCollisionObject
}
}
delete ptr;
m_data->m_swRenderInstances.remove(colObj);
m_data->m_swRenderInstances.remove(shapeUid);
}
}

View File

@ -0,0 +1,61 @@
#ifndef TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
#define TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H
#include "../../../Importers/ImportURDFDemo/UrdfRenderingInterface.h"
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
{
struct TinyRendererVisualShapeConverterInternalData* m_data;
TinyRendererVisualShapeConverter();
virtual ~TinyRendererVisualShapeConverter();
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex);
virtual int getNumVisualShapes(int bodyUniqueId);
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, const double rgbaColor[4]);
virtual void removeVisualShape(int shapeUid);
virtual void setUpAxis(int axis);
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
virtual void clearBuffers(struct TGAColor& clearColor);
virtual void resetAll();
virtual void getWidthAndHeight(int& width, int& height);
virtual void setWidthAndHeight(int width, int height);
virtual void setLightDirection(float x, float y, float z);
virtual void setLightColor(float x, float y, float z);
virtual void setLightDistance(float dist);
virtual void setLightAmbientCoeff(float ambientCoeff);
virtual void setLightDiffuseCoeff(float diffuseCoeff);
virtual void setLightSpecularCoeff(float specularCoeff);
virtual void setShadow(bool hasShadow);
virtual void setFlags(int flags);
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
virtual void render();
virtual void render(const float viewMat[16], const float projMat[16]);
virtual int loadTextureFile(const char* filename);
virtual int registerTexture(unsigned char* texels, int width, int height);
virtual void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
virtual void syncTransform(int shapeUid, const class btTransform& worldTransform, const class btVector3& localScaling);
};
#endif //TINY_RENDERER_VISUAL_SHAPE_CONVERTER_H

View File

@ -0,0 +1,57 @@
project ("pybullet_tinyRendererPlugin")
language "C++"
kind "SharedLib"
includedirs {".","../../../../src", "../../../../examples",
"../../../ThirdPartyLibs"}
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
hasCL = findOpenCL("clew")
links{"BulletCollision", "Bullet3Common", "LinearMath"}
if os.is("MacOSX") then
-- targetextension {"so"}
links{"Cocoa.framework","Python"}
end
files {
"tinyRendererPlugin.cpp",
"tinyRendererPlugin.h",
"TinyRendererVisualShapeConverter.cpp",
"TinyRendererVisualShapeConverter.h",
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.h",
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.h",
"../../../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
"../../../Importers/ImportObjDemo/LoadMeshFromObj.h",
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h",
"../../../TinyRenderer/geometry.cpp",
"../../../TinyRenderer/model.cpp",
"../../../TinyRenderer/our_gl.cpp",
"../../../TinyRenderer/tgaimage.cpp",
"../../../TinyRenderer/TinyRenderer.cpp",
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../../../ThirdPartyLibs/stb_image/stb_image.cpp",
"../../../ThirdPartyLibs/stb_image/stb_image.h",
"../../../ThirdPartyLibs/tinyxml/tinystr.cpp",
"../../../ThirdPartyLibs/tinyxml/tinystr.h",
"../../../ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../../../ThirdPartyLibs/tinyxml/tinyxml.h",
"../../../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../../../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../../../OpenGLWindow/SimpleCamera.cpp",
"../../../OpenGLWindow/SimpleCamera.h",
"../../../Utils/b3Clock.cpp",
"../../../Utils/b3Clock.h",
"../../../Utils/b3ResourcePath.cpp",
"../../../Utils/b3ResourcePath.h",
}

View File

@ -0,0 +1,62 @@
//tinyRenderer plugin
/*
import pybullet as p
p.connect(p.GUI)
plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_tinyRendererPlugin_vs2010_x64_debug.dll","_tinyRendererPlugin")
print("plugin=",plugin)
p.loadURDF("r2d2.urdf")
while (1):
p.getCameraImage(320,200)
*/
#include "tinyRendererPlugin.h"
#include "TinyRendererVisualShapeConverter.h"
#include "../../SharedMemoryPublic.h"
#include "../b3PluginContext.h"
#include <stdio.h>
struct MyRendererPluginClass
{
TinyRendererVisualShapeConverter m_renderer;
MyRendererPluginClass()
{
}
virtual ~MyRendererPluginClass()
{
}
};
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context)
{
MyRendererPluginClass* obj = new MyRendererPluginClass();
context->m_userPointer = obj;
return SHARED_MEMORY_MAGIC_NUMBER;
}
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
{
return -1;
}
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context)
{
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
delete obj;
context->m_userPointer = 0;
}
//all the APIs below are optional
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context)
{
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
return &obj->m_renderer;
}

View File

@ -0,0 +1,25 @@
#ifndef TINY_RENDERER_PLUGIN_H
#define TINY_RENDERER_PLUGIN_H
#include "../b3PluginAPI.h"
#ifdef __cplusplus
extern "C"
{
#endif
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context);
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context);
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
//all the APIs below are optional
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context);
#ifdef __cplusplus
};
#endif
#endif//#define TEST_PLUGIN_H

View File

@ -13,11 +13,10 @@ B3_SHARED_API int initPlugin_vrSyncPlugin(struct b3PluginContext* context);
B3_SHARED_API void exitPlugin_vrSyncPlugin(struct b3PluginContext* context);
B3_SHARED_API int executePluginCommand_vrSyncPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
//preTickPluginCallback and postTickPluginCallback are optional.
//optional APIs
B3_SHARED_API int preTickPluginCallback_vrSyncPlugin(struct b3PluginContext* context);
#ifdef __cplusplus
};
#endif

View File

@ -55,13 +55,6 @@ myfiles =
"PhysicsServerCommandProcessor.h",
"b3PluginManager.cpp",
"b3PluginManager.h",
"TinyRendererVisualShapeConverter.cpp",
"TinyRendererVisualShapeConverter.h",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp",
"../OpenGLWindow/SimpleCamera.cpp",
"../OpenGLWindow/SimpleCamera.h",
"../Importers/ImportURDFDemo/ConvertRigidBodies2MultiBody.h",
@ -115,6 +108,20 @@ if (_OPTIONS["enable_static_vr_plugin"]) then
files {"plugins/vrSyncPlugin/vrSyncPlugin.cpp"}
end
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
files
{
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp"
}
else
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
end
files {
"../MultiThreading/b3ThreadSupportInterface.cpp",
@ -200,6 +207,21 @@ language "C++"
end
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
files
{
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp"
}
else
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
end
files {
myfiles,
@ -344,7 +366,22 @@ if os.is("Windows") then
initOpenGL()
initGlew()
if (not _OPTIONS["disable_static_tinyrenderer_plugin"]) then
files
{
"plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../TinyRenderer/geometry.cpp",
"../TinyRenderer/model.cpp",
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp"
}
else
defines("SKIP_STATIC_TINYRENDERER_PLUGIN")
end
files
{
myfiles,
@ -426,5 +463,6 @@ include "udp"
include "tcp"
include "plugins/testPlugin"
include "plugins/vrSyncPlugin"
include "plugins/tinyRendererPlugin"

View File

@ -90,9 +90,9 @@ myfiles =
"../PhysicsServerCommandProcessor.h",
"../b3PluginManager.cpp",
"../PhysicsDirect.cpp",
"../PhysicsClient.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../PhysicsClient.cpp",
"../plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../TinyRenderer/geometry.cpp",
"../../TinyRenderer/model.cpp",
"../../TinyRenderer/tgaimage.cpp",

View File

@ -82,8 +82,8 @@ myfiles =
"../b3PluginManager.cpp",
"../PhysicsDirect.cpp",
"../PhysicsClient.cpp",
"../TinyRendererVisualShapeConverter.cpp",
"../TinyRendererVisualShapeConverter.h",
"../plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../TinyRenderer/geometry.cpp",
"../../TinyRenderer/model.cpp",
"../../TinyRenderer/tgaimage.cpp",

View File

@ -13,8 +13,8 @@ SET(RobotSimulator_SRCS
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp

View File

@ -18,8 +18,10 @@ SET(pybullet_SRCS
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp

View File

@ -0,0 +1,9 @@
import pybullet as p
p.connect(p.GUI)
plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_tinyRendererPlugin_vs2010_x64_debug.dll","_tinyRendererPlugin")
print("plugin=",plugin)
p.loadURDF("r2d2.urdf")
while (1):
p.getCameraImage(320,200)

View File

@ -124,7 +124,7 @@ def pybullet_humanoid():
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
env = 'HumanoidBulletEnv-v0'
max_length = 1000
steps = 3e7 # 30M
steps = 3e8 # 300M
return locals()

View File

@ -91,8 +91,10 @@ if not _OPTIONS["no-enet"] then
"../../examples/SharedMemory/IKTrajectoryHelper.cpp",
"../../examples/SharedMemory/IKTrajectoryHelper.h",
"../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h",
"../../examples/OpenGLWindow/SimpleCamera.cpp",
"../../examples/OpenGLWindow/SimpleCamera.h",
"../../examples/TinyRenderer/geometry.cpp",

View File

@ -65,7 +65,8 @@ sources = ["examples/pybullet/pybullet.c"]\
+["examples/SharedMemory/PhysicsClientC_API.cpp"]\
+["examples/SharedMemory/Win32SharedMemory.cpp"]\
+["examples/SharedMemory/PosixSharedMemory.cpp"]\
+["examples/SharedMemory/TinyRendererVisualShapeConverter.cpp"]\
+["examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp"]\
+["examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp"]\
+["examples/SharedMemory/PhysicsClientUDP.cpp"]\
+["examples/SharedMemory/PhysicsClientUDP_C_API.cpp"]\
+["examples/SharedMemory/PhysicsClientTCP.cpp"]\
@ -443,7 +444,7 @@ print("-----")
setup(
name = 'pybullet',
version='1.8.2',
version='1.8.3',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',

View File

@ -49,9 +49,9 @@ inline mat33 operator*(const idScalar& s, const mat33& a) { return a * s; }
class vecx : public btVectorX<idScalar> {
public:
vecx(int size) : btVectorX(size) {}
vecx(int size) : btVectorX<idScalar>(size) {}
const vecx& operator=(const btVectorX<idScalar>& rhs) {
*static_cast<btVectorX*>(this) = rhs;
*static_cast<btVectorX<idScalar>*>(this) = rhs;
return *this;
}

View File

@ -66,8 +66,8 @@ ENDIF()
../../examples/Utils/ChromeTraceUtil.h
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/RobotLoggingUtil.h
../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/TinyRendererVisualShapeConverter.h
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp

View File

@ -191,8 +191,8 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../examples/OpenGLWindow/SimpleCamera.cpp",
"../../examples/OpenGLWindow/SimpleCamera.h",
"../../examples/TinyRenderer/geometry.cpp",
@ -276,8 +276,8 @@ end
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../examples/TinyRenderer/geometry.cpp",
"../../examples/TinyRenderer/model.cpp",
"../../examples/TinyRenderer/tgaimage.cpp",
@ -388,8 +388,8 @@ project ("Test_PhysicsServerInProcessExampleBrowser")
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp",
"../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp",
"../../examples/TinyRenderer/geometry.cpp",
"../../examples/TinyRenderer/model.cpp",
"../../examples/TinyRenderer/tgaimage.cpp",