Merge remote-tracking branch 'upstream/master'
This commit is contained in:
@@ -672,6 +672,40 @@ int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHan
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_INIT_POSE);
|
||||
command->m_updateFlags |= INIT_POSE_HAS_BASE_LINEAR_VELOCITY;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[0] = 1;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[1] = 1;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[2] = 1;
|
||||
|
||||
command->m_initPoseArgs.m_initialStateQdot[0] = linVel[0];
|
||||
command->m_initPoseArgs.m_initialStateQdot[1] = linVel[1];
|
||||
command->m_initPoseArgs.m_initialStateQdot[2] = linVel[2];
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_INIT_POSE);
|
||||
command->m_updateFlags |= INIT_POSE_HAS_BASE_ANGULAR_VELOCITY;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[3] = 1;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[4] = 1;
|
||||
command->m_initPoseArgs.m_hasInitialStateQdot[5] = 1;
|
||||
|
||||
command->m_initPoseArgs.m_initialStateQdot[3] = angVel[0];
|
||||
command->m_initPoseArgs.m_initialStateQdot[4] = angVel[1];
|
||||
command->m_initPoseArgs.m_initialStateQdot[5] = angVel[2];
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
@@ -686,6 +720,8 @@ int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHand
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
@@ -1195,6 +1231,46 @@ int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle)
|
||||
return status->m_userDebugDrawArgs.m_debugItemUniqueId;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(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 = 0;
|
||||
return (b3SharedMemoryCommandHandle)command;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3])
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
|
||||
command->m_updateFlags |= USER_DEBUG_SET_CUSTOM_OBJECT_COLOR;
|
||||
command->m_userDebugDrawArgs.m_objectUniqueId = objectUniqueId;
|
||||
command->m_userDebugDrawArgs.m_linkIndex = linkIndex;
|
||||
command->m_userDebugDrawArgs.m_objectDebugColorRGB[0] = objectColorRGB[0];
|
||||
command->m_userDebugDrawArgs.m_objectDebugColorRGB[1] = objectColorRGB[1];
|
||||
command->m_userDebugDrawArgs.m_objectDebugColorRGB[2] = objectColorRGB[2];
|
||||
}
|
||||
|
||||
void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
|
||||
command->m_updateFlags |= USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR;
|
||||
command->m_userDebugDrawArgs.m_objectUniqueId = objectUniqueId;
|
||||
command->m_userDebugDrawArgs.m_linkIndex = linkIndex;
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
///request an image from a simulated camera, using a software renderer.
|
||||
b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient)
|
||||
@@ -1533,6 +1609,8 @@ b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClient
|
||||
command->m_requestContactPointArguments.m_startingContactPointIndex = 0;
|
||||
command->m_requestContactPointArguments.m_objectAIndexFilter = -1;
|
||||
command->m_requestContactPointArguments.m_objectBIndexFilter = -1;
|
||||
command->m_requestContactPointArguments.m_linkIndexAIndexFilter = -2;
|
||||
command->m_requestContactPointArguments.m_linkIndexBIndexFilter = -2;
|
||||
command->m_updateFlags = 0;
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
@@ -1545,6 +1623,37 @@ void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int body
|
||||
command->m_requestContactPointArguments.m_objectAIndexFilter = bodyUniqueIdA;
|
||||
}
|
||||
|
||||
void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
|
||||
command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER;
|
||||
command->m_requestContactPointArguments.m_linkIndexAIndexFilter= linkIndexA;
|
||||
}
|
||||
|
||||
void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION);
|
||||
command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER;
|
||||
command->m_requestContactPointArguments.m_linkIndexBIndexFilter = linkIndexB;
|
||||
}
|
||||
|
||||
void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA)
|
||||
{
|
||||
b3SetContactFilterLinkA(commandHandle, linkIndexA);
|
||||
}
|
||||
|
||||
void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB)
|
||||
{
|
||||
b3SetContactFilterLinkB(commandHandle, linkIndexB);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -89,9 +89,15 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle p
|
||||
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);
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient);
|
||||
void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]);
|
||||
void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex);
|
||||
|
||||
///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]);
|
||||
@@ -126,12 +132,16 @@ void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle comm
|
||||
b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient);
|
||||
void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA);
|
||||
void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
|
||||
void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA);
|
||||
void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB);
|
||||
void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo);
|
||||
|
||||
///compute the closest points between two bodies
|
||||
b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient);
|
||||
void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA);
|
||||
void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA);
|
||||
void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB);
|
||||
void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB);
|
||||
void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance);
|
||||
void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo);
|
||||
|
||||
@@ -248,6 +258,9 @@ int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, do
|
||||
b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex);
|
||||
int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ);
|
||||
int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW);
|
||||
int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]);
|
||||
int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]);
|
||||
|
||||
int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions);
|
||||
int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition);
|
||||
|
||||
|
||||
@@ -542,7 +542,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
m_kukaGripperMultiBody(0),
|
||||
m_kukaGripperRevolute1(0),
|
||||
m_kukaGripperRevolute2(0),
|
||||
m_allowRealTimeSimulation(true),
|
||||
m_allowRealTimeSimulation(false),
|
||||
m_huskyId(-1),
|
||||
m_KukaId(-1),
|
||||
m_sphereId(-1),
|
||||
@@ -2352,6 +2352,28 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
if (body && body->m_multiBody)
|
||||
{
|
||||
btMultiBody* mb = body->m_multiBody;
|
||||
btVector3 baseLinVel(0, 0, 0);
|
||||
btVector3 baseAngVel(0, 0, 0);
|
||||
|
||||
|
||||
if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_LINEAR_VELOCITY)
|
||||
{
|
||||
baseLinVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[0],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQdot[1],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQdot[2]);
|
||||
mb->setBaseVel(baseLinVel);
|
||||
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_ANGULAR_VELOCITY)
|
||||
{
|
||||
baseAngVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[3],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQdot[4],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQdot[5]);
|
||||
mb->setBaseOmega(baseAngVel);
|
||||
}
|
||||
|
||||
|
||||
if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION)
|
||||
{
|
||||
btVector3 zero(0,0,0);
|
||||
@@ -2359,7 +2381,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
clientCmd.m_initPoseArgs.m_hasInitialStateQ[1] &&
|
||||
clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]);
|
||||
|
||||
mb->setBaseVel(zero);
|
||||
mb->setBaseVel(baseLinVel);
|
||||
mb->setBasePos(btVector3(
|
||||
clientCmd.m_initPoseArgs.m_initialStateQ[0],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQ[1],
|
||||
@@ -2372,7 +2394,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
clientCmd.m_initPoseArgs.m_hasInitialStateQ[5] &&
|
||||
clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]);
|
||||
|
||||
mb->setBaseOmega(btVector3(0,0,0));
|
||||
mb->setBaseOmega(baseAngVel);
|
||||
btQuaternion invOrn(clientCmd.m_initPoseArgs.m_initialStateQ[3],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQ[4],
|
||||
clientCmd.m_initPoseArgs.m_initialStateQ[5],
|
||||
@@ -2784,6 +2806,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
int bodyUniqueIdA = clientCmd.m_requestContactPointArguments.m_objectAIndexFilter;
|
||||
int bodyUniqueIdB = clientCmd.m_requestContactPointArguments.m_objectBIndexFilter;
|
||||
|
||||
bool hasLinkIndexAFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER));
|
||||
bool hasLinkIndexBFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER));
|
||||
|
||||
int linkIndexA = clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter;
|
||||
int linkIndexB = clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter;
|
||||
|
||||
btAlignedObjectArray<btCollisionObject*> setA;
|
||||
btAlignedObjectArray<btCollisionObject*> setB;
|
||||
btAlignedObjectArray<int> setALinkIndex;
|
||||
@@ -2798,15 +2826,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
if (bodyA->m_multiBody->getBaseCollider())
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getBaseCollider());
|
||||
setALinkIndex.push_back(-1);
|
||||
if (!hasLinkIndexAFilter || (linkIndexA == -1))
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getBaseCollider());
|
||||
setALinkIndex.push_back(-1);
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < bodyA->m_multiBody->getNumLinks(); i++)
|
||||
{
|
||||
if (bodyA->m_multiBody->getLink(i).m_collider)
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getLink(i).m_collider);
|
||||
setALinkIndex.push_back(i);
|
||||
if (!hasLinkIndexAFilter || (linkIndexA == i))
|
||||
{
|
||||
setA.push_back(bodyA->m_multiBody->getLink(i).m_collider);
|
||||
setALinkIndex.push_back(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -2826,15 +2860,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
if (bodyB->m_multiBody->getBaseCollider())
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getBaseCollider());
|
||||
setBLinkIndex.push_back(-1);
|
||||
if (!hasLinkIndexBFilter || (linkIndexB == -1))
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getBaseCollider());
|
||||
setBLinkIndex.push_back(-1);
|
||||
}
|
||||
}
|
||||
for (int i = 0; i < bodyB->m_multiBody->getNumLinks(); i++)
|
||||
{
|
||||
if (bodyB->m_multiBody->getLink(i).m_collider)
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getLink(i).m_collider);
|
||||
setBLinkIndex.push_back(i);
|
||||
if (!hasLinkIndexBFilter || (linkIndexB ==i))
|
||||
{
|
||||
setB.push_back(bodyB->m_multiBody->getLink(i).m_collider);
|
||||
setBLinkIndex.push_back(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -3528,7 +3568,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
for( int i=0;i<numRb;i++)
|
||||
{
|
||||
btCollisionObject* colObj = importer->getRigidBodyByIndex(i);
|
||||
|
||||
if (colObj)
|
||||
{
|
||||
btRigidBody* rb = btRigidBody::upcast(colObj);
|
||||
@@ -3591,7 +3630,54 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
SharedMemoryStatus& serverCmd = serverStatusOut;
|
||||
serverCmd.m_type = CMD_USER_DEBUG_DRAW_FAILED;
|
||||
hasStatus = true;
|
||||
|
||||
|
||||
if ((clientCmd.m_updateFlags & USER_DEBUG_SET_CUSTOM_OBJECT_COLOR) || (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR))
|
||||
{
|
||||
int bodyUniqueId = clientCmd.m_userDebugDrawArgs.m_objectUniqueId;
|
||||
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
|
||||
if (body)
|
||||
{
|
||||
btCollisionObject* destColObj = 0;
|
||||
|
||||
if (body->m_multiBody)
|
||||
{
|
||||
if (clientCmd.m_userDebugDrawArgs.m_linkIndex == -1)
|
||||
{
|
||||
destColObj = body->m_multiBody->getBaseCollider();
|
||||
}
|
||||
else
|
||||
{
|
||||
if (clientCmd.m_userDebugDrawArgs.m_linkIndex >= 0 && clientCmd.m_userDebugDrawArgs.m_linkIndex < body->m_multiBody->getNumLinks())
|
||||
{
|
||||
destColObj = body->m_multiBody->getLink(clientCmd.m_userDebugDrawArgs.m_linkIndex).m_collider;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
if (body->m_rigidBody)
|
||||
{
|
||||
destColObj = body->m_rigidBody;
|
||||
}
|
||||
|
||||
if (destColObj)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR)
|
||||
{
|
||||
destColObj->removeCustomDebugColor();
|
||||
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
|
||||
}
|
||||
if (clientCmd.m_updateFlags & USER_DEBUG_SET_CUSTOM_OBJECT_COLOR)
|
||||
{
|
||||
btVector3 objectColorRGB;
|
||||
objectColorRGB.setValue(clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[0],
|
||||
clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[1],
|
||||
clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[2]);
|
||||
destColObj->setCustomDebugColor(objectColorRGB);
|
||||
serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & USER_DEBUG_HAS_TEXT)
|
||||
{
|
||||
|
||||
@@ -825,6 +825,7 @@ public:
|
||||
virtual bool wantsTermination();
|
||||
virtual bool isConnected();
|
||||
virtual void renderScene();
|
||||
void drawUserDebugLines();
|
||||
virtual void exitPhysics();
|
||||
|
||||
virtual void physicsDebugDraw(int debugFlags);
|
||||
@@ -1353,7 +1354,51 @@ extern int gHuskyId;
|
||||
extern btTransform huskyTr;
|
||||
|
||||
|
||||
void PhysicsServerExample::drawUserDebugLines()
|
||||
{
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
//draw all user-debug-lines
|
||||
|
||||
//add array of lines
|
||||
|
||||
//draw all user- 'text3d' messages
|
||||
if (m_multiThreadedHelper)
|
||||
{
|
||||
|
||||
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()->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);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void PhysicsServerExample::renderScene()
|
||||
{
|
||||
@@ -1369,48 +1414,8 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
|
||||
B3_PROFILE("PhysicsServerExample::RenderScene");
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
//draw all user-debug-lines
|
||||
|
||||
//add array of lines
|
||||
|
||||
//draw all user- 'text3d' messages
|
||||
if (m_multiThreadedHelper)
|
||||
{
|
||||
|
||||
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()->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);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
drawUserDebugLines();
|
||||
|
||||
if (gEnableRealTimeSimVR)
|
||||
{
|
||||
@@ -1424,6 +1429,7 @@ void PhysicsServerExample::renderScene()
|
||||
static int count = 0;
|
||||
count++;
|
||||
|
||||
#if 0
|
||||
if (0 == (count & 1))
|
||||
{
|
||||
btScalar curTime = m_clock.getTimeSeconds();
|
||||
@@ -1444,6 +1450,7 @@ void PhysicsServerExample::renderScene()
|
||||
worseFps = 1000000;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BT_ENABLE_VR
|
||||
if ((gInternalSimFlags&2 ) && m_tinyVrGui==0)
|
||||
@@ -1468,7 +1475,9 @@ void PhysicsServerExample::renderScene()
|
||||
tr = tr*b3Transform(b3Quaternion(0,0,-SIMD_HALF_PI),b3MakeVector3(0,0,0));
|
||||
b3Scalar dt = 0.01;
|
||||
m_tinyVrGui->clearTextArea();
|
||||
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
|
||||
m_tinyVrGui->grapicalPrintf(line0,0,0,0,0,0,255);
|
||||
m_tinyVrGui->grapicalPrintf(line1,0,16,255,255,255,255);
|
||||
|
||||
@@ -1544,6 +1553,8 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
|
||||
{
|
||||
drawUserDebugLines();
|
||||
|
||||
///debug rendering
|
||||
m_physicsServer.physicsDebugDraw(debugDrawFlags);
|
||||
|
||||
|
||||
@@ -109,7 +109,9 @@ enum EnumInitPoseFlags
|
||||
{
|
||||
INIT_POSE_HAS_INITIAL_POSITION=1,
|
||||
INIT_POSE_HAS_INITIAL_ORIENTATION=2,
|
||||
INIT_POSE_HAS_JOINT_STATE=4
|
||||
INIT_POSE_HAS_JOINT_STATE=4,
|
||||
INIT_POSE_HAS_BASE_LINEAR_VELOCITY = 8,
|
||||
INIT_POSE_HAS_BASE_ANGULAR_VELOCITY = 16,
|
||||
};
|
||||
|
||||
|
||||
@@ -122,6 +124,8 @@ struct InitPoseArgs
|
||||
int m_bodyUniqueId;
|
||||
int m_hasInitialStateQ[MAX_DEGREE_OF_FREEDOM];
|
||||
double m_initialStateQ[MAX_DEGREE_OF_FREEDOM];
|
||||
int m_hasInitialStateQdot[MAX_DEGREE_OF_FREEDOM];
|
||||
double m_initialStateQdot[MAX_DEGREE_OF_FREEDOM];
|
||||
};
|
||||
|
||||
|
||||
@@ -160,6 +164,8 @@ enum EnumRequestContactDataUpdateFlags
|
||||
{
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE=1,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_CLOSEST_DISTANCE_THRESHOLD=2,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER = 4,
|
||||
CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER = 8,
|
||||
};
|
||||
|
||||
struct RequestContactDataArgs
|
||||
@@ -167,6 +173,8 @@ struct RequestContactDataArgs
|
||||
int m_startingContactPointIndex;
|
||||
int m_objectAIndexFilter;
|
||||
int m_objectBIndexFilter;
|
||||
int m_linkIndexAIndexFilter;
|
||||
int m_linkIndexBIndexFilter;
|
||||
double m_closestDistanceThreshold;
|
||||
int m_mode;
|
||||
};
|
||||
@@ -526,7 +534,10 @@ enum EnumUserDebugDrawFlags
|
||||
USER_DEBUG_HAS_LINE=1,
|
||||
USER_DEBUG_HAS_TEXT=2,
|
||||
USER_DEBUG_REMOVE_ONE_ITEM=4,
|
||||
USER_DEBUG_REMOVE_ALL=8
|
||||
USER_DEBUG_REMOVE_ALL=8,
|
||||
USER_DEBUG_SET_CUSTOM_OBJECT_COLOR = 16,
|
||||
USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR = 32,
|
||||
|
||||
};
|
||||
|
||||
struct UserDebugDrawArgs
|
||||
@@ -543,6 +554,10 @@ struct UserDebugDrawArgs
|
||||
double m_textPositionXYZ[3];
|
||||
double m_textColorRGB[3];
|
||||
double m_textSize;
|
||||
|
||||
double m_objectDebugColorRGB[3];
|
||||
int m_objectUniqueId;
|
||||
int m_linkIndex;
|
||||
};
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user