add user debug line/text features in pybullet + shared memory API:

addUserDebugLine,
addUserDebugText
removeUserDebugItem
removeAllUserDebugItems
This commit is contained in:
Erwin Coumans
2016-11-14 07:39:34 -08:00
parent d49e3d787a
commit c521d816c6
17 changed files with 809 additions and 35 deletions

View File

@@ -793,6 +793,7 @@ int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyInd
{
switch (status->m_type)
{
case CMD_BULLET_LOADING_COMPLETED:
case CMD_SDF_LOADING_COMPLETED:
{
int i,maxBodies;
@@ -1062,6 +1063,107 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
}
/// Add/remove user-specific debug lines and debug text messages
b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_USER_DEBUG_DRAW;
command->m_updateFlags = USER_DEBUG_HAS_LINE; //USER_DEBUG_HAS_TEXT
command->m_userDebugDrawArgs.m_debugLineFromXYZ[0] = fromXYZ[0];
command->m_userDebugDrawArgs.m_debugLineFromXYZ[1] = fromXYZ[1];
command->m_userDebugDrawArgs.m_debugLineFromXYZ[2] = fromXYZ[2];
command->m_userDebugDrawArgs.m_debugLineToXYZ[0] = toXYZ[0];
command->m_userDebugDrawArgs.m_debugLineToXYZ[1] = toXYZ[1];
command->m_userDebugDrawArgs.m_debugLineToXYZ[2] = toXYZ[2];
command->m_userDebugDrawArgs.m_debugLineColorRGB[0] = colorRGB[0];
command->m_userDebugDrawArgs.m_debugLineColorRGB[1] = colorRGB[1];
command->m_userDebugDrawArgs.m_debugLineColorRGB[2] = colorRGB[2];
command->m_userDebugDrawArgs.m_lineWidth = lineWidth;
command->m_userDebugDrawArgs.m_lifeTime = lifeTime;
return (b3SharedMemoryCommandHandle) command;
}
b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_USER_DEBUG_DRAW;
command->m_updateFlags = USER_DEBUG_HAS_TEXT;
int len = strlen(txt);
if (len<MAX_FILENAME_LENGTH)
{
strcpy(command->m_userDebugDrawArgs.m_text,txt);
} else
{
command->m_userDebugDrawArgs.m_text[0] = 0;
}
command->m_userDebugDrawArgs.m_textPositionXYZ[0] = positionXYZ[0];
command->m_userDebugDrawArgs.m_textPositionXYZ[1] = positionXYZ[1];
command->m_userDebugDrawArgs.m_textPositionXYZ[2] = positionXYZ[2];
command->m_userDebugDrawArgs.m_textColorRGB[0] = colorRGB[0];
command->m_userDebugDrawArgs.m_textColorRGB[1] = colorRGB[1];
command->m_userDebugDrawArgs.m_textColorRGB[2] = colorRGB[2];
command->m_userDebugDrawArgs.m_textSize = textSize;
command->m_userDebugDrawArgs.m_lifeTime = lifeTime;
return (b3SharedMemoryCommandHandle) command;
}
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_USER_DEBUG_DRAW;
command->m_updateFlags = USER_DEBUG_REMOVE_ONE_ITEM;
command->m_userDebugDrawArgs.m_removeItemUniqueId = debugItemUniqueId;
return (b3SharedMemoryCommandHandle) command;
}
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type =CMD_USER_DEBUG_DRAW;
command->m_updateFlags = USER_DEBUG_REMOVE_ALL;
return (b3SharedMemoryCommandHandle) command;
}
int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;
btAssert(status->m_type == CMD_USER_DEBUG_DRAW_COMPLETED);
if (status->m_type != CMD_USER_DEBUG_DRAW_COMPLETED)
return -1;
return status->m_userDebugDrawArgs.m_debugItemUniqueId;
}
///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient)
{
@@ -1627,6 +1729,7 @@ b3SharedMemoryCommandHandle b3CalculateJacobianCommandInit(b3PhysicsClientHandle
return (b3SharedMemoryCommandHandle)command;
}
int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle, double* linearJacobian, double* angularJacobian)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus*)statusHandle;

View File

