This commit is contained in:
Erwin Coumans
2018-07-08 11:24:37 +02:00
19 changed files with 5055 additions and 9 deletions

View File

@@ -5,7 +5,7 @@
<worldbody> <worldbody>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/> <light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/> <geom type="plane" size="1 1 0.1" rgba=".9 0 0 1"/>
<body pos="0 0 1"> <body name="capsule" pos="0 0 1">
<joint type="free"/> <joint type="free"/>
<geom name="aux_1_geom" size="0.05 0.1" type="capsule"/> <geom name="aux_1_geom" size="0.05 0.1" type="capsule"/>
</body> </body>

View File

@@ -752,6 +752,8 @@ enum eCONNECT_METHOD {
eCONNECT_GUI_SERVER=7, eCONNECT_GUI_SERVER=7,
eCONNECT_GUI_MAIN_THREAD=8, eCONNECT_GUI_MAIN_THREAD=8,
eCONNECT_SHARED_MEMORY_SERVER=9, eCONNECT_SHARED_MEMORY_SERVER=9,
eCONNECT_DART=10,
eCONNECT_MUJOCO=11,
}; };
enum eURDF_Flags enum eURDF_Flags

View File

@@ -0,0 +1,16 @@
#ifdef BT_ENABLE_DART
#include "DARTPhysicsC_API.h"
#include "DARTPhysicsServerCommandProcessor.h"
#include "DARTPhysicsClient.h"
//think more about naming. The b3ConnectPhysicsLoopback
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsDART()
{
DARTPhysicsServerCommandProcessor* sdk = new DARTPhysicsServerCommandProcessor;
DARTPhysicsClient* direct = new DARTPhysicsClient(sdk,true);
bool connected;
connected = direct->connect();
return (b3PhysicsClientHandle )direct;
}
#endif//BT_ENABLE_DART

View File

@@ -0,0 +1,20 @@
#ifndef DART_PHYSICS_C_API_H
#define DART_PHYSICS_C_API_H
#ifdef BT_ENABLE_DART
#include "../PhysicsClientC_API.h"
#ifdef __cplusplus
extern "C" {
#endif
//think more about naming. The b3ConnectPhysicsLoopback
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsDART();
#ifdef __cplusplus
}
#endif
#endif //BT_ENABLE_DART
#endif //DART_PHYSICS_C_API_H

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,124 @@
#ifndef DART_PHYSICS_CLIENT_H
#define DART_PHYSICS_CLIENT_H
#include "../PhysicsClient.h"
///PhysicsDirect executes the commands directly, without transporting them or having a separate server executing commands
class DARTPhysicsClient : public PhysicsClient
{
protected:
struct DARTPhysicsDirectInternalData* m_data;
bool processDebugLines(const struct SharedMemoryCommand& orgCommand);
bool processCamera(const struct SharedMemoryCommand& orgCommand);
bool processContactPointData(const struct SharedMemoryCommand& orgCommand);
bool processOverlappingObjects(const struct SharedMemoryCommand& orgCommand);
bool processVisualShapeData(const struct SharedMemoryCommand& orgCommand);
void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd);
void processAddUserData(const struct SharedMemoryStatus& serverCmd);
void postProcessStatus(const struct SharedMemoryStatus& serverCmd);
void resetData();
void removeCachedBody(int bodyUniqueId);
public:
DARTPhysicsClient(class PhysicsCommandProcessorInterface* physSdk, bool passSdkOwnership);
virtual ~DARTPhysicsClient();
// return true if connection succesfull, can also check 'isConnected'
//it is OK to pass a null pointer for the gui helper
virtual bool connect();
////todo: rename to 'disconnect'
virtual void disconnectSharedMemory();
virtual bool isConnected() const;
// return non-null if there is a status, nullptr otherwise
virtual const SharedMemoryStatus* processServerStatus();
virtual SharedMemoryCommand* getAvailableSharedMemoryCommand();
virtual bool canSubmitCommand() const;
virtual bool submitClientCommand(const struct SharedMemoryCommand& command);
virtual int getNumBodies() const;
virtual int getBodyUniqueId(int serialIndex) const;
virtual bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo& info) const;
virtual int getNumJoints(int bodyIndex) const;
virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const;
virtual int getNumUserConstraints() const;
virtual int getUserConstraintInfo(int constraintUniqueId, struct b3UserConstraint& info) const;
virtual int getUserConstraintId(int serialIndex) const;
///todo: move this out of the
virtual void setSharedMemoryKey(int key);
void uploadBulletFileToSharedMemory(const char* data, int len);
virtual void uploadRaysToSharedMemory(struct SharedMemoryCommand& command, const double* rayFromWorldArray, const double* rayToWorldArray, int numRays);
virtual int getNumDebugLines() const;
virtual const float* getDebugLinesFrom() const;
virtual const float* getDebugLinesTo() const;
virtual const float* getDebugLinesColor() const;
virtual void getCachedCameraImage(b3CameraImageData* cameraData);
virtual void getCachedContactPointInformation(struct b3ContactInformation* contactPointData);
virtual void getCachedOverlappingObjects(struct b3AABBOverlapData* overlappingObjects);
virtual void getCachedVisualShapeInformation(struct b3VisualShapeInformation* visualShapesInfo);
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData);
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix);
//the following APIs are for internal use for visualization:
virtual bool connect(struct GUIHelperInterface* guiHelper);
virtual void renderScene();
virtual void debugDraw(int debugDrawMode);
virtual void setTimeOut(double timeOutInSeconds);
virtual double getTimeOut() const;
virtual bool getCachedUserData(int bodyUniqueId, int linkIndex, int userDataId, struct b3UserDataValue &valueOut) const;
virtual int getCachedUserDataId(int bodyUniqueId, int linkIndex, const char *key) const;
virtual int getNumUserData(int bodyUniqueId, int linkIndex) const;
virtual void getUserDataInfo(int bodyUniqueId, int linkIndex, int userDataIndex, const char **keyOut, int *userDataIdOut) const;
virtual void pushProfileTiming(const char* timingName);
virtual void popProfileTiming();
};
#endif //DART_PHYSICS__H

