improvements to the shared memory physics API:
support picking in C API etc.
This commit is contained in:
@@ -139,11 +139,11 @@ b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle phy
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
|
||||
int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
command->m_sendDesiredStateCommandArgument.m_desiredStateQ[dofIndex] = value;
|
||||
command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value;
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -200,6 +200,19 @@ b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandl
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
void b3GetJointState(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int jointIndex, b3JointSensorState *state)
|
||||
{
|
||||
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
|
||||
b3Assert(status);
|
||||
b3JointInfo info;
|
||||
b3GetJointInfo(physClient, jointIndex, &info);
|
||||
state->m_jointPosition = status->m_sendActualStateArgs.m_actualStateQ[info.m_qIndex];
|
||||
state->m_jointVelocity = status->m_sendActualStateArgs.m_actualStateQdot[info.m_uIndex];
|
||||
for (int ii(0); ii < 6; ++ii) {
|
||||
state->m_jointForceTorque[ii] = status->m_sendActualStateArgs.m_jointReactionForces[6 * jointIndex + ii];
|
||||
}
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3CreateBoxShapeCommandInit(b3PhysicsClientHandle physClient)
|
||||
{
|
||||
PhysicsClientSharedMemory* cl = (PhysicsClientSharedMemory* ) physClient;
|
||||
@@ -379,7 +392,43 @@ void b3GetJointInfo(b3PhysicsClientHandle physClient, int linkIndex, struct b3Jo
|
||||
cl->getJointInfo(linkIndex,*info);
|
||||
}
|
||||
|
||||
int b3PickBody(struct SharedMemoryCommand *command,
|
||||
double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ,
|
||||
double rayToWorldX, double rayToWorldY, double rayToWorldZ)
|
||||
{
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_PICK_BODY);
|
||||
command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
|
||||
command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
|
||||
command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
|
||||
command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
|
||||
command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
|
||||
command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3MovePickedBody(struct SharedMemoryCommand *command,
|
||||
double rayFromWorldX, double rayFromWorldY, double rayFromWorldZ,
|
||||
double rayToWorldX, double rayToWorldY, double rayToWorldZ)
|
||||
{
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_MOVE_PICKED_BODY);
|
||||
command->m_pickBodyArguments.m_rayFromWorld[0] = rayFromWorldX;
|
||||
command->m_pickBodyArguments.m_rayFromWorld[1] = rayFromWorldY;
|
||||
command->m_pickBodyArguments.m_rayFromWorld[2] = rayFromWorldZ;
|
||||
command->m_pickBodyArguments.m_rayToWorld[0] = rayToWorldX;
|
||||
command->m_pickBodyArguments.m_rayToWorld[1] = rayToWorldY;
|
||||
command->m_pickBodyArguments.m_rayToWorld[2] = rayToWorldZ;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3RemovePickingConstraint(b3SharedMemoryCommandHandle commandHandle)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_REMOVE_PICKING_CONSTRAINT_BODY);
|
||||
return 0;
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitRequestDebugLinesCommand(b3PhysicsClientHandle physClient, int debugMode)
|
||||
{
|
||||
@@ -409,4 +458,3 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user