@@ -74,14 +74,22 @@ int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointInd
b3SharedMemoryCommandHandle b3CreateJoint(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);
///Request debug lines for debug visualization. The flags in debugMode are the same as used in Bullet
///Request physics debug lines for debug visualization. The flags in debugMode are the same as used in Bullet
///See btIDebugDraw::DebugDrawModes in Bullet/src/LinearMath/btIDebugDraw.h
b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode);
///Get the pointers to the debug line information, after b3InitRequestDebugLinesCommand returns
///Get the pointers to the physics debug line information, after b3InitRequestDebugLinesCommand returns
///status CMD_DEBUG_LINES_COMPLETED
void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* lines);
/// Add/remove user-specific debug lines and debug text messages
b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle physClient, double fromXYZ[3], double toXYZ[3], double colorRGB[3], double lineWidth, double lifeTime);
b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime);
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId);
b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient);
///All debug items unique Ids are positive: a negative unique Id means failure.
int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle);
///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient);
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]);

View File

@@ -722,6 +722,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
b3Warning("Load .mjcf failed");
break;
}
case CMD_USER_DEBUG_DRAW_COMPLETED:
{
break;
}
case CMD_USER_DEBUG_DRAW_FAILED:
{
b3Warning("User debug draw failed");
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);

View File