View File

@@ -0,0 +1,39 @@
#include "DARTPhysicsServerCommandProcessor.h"
DARTPhysicsServerCommandProcessor::DARTPhysicsServerCommandProcessor()
{
}
DARTPhysicsServerCommandProcessor::~DARTPhysicsServerCommandProcessor()
{
}
bool DARTPhysicsServerCommandProcessor::connect()
{
return false;
}
void DARTPhysicsServerCommandProcessor::disconnect()
{
}
bool DARTPhysicsServerCommandProcessor::isConnected() const
{
return false;
}
bool DARTPhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
return false;
}
bool DARTPhysicsServerCommandProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
return false;
}

View File

@@ -0,0 +1,31 @@
#ifndef DART_PHYSICS_SERVER_COMMAND_PROCESSOR_H
#define DART_PHYSICS_SERVER_COMMAND_PROCESSOR_H
#include "../PhysicsCommandProcessorInterface.h"
class DARTPhysicsServerCommandProcessor : public PhysicsCommandProcessorInterface
{
public:
DARTPhysicsServerCommandProcessor();
virtual ~DARTPhysicsServerCommandProcessor();
virtual bool connect();
virtual void disconnect();
virtual bool isConnected() const;
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene(int renderFlags){}
virtual void physicsDebugDraw(int debugDrawFlags){}
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper){}
virtual void setTimeOut(double timeOutInSeconds){}
};
#endif //DART_PHYSICS_COMMAND_PROCESSOR_H

View File

@@ -0,0 +1,15 @@
#ifdef BT_ENABLE_MUJOCO
#include "MuJoCoPhysicsC_API.h"
#include "MuJoCoPhysicsServerCommandProcessor.h"
#include "MuJoCoPhysicsClient.h"
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsMuJoCo()
{
MuJoCoPhysicsServerCommandProcessor* sdk = new MuJoCoPhysicsServerCommandProcessor;
MuJoCoPhysicsClient* direct = new MuJoCoPhysicsClient(sdk,true);
bool connected;
connected = direct->connect();
return (b3PhysicsClientHandle )direct;
}
#endif//BT_ENABLE_MUJOCO

View File

@@ -0,0 +1,20 @@
#ifndef MUJOCO_PHYSICS_C_API_H
#define MUJOCO_PHYSICS_C_API_H
#ifdef BT_ENABLE_MUJOCO
#include "../PhysicsClientC_API.h"
#ifdef __cplusplus
extern "C" {
#endif
//think more about naming. The b3ConnectPhysicsLoopback
B3_SHARED_API b3PhysicsClientHandle b3ConnectPhysicsMuJoCo();
#ifdef __cplusplus
}
#endif
#endif //BT_ENABLE_MUJOCO
#endif //MUJOCO_PHYSICS_C_API_H

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,123 @@
#ifndef MUJOCO_PHYSICS_CLIENT_H
#define MUJOCO_PHYSICS_CLIENT_H
#include "../PhysicsClient.h"
///PhysicsDirect executes the commands directly, without transporting them or having a separate server executing commands
class MuJoCoPhysicsClient : public PhysicsClient
{
protected:
struct MuJoCoPhysicsDirectInternalData* m_data;
bool processDebugLines(const struct SharedMemoryCommand& orgCommand);
bool processCamera(const struct SharedMemoryCommand& orgCommand);
bool processContactPointData(const struct SharedMemoryCommand& orgCommand);
bool processOverlappingObjects(const struct SharedMemoryCommand& orgCommand);
bool processVisualShapeData(const struct SharedMemoryCommand& orgCommand);
void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd);
void processAddUserData(const struct SharedMemoryStatus& serverCmd);
void postProcessStatus(const struct SharedMemoryStatus& serverCmd);
void resetData();
void removeCachedBody(int bodyUniqueId);
public:
MuJoCoPhysicsClient(class PhysicsCommandProcessorInterface* physSdk, bool passSdkOwnership);
virtual ~MuJoCoPhysicsClient();
// return true if connection succesfull, can also check 'isConnected'
//it is OK to pass a null pointer for the gui helper
virtual bool connect();
////todo: rename to 'disconnect'
virtual void disconnectSharedMemory();
virtual bool isConnected() const;
// return non-null if there is a status, nullptr otherwise
virtual const SharedMemoryStatus* processServerStatus();
virtual SharedMemoryCommand* getAvailableSharedMemoryCommand();
virtual bool canSubmitCommand() const;
virtual bool submitClientCommand(const struct SharedMemoryCommand& command);
virtual int getNumBodies() const;
virtual int getBodyUniqueId(int serialIndex) const;
virtual bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo& info) const;
virtual int getNumJoints(int bodyIndex) const;
virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const;
virtual int getNumUserConstraints() const;
virtual int getUserConstraintInfo(int constraintUniqueId, struct b3UserConstraint& info) const;
virtual int getUserConstraintId(int serialIndex) const;
///todo: move this out of the
virtual void setSharedMemoryKey(int key);
void uploadBulletFileToSharedMemory(const char* data, int len);
virtual void uploadRaysToSharedMemory(struct SharedMemoryCommand& command, const double* rayFromWorldArray, const double* rayToWorldArray, int numRays);
virtual int getNumDebugLines() const;
virtual const float* getDebugLinesFrom() const;
virtual const float* getDebugLinesTo() const;
virtual const float* getDebugLinesColor() const;
virtual void getCachedCameraImage(b3CameraImageData* cameraData);
virtual void getCachedContactPointInformation(struct b3ContactInformation* contactPointData);
virtual void getCachedOverlappingObjects(struct b3AABBOverlapData* overlappingObjects);
virtual void getCachedVisualShapeInformation(struct b3VisualShapeInformation* visualShapesInfo);
virtual void getCachedCollisionShapeInformation(struct b3CollisionShapeInformation* collisionShapesInfo);
virtual void getCachedVREvents(struct b3VREventsData* vrEventsData);
virtual void getCachedKeyboardEvents(struct b3KeyboardEventsData* keyboardEventsData);
virtual void getCachedMouseEvents(struct b3MouseEventsData* mouseEventsData);
virtual void getCachedRaycastHits(struct b3RaycastInformation* raycastHits);
virtual void getCachedMassMatrix(int dofCountCheck, double* massMatrix);
//the following APIs are for internal use for visualization:
virtual bool connect(struct GUIHelperInterface* guiHelper);
virtual void renderScene();
virtual void debugDraw(int debugDrawMode);
virtual void setTimeOut(double timeOutInSeconds);
virtual double getTimeOut() const;
virtual bool getCachedUserData(int bodyUniqueId, int linkIndex, int userDataId, struct b3UserDataValue &valueOut) const;
virtual int getCachedUserDataId(int bodyUniqueId, int linkIndex, const char *key) const;
virtual int getNumUserData(int bodyUniqueId, int linkIndex) const;
virtual void getUserDataInfo(int bodyUniqueId, int linkIndex, int userDataIndex, const char **keyOut, int *userDataIdOut) const;
virtual void pushProfileTiming(const char* timingName);
virtual void popProfileTiming();
};
#endif //MUJOCO_PHYSICS_CLIENT_H

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,45 @@
#ifndef MUJOCO_PHYSICS_SERVER_COMMAND_PROCESSOR_H
#define MUJOCO_PHYSICS_SERVER_COMMAND_PROCESSOR_H
#include "../PhysicsCommandProcessorInterface.h"
class MuJoCoPhysicsServerCommandProcessor : public PhysicsCommandProcessorInterface
{
struct MuJoCoPhysicsServerCommandProcessorInternalData* m_data;
bool processSyncBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestInternalDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processSyncUserDataCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processLoadMJCFCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestBodyInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processSendPhysicsParametersCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestActualStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processResetSimulationCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
void resetSimulation();
public:
MuJoCoPhysicsServerCommandProcessor();
virtual ~MuJoCoPhysicsServerCommandProcessor();
virtual bool connect();
virtual void disconnect();
virtual bool isConnected() const;
virtual bool processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
virtual void renderScene(int renderFlags){}
virtual void physicsDebugDraw(int debugDrawFlags){}
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper){}
virtual void setTimeOut(double timeOutInSeconds){}
};
#endif //MUJOCO_PHYSICS_COMMAND_PROCESSOR_H