@@ -3363,9 +3363,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_LOAD_TEXTURE_FAILED;
m_data->m_visualConverter.loadTextureFile(clientCmd.m_loadTextureArguments.m_textureFileName);
int uid = m_data->m_visualConverter.loadTextureFile(clientCmd.m_loadTextureArguments.m_textureFileName);
serverCmd.m_type = CMD_LOAD_TEXTURE_COMPLETED;
if (uid>=0)
{
serverCmd.m_type = CMD_LOAD_TEXTURE_COMPLETED;
} else
{
serverCmd.m_type = CMD_LOAD_TEXTURE_FAILED;
}
hasStatus = true;
break;
@@ -3403,6 +3409,34 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
bool ok = importer->loadFile(relativeFileName);
if (ok)
{
int numRb = importer->getNumRigidBodies();
serverStatusOut.m_sdfLoadedArgs.m_numBodies = 0;
for( int i=0;i<numRb;i++)
{
btCollisionObject* colObj = importer->getRigidBodyByIndex(i);
if (colObj)
{
btRigidBody* rb = btRigidBody::upcast(colObj);
if (rb)
{
int bodyUniqueId = m_data->allocHandle();
InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
colObj->setUserIndex2(bodyUniqueId);
bodyHandle->m_rigidBody = rb;
if (serverStatusOut.m_sdfLoadedArgs.m_numBodies<MAX_SDF_BODIES)
{
serverStatusOut.m_sdfLoadedArgs.m_numBodies++;
serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = bodyUniqueId;
}
}
}
}
serverCmd.m_type = CMD_BULLET_LOADING_COMPLETED;
m_data->m_guiHelper->autogenerateGraphicsObjects(m_data->m_dynamicsWorld);
hasStatus = true;
@@ -3441,6 +3475,62 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_USER_DEBUG_DRAW:
{
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_USER_DEBUG_DRAW_FAILED;
hasStatus = true;
if (clientCmd.m_updateFlags & USER_DEBUG_HAS_TEXT)
{
int uid = m_data->m_guiHelper->addUserDebugText3D(clientCmd.m_userDebugDrawArgs.m_text,
clientCmd.m_userDebugDrawArgs.m_textPositionXYZ,
clientCmd.m_userDebugDrawArgs.m_textColorRGB,
clientCmd.m_userDebugDrawArgs.m_textSize,
clientCmd.m_userDebugDrawArgs.m_lifeTime);
if (uid>=0)
{
serverCmd.m_userDebugDrawArgs.m_debugItemUniqueId = uid;
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
}
if (clientCmd.m_updateFlags & USER_DEBUG_HAS_LINE)
{
int uid = m_data->m_guiHelper->addUserDebugLine(
clientCmd.m_userDebugDrawArgs.m_debugLineFromXYZ,
clientCmd.m_userDebugDrawArgs.m_debugLineToXYZ,
clientCmd.m_userDebugDrawArgs.m_debugLineColorRGB,
clientCmd.m_userDebugDrawArgs.m_lineWidth,
clientCmd.m_userDebugDrawArgs.m_lifeTime);
if (uid>=0)
{
serverCmd.m_userDebugDrawArgs.m_debugItemUniqueId = uid;
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
}
if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_ALL)
{
m_data->m_guiHelper->removeAllUserDebugItems();
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_ONE_ITEM)
{
m_data->m_guiHelper->removeUserDebugItem(clientCmd.m_userDebugDrawArgs.m_removeItemUniqueId);
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
}
break;
}
default:
{
b3Error("Unknown command encountered");

View File

@@ -75,6 +75,10 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperRemoveAllGraphicsInstances,
eGUIHelperCopyCameraImageData,
eGUIHelperAutogenerateGraphicsObjects,
eGUIUserDebugAddText,
eGUIUserDebugAddLine,
eGUIUserDebugRemoveItem,
eGUIUserDebugRemoveAllItems,
};
#include <stdio.h>
@@ -271,17 +275,43 @@ void* MotionlsMemoryFunc()
struct UserDebugDrawLine
{
double m_debugLineFromXYZ[3];
double m_debugLineToXYZ[3];
double m_debugLineColorRGB[3];
double m_lineWidth;
double m_lifeTime;
int m_itemUniqueId;
};
struct UserDebugText
{
char m_text[1024];
double m_textPositionXYZ[3];
double m_textColorRGB[3];
double textSize;
double m_lifeTime;
int m_itemUniqueId;
};
class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
{
CommonGraphicsApp* m_app;
b3CriticalSection* m_cs;
public:
GUIHelperInterface* m_childGuiHelper;
int m_uidGenerator;
const unsigned char* m_texels;
int m_textureWidth;
int m_textureHeight;
@@ -305,6 +335,7 @@ public:
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
:m_app(app)
,m_cs(0),
m_uidGenerator(0),
m_texels(0),
m_textureId(-1)
{
@@ -548,6 +579,96 @@ public:
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)
{
}
btAlignedObjectArray<UserDebugText> m_userDebugText;
UserDebugText m_tmpText;
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double textColorRGB[3], double size, double lifeTime)
{
m_tmpText.m_itemUniqueId = m_uidGenerator++;
m_tmpText.m_lifeTime = lifeTime;
m_tmpText.textSize = size;
int len = strlen(txt);
strcpy(m_tmpText.m_text,txt);
m_tmpText.m_textPositionXYZ[0] = positionXYZ[0];
m_tmpText.m_textPositionXYZ[1] = positionXYZ[1];
m_tmpText.m_textPositionXYZ[2] = positionXYZ[2];
m_tmpText.m_textColorRGB[0] = textColorRGB[0];
m_tmpText.m_textColorRGB[1] = textColorRGB[1];
m_tmpText.m_textColorRGB[2] = textColorRGB[2];
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugAddText);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId;
}
btAlignedObjectArray<UserDebugDrawLine> m_userDebugLines;
UserDebugDrawLine m_tmpLine;
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime )
{
m_tmpLine.m_lifeTime = lifeTime;
m_tmpLine.m_lineWidth = lineWidth;
m_tmpLine.m_itemUniqueId = m_uidGenerator++;
m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0];
m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1];
m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2];
m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0];
m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId;
}
int m_removeDebugItemUid;
virtual void removeUserDebugItem( int debugItemUniqueId)
{
m_removeDebugItemUid = debugItemUniqueId;
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugRemoveItem);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
}
virtual void removeAllUserDebugItems( )
{
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
}
};
@@ -935,10 +1056,68 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugAddText:
{
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugAddLine:
{
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugRemoveItem:
{
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
break;
}
}
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
break;
}
}
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugRemoveAllItems:
{
m_multiThreadedHelper->m_userDebugLines.clear();
m_multiThreadedHelper->m_userDebugText.clear();
m_multiThreadedHelper->m_uidGenerator = 0;
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperIdle:
{
break;
}
default:
{
btAssert(0);
}
}
@@ -993,15 +1172,38 @@ void PhysicsServerExample::renderScene()
//add array of lines
//draw all user- 'text3d' messages
if (m_guiHelper)
if (m_multiThreadedHelper)
{
btVector3 from(0, 0, 0);
btVector3 toX(1, 1, 1);
btVector3 color(0, 1, 0);
double width = 2;
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, width);
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
{
btVector3 from;
from.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
btVector3 toX;
toX.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
btVector3 color;
color.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
m_guiHelper->getAppInterface()->drawText3D("hi", 1, 1, 1, 1);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
}
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
m_multiThreadedHelper->m_userDebugText[i].textSize);
}
}

View File