View File

@@ -178,13 +178,16 @@ int main(int argc, char *argv[])
SharedMemoryCommand* cmdPtr = 0; SharedMemoryCommand* cmdPtr = 0;
int type = *(int*)&bytesReceived[0];
//performance test //performance test
if (numBytesRec == sizeof(int)) if (numBytesRec == sizeof(int))
{ {
cmdPtr = &cmd; cmdPtr = &cmd;
cmd.m_type = *(int*)&bytesReceived[0]; cmd.m_type = *(int*)&bytesReceived[0];
} }
else
{
if (numBytesRec == sizeof(SharedMemoryCommand)) if (numBytesRec == sizeof(SharedMemoryCommand))
{ {
@@ -192,7 +195,12 @@ int main(int argc, char *argv[])
} }
else else
{ {
cmdPtr = (SharedMemoryCommand*)&bytesReceived[0]; if (numBytesRec==36)
{
cmdPtr = &cmd;
memcpy(&cmd, &bytesReceived[0], numBytesRec);
}
}
} }
if (cmdPtr) if (cmdPtr)
{ {

View File

@@ -0,0 +1,40 @@
import pybullet as p
import pybullet_data
import os
import time
GRAVITY = -9.8
dt = 1e-3
iters=2000
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
#p.setRealTimeSimulation(True)
p.setGravity(0,0,GRAVITY)
p.setTimeStep(dt)
planeId = p.loadURDF("plane.urdf")
cubeStartPos = [0,0,1.13]
cubeStartOrientation = p.getQuaternionFromEuler([0.,0,0])
botId = p.loadURDF("biped/biped2d_pybullet.urdf",
cubeStartPos,
cubeStartOrientation)
#disable the default velocity motors
#and set some position control with small force to emulate joint friction/return to a rest pose
jointFrictionForce=1
for joint in range (p.getNumJoints(botId)):
p.setJointMotorControl2(botId,joint,p.POSITION_CONTROL,force=jointFrictionForce)
#for i in range(10000):
# p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
# p.stepSimulation()
#import ipdb
#ipdb.set_trace()
import time
p.setRealTimeSimulation(1)
while (1):
#p.stepSimulation()
#p.setJointMotorControl2(botId, 1, p.TORQUE_CONTROL, force=1098.0)
p.setGravity(0,0,GRAVITY)
time.sleep(1/240.)
time.sleep(1000)

View File

@@ -0,0 +1,32 @@
import pybullet as p
import time
#p.connect(p.DIRECT)
#p.connect(p.DART)
p.connect(p.MuJoCo)
#p.connect(p.GUI)
bodies = p.loadMJCF("mjcf/capsule.xml")
print("bodies=",bodies)
numBodies = p.getNumBodies()
print("numBodies=",numBodies)
for i in range (numBodies):
print("bodyInfo[",i,"]=",p.getBodyInfo(i))
p.setGravity(0,0,-10)
timeStep = 1./240.
p.setPhysicsEngineParameter(fixedTimeStep=timeStep)
#while (p.isConnected()):
for i in range (1000):
p.stepSimulation()
for b in bodies:
pos,orn=p.getBasePositionAndOrientation(b)
print("pos[",b,"]=",pos)
print("orn[",b,"]=",orn)
linvel,angvel=p.getBaseVelocity(b)
print("linvel[",b,"]=",linvel)
print("angvel[",b,"]=",angvel)
time.sleep(timeStep)

View File

@@ -0,0 +1,273 @@
<?xml version="1.0"?>
<robot name="balance">
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<material name="black">
<color rgba="0.2 0.2 0.2 1"/>
</material>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
<link name="world">
<inertial>
<mass value="0"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<link name="y_prismatic">
<inertial>
<mass value="0.01"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="y_to_world" type="prismatic">
<parent link="world"/>
<child link="y_prismatic"/>
<axis xyz="0 1 0"/>
<limit effort="0.0" lower="1" upper="-1" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="z_prismatic">
<inertial>
<mass value="0.01"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</inertial>
</link>
<joint name="z_to_y" type="prismatic">
<parent link="y_prismatic"/>
<child link="z_prismatic"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="1" upper="-1" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<joint name="torso_to_z" type="continuous">
<parent link="z_prismatic"/>
<child link="torso"/>
<axis xyz="1 0 0"/>
<origin rpy="0 0 0" xyz="0 0 1.4"/>
</joint>
<link name="torso">
<visual>
<geometry>
<box size="0.1 0.1 0.48"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="0.1 0.1 0.48"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0.0 0"/>
<contact_coefficients mu="0.08" />
</collision>
<inertial>
<mass value="70"/>
<inertia ixx="0.2404" ixy="-0.01" ixz="-0.048" iyy="0.2404" iyz="-0.048" izz="0.02"/>
<origin rpy="0 0 0" xyz="0 0.0 0"/>
</inertial>
</link>
<link name="r_upperleg">
<visual>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="0.018 0. -0.21715"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="0.018 -0.0 -0.21715"/>
<contact_coefficients mu="0.08" />
</collision>
<inertial>
<mass value="5"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="0.018 -0 -0.21715"/>
</inertial>
</link>
<joint name="torso_to_rightleg" type="revolute">
<parent link="torso"/>
<child link="r_upperleg"/>
<axis xyz="1 0 0"/>
<limit effort="0.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="0.05 0 -0.17"/>
</joint>
<link name="l_upperleg">
<visual>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.018 0. -0.21715"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.018 0.0 -0.21715"/>
<contact_coefficients mu="0.08" />
</collision>
<inertial>
<mass value="5"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="-0.018 -0 -0.21715"/>
</inertial>
</link>
<joint name="torso_to_leftleg" type="revolute">
<parent link="torso"/>
<child link="l_upperleg"/>
<axis xyz="1 0 0"/>
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="-0.05 0 -0.17"/>
</joint>
<link name="r_lowerleg">
<visual>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="0.048 0. -0.21715"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="0.048 0.0 -0.21715"/>
<contact_coefficients mu="0.08" />
</collision>
<inertial>
<mass value="4"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="0.048 -0 -0.21715"/>
</inertial>
</link>
<joint name="r_knee" type="revolute">
<parent link="r_upperleg"/>
<child link="r_lowerleg"/>
<axis xyz="1 0 0"/>
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="0.015 0 -.41"/>
</joint>
<link name="l_lowerleg">
<visual>
<geometry>
<box size="0.05 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.048 0. -0.21715"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="0.1 0.1 .45"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.048 0.0 -0.21715"/>
<contact_coefficients mu="0.08" />
</collision>
<inertial>
<mass value="4"/>
<inertia ixx="0.2125" ixy="-0.005" ixz="0.0225" iyy="0.205" iyz="0.045" izz="0.0125"/>
<origin rpy="0 0 0" xyz="-0.048 -0 -0.21715"/>
</inertial>
</link>
<joint name="l_knee" type="revolute">
<parent link="l_upperleg"/>
<child link="l_lowerleg"/>
<axis xyz="1 0 0"/>
<limit effort="10.0" lower="-1.57." upper="1.57" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="-0.015 0 -.41"/>
</joint>
<link name="l_foot">
<visual>
<geometry>
<box size="0.05 0.2 .04"/>
</geometry>
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="0.05 0.2 .04"/>
</geometry>
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
<contact_coefficients mu="0.5" />
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.0416" ixy="-0.01" ixz="-0.002" iyy="0.0041" iyz="-0.008" izz="0.0425"/>
<origin rpy="0 0 0" xyz="0.05 0.08 -0.038"/>
</inertial>
</link>
<joint name="l_ankle" type="revolute">
<parent link="l_lowerleg"/>
<child link="l_foot"/>
<axis xyz="1 0 0"/>
<limit effort="10.0" lower="-2" upper="2" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="-0.05 -0.03 -.459"/>
</joint>
<link name="r_foot">
<visual>
<geometry>
<box size="0.05 0.2 .04"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="0.05 0.2 .04"/>
</geometry>
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
<contact_coefficients mu="0.5" />
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="0.0416" ixy="-0.01" ixz="-0.002" iyy="0.0041" iyz="-0.008" izz="0.0425"/>
<origin rpy="0 0 0" xyz="-0.05 0.08 -0.038"/>
</inertial>
</link>
<joint name="r_ankle" type="revolute">
<parent link="r_lowerleg"/>
<child link="r_foot"/>
<axis xyz="1 0 0"/>
<limit effort="10.0" lower="-2." upper="2" velocity="1000.0"/>
<origin rpy="0 0 0" xyz="0.05 -0.03 -.459"/>
</joint>
</robot>

View File

@@ -5,6 +5,14 @@
#include "../SharedMemory/PhysicsClientUDP_C_API.h" #include "../SharedMemory/PhysicsClientUDP_C_API.h"
#endif //BT_ENABLE_ENET #endif //BT_ENABLE_ENET
#ifdef BT_ENABLE_DART
#include "../SharedMemory/dart/DARTPhysicsC_API.h"
#endif
#ifdef BT_ENABLE_MUJOCO
#include "../SharedMemory/mujoco/MuJoCoPhysicsC_API.h"
#endif
#ifdef BT_ENABLE_CLSOCKET #ifdef BT_ENABLE_CLSOCKET
#include "../SharedMemory/PhysicsClientTCP_C_API.h" #include "../SharedMemory/PhysicsClientTCP_C_API.h"
#endif //BT_ENABLE_CLSOCKET #endif //BT_ENABLE_CLSOCKET
@@ -407,6 +415,22 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
sm = b3ConnectPhysicsDirect(); sm = b3ConnectPhysicsDirect();
break; break;
} }
#ifdef BT_ENABLE_DART
case eCONNECT_DART:
{
sm = b3ConnectPhysicsDART();
break;
}
#endif
#ifdef BT_ENABLE_MUJOCO
case eCONNECT_MUJOCO:
{
sm = b3ConnectPhysicsMuJoCo();
break;
}
#endif
case eCONNECT_SHARED_MEMORY: case eCONNECT_SHARED_MEMORY:
{ {
sm = b3ConnectSharedMemory(key); sm = b3ConnectSharedMemory(key);
@@ -9558,6 +9582,14 @@ initpybullet(void)
PyModule_AddIntConstant(m, "GUI_SERVER", eCONNECT_GUI_SERVER); // user read PyModule_AddIntConstant(m, "GUI_SERVER", eCONNECT_GUI_SERVER); // user read
PyModule_AddIntConstant(m, "GUI_MAIN_THREAD", eCONNECT_GUI_MAIN_THREAD); // user read PyModule_AddIntConstant(m, "GUI_MAIN_THREAD", eCONNECT_GUI_MAIN_THREAD); // user read
PyModule_AddIntConstant(m, "SHARED_MEMORY_SERVER", eCONNECT_SHARED_MEMORY_SERVER); // user read PyModule_AddIntConstant(m, "SHARED_MEMORY_SERVER", eCONNECT_SHARED_MEMORY_SERVER); // user read
#ifdef BT_ENABLE_DART
PyModule_AddIntConstant(m, "DART", eCONNECT_DART); // user read
#endif
#ifdef BT_ENABLE_MUJOCO
PyModule_AddIntConstant(m, "MuJoCo", eCONNECT_MUJOCO); // user read
#endif
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY); PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY);
PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY2", SHARED_MEMORY_KEY+1); PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY2", SHARED_MEMORY_KEY+1);