@@ -500,6 +500,40 @@ struct CreateJointArgs
int m_jointType;
};
enum EnumUserDebugDrawFlags
{
USER_DEBUG_HAS_LINE=1,
USER_DEBUG_HAS_TEXT=2,
USER_DEBUG_REMOVE_ONE_ITEM=4,
USER_DEBUG_REMOVE_ALL=8
};
struct UserDebugDrawArgs
{
double m_debugLineFromXYZ[3];
double m_debugLineToXYZ[3];
double m_debugLineColorRGB[3];
double m_lineWidth;
double m_lifeTime;
int m_removeItemUniqueId;
char m_text[MAX_FILENAME_LENGTH];
double m_textPositionXYZ[3];
double m_textColorRGB[3];
double m_textSize;
};
struct UserDebugDrawResultArgs
{
int m_debugItemUniqueId;
};
struct SharedMemoryCommand
{
int m_type;
@@ -536,6 +570,7 @@ struct SharedMemoryCommand
struct UpdateVisualShapeDataArgs m_updateVisualShapeDataArguments;
struct LoadTextureArgs m_loadTextureArguments;
struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments;
struct UserDebugDrawArgs m_userDebugDrawArgs;
struct LoadBunnyArgs m_loadBunnyArguments;
};
};
@@ -584,6 +619,7 @@ struct SharedMemoryStatus
struct SendOverlappingObjectsArgs m_sendOverlappingObjectsArgs;
struct CalculateInverseKinematicsResultArgs m_inverseKinematicsResultArgs;
struct SendVisualShapeDataArgs m_sendVisualShapeArgs;
struct UserDebugDrawResultArgs m_userDebugDrawArgs;
};
};

View File

@@ -40,6 +40,8 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_VISUAL_SHAPE_INFO,
CMD_UPDATE_VISUAL_SHAPE,
CMD_LOAD_TEXTURE,
CMD_USER_DEBUG_DRAW,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -100,6 +102,8 @@ enum EnumSharedMemoryServerStatus
CMD_VISUAL_SHAPE_UPDATE_FAILED,
CMD_LOAD_TEXTURE_COMPLETED,
CMD_LOAD_TEXTURE_FAILED,
CMD_USER_DEBUG_DRAW_COMPLETED,
CMD_USER_DEBUG_DRAW_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -239,6 +243,7 @@ struct b3VisualShapeData
char m_meshAssetFileName[VISUAL_SHAPE_MAX_PATH_LEN];
double m_localInertiaFrame[7];//pos[3], orn[4]
//todo: add more data if necessary (material color etc, although material can be in asset file .obj file)
double m_rgbaColor[4];
};
struct b3VisualShapeInformation

View File

@@ -527,7 +527,11 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const
visualShape.m_localInertiaFrame[4] = localInertiaFrame.getRotation()[1];
visualShape.m_localInertiaFrame[5] = localInertiaFrame.getRotation()[2];
visualShape.m_localInertiaFrame[6] = localInertiaFrame.getRotation()[3];
visualShape.m_rgbaColor[0] = rgbaColor[0];
visualShape.m_rgbaColor[1] = rgbaColor[1];
visualShape.m_rgbaColor[2] = rgbaColor[2];
visualShape.m_rgbaColor[3] = rgbaColor[3];
convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures, visualShape);
m_data->m_visualShapes.push_back(visualShape);
@@ -872,10 +876,14 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
return m_data->m_textures.size()-1;
}
void TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
{
int width,height,n;
unsigned char* image=0;
image = stbi_load(filename, &width, &height, &n, 3);
registerTexture(image, width, height);
if (image && (width>=0) && (height>=0))
{
return registerTexture(image, width, height);
}
return -1;
}

View File

@@ -38,7 +38,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
void render();
void render(const float viewMat[16], const float projMat[16]);
void loadTextureFile(const char* filename);
int loadTextureFile(const char* filename);
int registerTexture(unsigned char* texels, int width, int height);
void activateShapeTexture(int shapeUniqueId, int textureUniqueId);
void activateShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);

View File

@@ -94,7 +94,8 @@ int main(int argc, char *argv[])
switch (event.type)
{
case ENET_EVENT_TYPE_CONNECT:
case ENET_EVENT_TYPE_CONNECT:
{
printf("A new client connected from %x:%u.\n",
event.peer->address.host,
event.peer->address.port);
@@ -103,8 +104,9 @@ int main(int argc, char *argv[])
event.peer->data = (void*)"Client information";
break;
}
case ENET_EVENT_TYPE_RECEIVE:
{
if (gVerboseNetworkMessagesServer)
{
printf("A packet of length %u containing '%s' was "
@@ -171,8 +173,9 @@ int main(int argc, char *argv[])
//enet_host_broadcast(server, 0, event.packet);
break;
}
case ENET_EVENT_TYPE_DISCONNECT:
{
printf("%s disconnected.\n", event.peer->data);
/* Reset the peer's client information. */
@@ -180,6 +183,11 @@ int main(int argc, char *argv[])
event.peer->data = NULL;
break;
}
default:
{
}
}
}
else if (serviceResult > 0)