Merge branch 'master' into cmake-option-per-extra

This commit is contained in:
Alexander Turkin 2021-04-14 13:41:19 +03:00
commit f04768ecc4
311 changed files with 57948 additions and 260 deletions

View File

@ -30,6 +30,8 @@ OPTION(BUILD_SHARED_LIBS "Use shared libraries" OFF)
OPTION(USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD "Use btSoftMultiBodyDynamicsWorld" ON)
OPTION(USE_OPENVR "Use OpenVR for virtual reality" OFF)
OPTION(ENABLE_VHACD "Use VHACD in BulletRobotics and pybullet" ON)
OPTION(BULLET2_MULTITHREADING "Build Bullet 2 libraries with mutex locking around certain operations (required for multi-threading)" OFF)
IF (BULLET2_MULTITHREADING)
OPTION(BULLET2_USE_OPEN_MP_MULTITHREADING "Build Bullet 2 with support for multi-threading with OpenMP (requires a compiler with OpenMP support)" OFF)

View File

@ -7,6 +7,9 @@ INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
)
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
SET(BulletRobotics_INCLUDES
../../examples/CommonInterfaces/Common2dCanvasInterface.h
@ -94,70 +97,103 @@ SET(BulletRobotics_INCLUDES
)
SET(BulletRobotics_SRCS ${BulletRobotics_INCLUDES}
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoGUI.cpp
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/b3Clock.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/ChromeTraceUtil.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/b3Clock.cpp
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/ChromeTraceUtil.cpp
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp
../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp
../../examples/ThirdPartyLibs/BussIK/Misc.cpp
../../examples/ThirdPartyLibs/BussIK/Node.cpp
../../examples/ThirdPartyLibs/BussIK/Tree.cpp
../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/ThirdPartyLibs/BussIK/Jacobian.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR2.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR3.cpp
../../examples/ThirdPartyLibs/BussIK/LinearR4.cpp
../../examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp
../../examples/ThirdPartyLibs/BussIK/Misc.cpp
../../examples/ThirdPartyLibs/BussIK/Node.cpp
../../examples/ThirdPartyLibs/BussIK/Tree.cpp
../../examples/ThirdPartyLibs/BussIK/VectorRn.cpp
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
)
IF(ENABLE_VHACD)
ADD_DEFINITIONS(-DBT_ENABLE_VHACD)
SET(BulletRobotics_SRCS ${BulletRobotics_SRCS}
../../Extras/VHACD/test/src/main_vhacd.cpp
../../Extras/VHACD/src/VHACD.cpp
../../Extras/VHACD/src/vhacdICHull.cpp
../../Extras/VHACD/src/vhacdManifoldMesh.cpp
../../Extras/VHACD/src/vhacdMesh.cpp
../../Extras/VHACD/src/vhacdVolume.cpp
)
INCLUDE_DIRECTORIES(
../../Extras/VHACD/inc
../../Extras/VHACD/public
)
ENDIF(ENABLE_VHACD)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
ENDIF(BUILD_CLSOCKET)

View File

@ -94,21 +94,6 @@ SET(BulletRoboticsGUI_INCLUDES
)
SET(BulletRoboticsGUI_SRCS ${BulletRoboticsGUI_INCLUDES}
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/SpAlg.h
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/Shape.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/RBDModel.h
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/MathUtil.h
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/KinTree.h
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.cpp
../../examples/SharedMemory/plugins/stablePDPlugin/BulletConversion.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/GraphicsServerExample.cpp
../../examples/SharedMemory/GraphicsClientExample.cpp

View File

@ -643,8 +643,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk)
if ((strcmp(oldType, "btShortIntIndexData") == 0))
{
int allocLen = 2;
char *dataAlloc = new char[(dataChunk.nr * allocLen) + 1];
memset(dataAlloc, 0, (dataChunk.nr * allocLen) + 1);
char *dataAlloc = new char[(dataChunk.nr * allocLen) + sizeof(void*)];
memset(dataAlloc, 0, (dataChunk.nr * allocLen) + sizeof(void*));
short *dest = (short *)dataAlloc;
const short *src = (short *)head;
for (int i = 0; i < dataChunk.nr; i++)
@ -682,8 +682,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk)
// numBlocks * length
int allocLen = (curLen);
char *dataAlloc = new char[(dataChunk.nr * allocLen) + 1];
memset(dataAlloc, 0, (dataChunk.nr * allocLen));
char *dataAlloc = new char[(dataChunk.nr * allocLen) + sizeof(void*)];
memset(dataAlloc, 0, (dataChunk.nr * allocLen) + sizeof(void*));
// track allocated
addDataBlock(dataAlloc);
@ -719,8 +719,8 @@ char *bFile::readStruct(char *head, bChunkInd &dataChunk)
#endif //
}
char *dataAlloc = new char[(dataChunk.len) + 1];
memset(dataAlloc, 0, dataChunk.len + 1);
char *dataAlloc = new char[(dataChunk.len) + sizeof(void*)];
memset(dataAlloc, 0, dataChunk.len + sizeof(void*));
// track allocated
addDataBlock(dataAlloc);

View File

@ -7,8 +7,11 @@ This is the official C++ source code repository of the Bullet Physics SDK: real-
![PyBullet](https://pybullet.org/wordpress/wp-content/uploads/2019/03/cropped-pybullet.png)
## Issues ##
The Issue tracker was flooded with support questions and is closed until it is cleaned up. Use the [PyBullet forums](http://pybullet.org) to discuss with others.
## PyBullet ##
New in Bullet 2.85: pybullet Python bindings, improved support for robotics and VR. Use pip install pybullet and checkout the [PyBullet Quickstart Guide](https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.2ye70wns7io3).
It is highly recommended to use PyBullet Python bindings for improved support for robotics, reinforcement learning and VR. Use pip install pybullet and checkout the [PyBullet Quickstart Guide](https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA/edit#heading=h.2ye70wns7io3).
Installation is simple:
```
@ -63,7 +66,7 @@ You can download and install Bullet using the [vcpkg](https://github.com/Microso
cd vcpkg
./bootstrap-vcpkg.sh
./vcpkg integrate install
vcpkg install bullet3
./vcpkg install bullet3
The Bullet port in vcpkg is kept up to date by Microsoft team members and community contributors. If the version is out of date, please [create an issue or pull request](https://github.com/Microsoft/vcpkg) on the vcpkg repository.
@ -91,9 +94,9 @@ p.connect(p.SHARED_MEMORY) #or (p.TCP, "localhost", 6667) or (p.UDP, "192.168.86
Make sure cmake is installed (sudo apt-get install cmake, brew install cmake, or https://cmake.org)
In a terminal type:
./build_cmake_pybullet_double.sh
```
./build_cmake_pybullet_double.sh
```
This script will invoke cmake and build in the build_cmake directory. You can find pybullet in Bullet/examples/pybullet.
The BulletExampleBrowser binary will be in Bullet/examples/ExampleBrowser.
@ -101,15 +104,15 @@ You can also build Bullet using premake. There are premake executables in the bu
Depending on your system (Linux 32bit, 64bit or Mac OSX) use one of the following lines
Using premake:
```
cd build3
./premake4_linux --double gmake
./premake4_linux64 --double gmake
./premake4_osx --double --enable_pybullet gmake
cd build3
./premake4_linux --double gmake
./premake4_linux64 --double gmake
./premake4_osx --double --enable_pybullet gmake
```
Then
```
cd gmake
make
cd gmake
make
```
Note that on Linux, you need to use cmake to build pybullet, since the compiler has issues of mixing shared and static libraries.
@ -117,9 +120,9 @@ Note that on Linux, you need to use cmake to build pybullet, since the compiler
**Mac OSX Xcode**
Click on build3/xcode4.command or in a terminal window execute
./premake_osx xcode4
```
./premake_osx xcode4
```
## Usage
The App_ExampleBrowser executables will be located in the bin folder.

View File

@ -55,7 +55,7 @@ public:
m_dynamicsWorld->stepSimulation(deltaTime, 4, internalTimeStep);
}
void addCloth(btVector3 origin);
void addCloth(const btVector3& origin);
virtual void renderScene()
{
@ -126,7 +126,7 @@ void DeformableSelfCollision::initPhysics()
getDeformableDynamicsWorld()->setLineSearch(false);
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void DeformableSelfCollision::addCloth(btVector3 origin)
void DeformableSelfCollision::addCloth(const btVector3& origin)
// create a piece of cloth
{
const btScalar s = 0.6;

View File

@ -1,7 +1,11 @@
#include "GwenParameterInterface.h"
#include "gwenInternalData.h"
#include <cstring>
#ifdef _WIN32
#define safe_printf _snprintf
#else
#define safe_printf snprintf
#endif
struct MyButtonEventHandler : public Gwen::Event::Handler
{
Gwen::Controls::Button* m_buttonControl;
@ -85,7 +89,7 @@ struct MySliderEventHandler : public Gwen::Event::Handler
if (m_showValue)
{
char txt[1024];
snprintf(txt, sizeof(txt), "%s : %.3f", m_variableName, val);
safe_printf(txt, sizeof(txt), "%s : %.3f", m_variableName, val);
m_label->SetText(txt);
}
}
@ -231,7 +235,7 @@ void GwenParameterInterface::registerSliderFloatParameter(SliderParams& params)
}
pSlider->SetValue(*params.m_paramValuePointer); //dimensions[i] );
char labelName[1024];
snprintf(labelName, sizeof(labelName), "%s", params.m_name); //axisNames[0]);
safe_printf(labelName, sizeof(labelName), "%s", params.m_name); //axisNames[0]);
MySliderEventHandler<btScalar>* handler = new MySliderEventHandler<btScalar>(labelName, label, pSlider, params.m_paramValuePointer, params.m_callback, params.m_userPointer);
handler->m_showValue = params.m_showValues;
m_paramInternalData->m_sliderEventHandlers.push_back(handler);

View File

@ -199,7 +199,15 @@ btScalar tmpUrdfScaling = 2;
btTransform ConvertURDF2BulletInternal(
const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation,
URDF2BulletCachedData& cache, int urdfLinkIndex,
const btTransform& parentTransformInWorldSpace, btMultiBodyDynamicsWorld* world1,
const btTransform& parentTransformInWorldSpace,
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btDiscreteDynamicsWorld* world1,
#else
btMultiBodyDynamicsWorld* world1,
#endif
bool createMultiBody, const char* pathPrefix,
int flags, UrdfVisualShapeCache* cachedLinkGraphicsShapesIn, UrdfVisualShapeCache* cachedLinkGraphicsShapesOut, bool recursive)
{
@ -505,6 +513,7 @@ btTransform ConvertURDF2BulletInternal(
creation.addLinkMapping(urdfLinkIndex, mbLinkIndex);
if (createMultiBody)
{
#ifndef USE_DISCRETE_DYNAMICS_WORLD
cache.m_bulletMultiBody->setupRevolute(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex,
parentRotToThis, quatRotate(offsetInB.getRotation(),
jointAxisInJointSpace),
@ -519,8 +528,10 @@ btTransform ConvertURDF2BulletInternal(
btMultiBodyConstraint* con = new btMultiBodyJointLimitConstraint(cache.m_bulletMultiBody, mbLinkIndex, jointLowerLimit, jointUpperLimit);
world1->addMultiBodyConstraint(con);
}
#endif
}
else
{
btGeneric6DofSpring2Constraint* dof6 = 0;
if (jointType == URDFRevoluteJoint && jointLowerLimit <= jointUpperLimit)
@ -560,6 +571,7 @@ btTransform ConvertURDF2BulletInternal(
if (createMultiBody)
{
#ifndef USE_DISCRETE_DYNAMICS_WORLD
cache.m_bulletMultiBody->setupPrismatic(mbLinkIndex, mass, localInertiaDiagonal, mbParentIndex,
parentRotToThis, quatRotate(offsetInB.getRotation(), jointAxisInJointSpace), offsetInA.getOrigin(), //parent2joint.getOrigin(),
-offsetInB.getOrigin(),
@ -574,6 +586,7 @@ btTransform ConvertURDF2BulletInternal(
world1->addMultiBodyConstraint(con);
}
//printf("joint lower limit=%d, upper limit = %f\n", jointLowerLimit, jointUpperLimit);
#endif
}
else
{
@ -775,10 +788,18 @@ bool MyIntCompareFunc(childParentIndex a, childParentIndex b)
}
void ConvertURDF2Bullet(
const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation,
const btTransform& rootTransformInWorldSpace,
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btDiscreteDynamicsWorld* world1,
#else
btMultiBodyDynamicsWorld* world1,
#endif
bool createMultiBody, const char* pathPrefix, int flags, UrdfVisualShapeCache* cachedLinkGraphicsShapes)
{
URDF2BulletCachedData cache;
@ -829,7 +850,7 @@ void ConvertURDF2Bullet(
{
*cachedLinkGraphicsShapes = cachedLinkGraphicsShapesOut;
}
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (world1 && cache.m_bulletMultiBody)
{
B3_PROFILE("Post process");
@ -855,4 +876,5 @@ void ConvertURDF2Bullet(
world1->addMultiBody(mb);
}
#endif
}

View File

@ -8,6 +8,7 @@
class btVector3;
class btTransform;
class btMultiBodyDynamicsWorld;
class btDiscreteDynamicsWorld;
class btTransform;
class URDFImporterInterface;
@ -20,7 +21,18 @@ struct UrdfVisualShapeCache
btAlignedObjectArray<UrdfMaterialColor> m_cachedUrdfLinkColors;
btAlignedObjectArray<int> m_cachedUrdfLinkVisualShapeIndices;
};
//#define USE_DISCRETE_DYNAMICS_WORLD
#ifdef USE_DISCRETE_DYNAMICS_WORLD
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
MultiBodyCreationInterface& creationCallback,
const btTransform& rootTransformInWorldSpace,
btDiscreteDynamicsWorld* world,
bool createMultiBody,
const char* pathPrefix,
int flags = 0,
UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0);
#else
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
MultiBodyCreationInterface& creationCallback,
const btTransform& rootTransformInWorldSpace,
@ -29,5 +41,5 @@ void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
const char* pathPrefix,
int flags = 0,
UrdfVisualShapeCache* cachedLinkGraphicsShapes = 0);
#endif
#endif //_URDF2BULLET_H

View File

@ -94,7 +94,8 @@ static void ParseUserData(const XMLElement* element, btHashMap<btHashString,
if (!key_attr) {
logger->reportError("User data tag must have a key attribute.");
}
user_data.insert(key_attr, user_data_xml->GetText());
const char* text = user_data_xml->GetText();
user_data.insert(key_attr, text ? text : "");
}
}
}
@ -1132,6 +1133,7 @@ bool UrdfParser::parseDeformable(UrdfModel& model, tinyxml2::XMLElement* config,
if (!i)
{
logger->reportError("expected an inertial element");
return false;
}
UrdfInertia inertia;
if (!parseInertia(inertia, i, logger))

View File

@ -397,6 +397,15 @@ void GLInstancingRenderer::removeAllInstances()
m_graphicsInstances.clear();
m_data->m_publicGraphicsInstances.exitHandles();
m_data->m_publicGraphicsInstances.initHandles();
for (int i=0;i<m_data->m_textureHandles.size();i++)
{
InternalTextureHandle& h = m_data->m_textureHandles[i];
glDeleteTextures(1, &h.m_glTexture);
}
m_data->m_textureHandles.clear();
}
GLInstancingRenderer::~GLInstancingRenderer()

View File

@ -977,6 +977,19 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedM
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPerformCollisionDetectionCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
b3Assert(cl->canSubmitCommand());
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_PERFORM_COLLISION_DETECTION;
command->m_updateFlags = 0;
return (b3SharedMemoryCommandHandle)command;
}
B3_SHARED_API b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
@ -1043,6 +1056,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3JointControlCommandInit2Internal(b3S
command->m_sendDesiredStateCommandArgument.m_Kp[i] = 0;
command->m_sendDesiredStateCommandArgument.m_Kd[i] = 0;
command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[i] = 0;
command->m_sendDesiredStateCommandArgument.m_damping[i] = 0;
}
command->m_sendDesiredStateCommandArgument.m_desiredStateQ[3] = 1;
return (b3SharedMemoryCommandHandle)command;
@ -1090,6 +1104,22 @@ B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle,
return 0;
}
B3_SHARED_API int b3JointControlSetKpMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kps, int dofCount)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4)
{
for (int dof = 0; dof < dofCount; dof++)
{
command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex + dof] = kps[dof];
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP;
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_KP;
}
}
return 0;
}
B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
@ -1103,6 +1133,22 @@ B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle,
return 0;
}
B3_SHARED_API int b3JointControlSetKdMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kds, int dofCount)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4)
{
for (int dof = 0; dof < dofCount; dof++)
{
command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex + dof] = kds[dof];
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD;
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_KD;
}
}
return 0;
}
B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
@ -1161,6 +1207,35 @@ B3_SHARED_API int b3JointControlSetDesiredForceTorqueMultiDof(b3SharedMemoryComm
return 0;
}
B3_SHARED_API int b3JointControlSetDamping(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM))
{
command->m_sendDesiredStateCommandArgument.m_damping[dofIndex] = value;
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_DAMPING;
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_DAMPING;
}
return 0;
}
B3_SHARED_API int b3JointControlSetDampingMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* damping, int dofCount)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
if ((dofIndex >= 0) && (dofIndex < MAX_DEGREE_OF_FREEDOM ) && dofCount >= 0 && dofCount <= 4)
{
for (int dof = 0; dof < dofCount; dof++)
{
command->m_sendDesiredStateCommandArgument.m_damping[dofIndex+dof] = damping[dof];
command->m_updateFlags |= SIM_DESIRED_STATE_HAS_DAMPING;
command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex + dof] |= SIM_DESIRED_STATE_HAS_DAMPING;
}
}
return 0;
}
B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
@ -2052,7 +2127,8 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl
const double linkInertialFrameOrientation[4],
int linkParentIndex,
int linkJointType,
const double linkJointAxis[3])
const double linkJointAxis[3],
const char* const linkName)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
@ -2097,6 +2173,7 @@ B3_SHARED_API int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandl
command->m_createMultiBodyArgs.m_linkJointAxis[3 * linkIndex + 2] = linkJointAxis[2];
command->m_createMultiBodyArgs.m_linkMasses[linkIndex] = linkMass;
command->m_createMultiBodyArgs.m_linkNames[linkIndex] = linkName;
command->m_createMultiBodyArgs.m_numLinks++;
return numLinks;
}

View File

@ -382,6 +382,8 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitStepSimulationCommand2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitPerformCollisionDetectionCommand(b3PhysicsClientHandle physClient);
B3_SHARED_API int b3GetStatusForwardDynamicsAnalyticsData(b3SharedMemoryStatusHandle statusHandle, struct b3ForwardDynamicsAnalyticsArgs* analyticsData);
@ -482,7 +484,9 @@ extern "C"
B3_SHARED_API int b3JointControlSetDesiredPositionMultiDof(b3SharedMemoryCommandHandle commandHandle, int qIndex, const double* position, int dofCount);
B3_SHARED_API int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
B3_SHARED_API int b3JointControlSetKpMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kps, int dofCount);
B3_SHARED_API int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
B3_SHARED_API int b3JointControlSetKdMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* kds, int dofCount);
B3_SHARED_API int b3JointControlSetMaximumVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double maximumVelocity);
///Only use when controlMode is CONTROL_MODE_VELOCITY
@ -492,6 +496,8 @@ extern "C"
B3_SHARED_API int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
B3_SHARED_API int b3JointControlSetDesiredForceTorqueMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* forces, int dofCount);
B3_SHARED_API int b3JointControlSetDamping(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
B3_SHARED_API int b3JointControlSetDampingMultiDof(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double* damping, int dofCount);
///Only use if when controlMode is CONTROL_MODE_TORQUE,
B3_SHARED_API int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value);
@ -552,7 +558,8 @@ extern "C"
const double linkInertialFrameOrientation[/*4*/],
int linkParentIndex,
int linkJointType,
const double linkJointAxis[/*3*/]);
const double linkJointAxis[/*3*/],
const char* const linkName);
//batch creation is an performance feature to create a large number of multi bodies in one command
B3_SHARED_API int b3CreateMultiBodySetBatchPositions(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, double* batchPositions, int numBatchObjects);

View File

@ -13,6 +13,12 @@
#include "PhysicsDirectC_API.h"
#include "PhysicsClientC_API.h"
#include "PhysicsServerSharedMemory.h"
#include <stdio.h>
#ifdef _WIN32
#define safe_printf _snprintf
#else
#define safe_printf snprintf
#endif
struct MyMotorInfo2
{
btScalar m_velTarget;
@ -655,7 +661,7 @@ void PhysicsClientExample::createButtons()
if (m_numMotors < MAX_NUM_MOTORS)
{
char motorName[1026];
snprintf(motorName, sizeof(motorName), "%s q", info.m_jointName);
safe_printf(motorName, sizeof(motorName), "%s q", info.m_jointName);
// MyMotorInfo2* motorInfo = &m_motorTargetVelocities[m_numMotors];
MyMotorInfo2* motorInfo = &m_motorTargetPositions[m_numMotors];
motorInfo->m_velTarget = 0.f;

View File

@ -702,6 +702,16 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus()
}
break;
}
case CMD_PERFORM_COLLISION_DETECTION_COMPLETED:
{
B3_PROFILE("CMD_PERFORM_COLLISION_DETECTION_COMPLETED");
if (m_data->m_verboseOutput)
{
b3Printf("Server completed performing collision detection");
}
break;
}
case CMD_URDF_LOADING_FAILED:
{
B3_PROFILE("CMD_URDF_LOADING_FAILED");

View File

@ -1166,6 +1166,10 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
{
break;
}
case CMD_PERFORM_COLLISION_DETECTION_COMPLETED:
{
break;
}
case CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED:
{
break;

View File

@ -12,10 +12,15 @@
#include "../Importers/ImportMeshUtility/b3ImportMeshUtility.h"
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h"
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
#include "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
//#define USE_DISCRETE_DYNAMICS_WORLD
//#define SKIP_DEFORMABLE_BODY
//#define SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
#include "../Utils/b3BulletDefaultFileIO.h"
#include "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h"
@ -1626,7 +1631,11 @@ struct PhysicsServerCommandProcessorInternalData
b3AlignedObjectArray<SaveWorldObjectData> m_saveWorldBodyData;
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btAlignedObjectArray<btWorldImporter*> m_worldImporters;
#else
btAlignedObjectArray<btMultiBodyWorldImporter*> m_worldImporters;
#endif
btAlignedObjectArray<std::string*> m_strings;
@ -1641,8 +1650,12 @@ struct PhysicsServerCommandProcessorInternalData
btHashedOverlappingPairCache* m_pairCache;
btBroadphaseInterface* m_broadphase;
btCollisionDispatcher* m_dispatcher;
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btSequentialImpulseConstraintSolver* m_solver;
#else
btMultiBodyConstraintSolver* m_solver;
#endif
btDefaultCollisionConfiguration* m_collisionConfiguration;
@ -1654,7 +1667,12 @@ struct PhysicsServerCommandProcessorInternalData
btAlignedObjectArray<btDeformableLagrangianForce*> m_lf;
#endif
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btDiscreteDynamicsWorld* m_dynamicsWorld;
#else
btMultiBodyDynamicsWorld* m_dynamicsWorld;
#endif
int m_constraintSolverType;
SharedMemoryDebugDrawer* m_remoteDebugDrawer;
@ -2232,6 +2250,11 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
virtual std::string getLinkName(int linkIndex) const
{
// Allow user overrides on default-created link names.
if(m_createBodyArgs.m_linkNames[linkIndex] != 0
&& strlen(m_createBodyArgs.m_linkNames[linkIndex]) > 0){
return std::string(m_createBodyArgs.m_linkNames[linkIndex]);
}
std::string linkName = "link";
char numstr[21]; // enough to hold all numbers up to 64-bits
sprintf(numstr, "%d", linkIndex);
@ -2309,6 +2332,11 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
virtual std::string getJointName(int linkIndex) const
{
// Allow user overrides on default-created joint names.
if(m_createBodyArgs.m_linkNames[linkIndex] != 0
&& strlen(m_createBodyArgs.m_linkNames[linkIndex]) > 0){
return std::string(m_createBodyArgs.m_linkNames[linkIndex]);
}
std::string jointName = "joint";
char numstr[21]; // enough to hold all numbers up to 64-bits
sprintf(numstr, "%d", linkIndex);
@ -2712,20 +2740,35 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags)
#endif
}
if ((0 == m_data->m_dynamicsWorld) && (0 == (flags & RESET_USE_DISCRETE_DYNAMICS_WORLD)))
{
m_data->m_solver = new btMultiBodyConstraintSolver;
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
m_data->m_solver = new btMultiBodyConstraintSolver;
m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
#else
#ifdef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_solver = new btSequentialImpulseConstraintSolver;
m_data->m_dynamicsWorld = new btDiscreteDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
#else
m_data->m_solver = new btMultiBodyConstraintSolver;
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
#endif
#endif
}
if (0 == m_data->m_dynamicsWorld)
{
#ifdef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_solver = new btSequentialImpulseConstraintSolver;
m_data->m_dynamicsWorld = new btDiscreteDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
#else
m_data->m_solver = new btMultiBodyConstraintSolver;
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
#endif
}
//Workaround: in a VR application, where we avoid synchronizing between GFX/Physics threads, we don't want to resize this array, so pre-allocate it
@ -2860,13 +2903,14 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
constraints.push_back(constraint);
m_data->m_dynamicsWorld->removeConstraint(constraint);
}
#ifndef USE_DISCRETE_DYNAMICS_WORLD
for (i = m_data->m_dynamicsWorld->getNumMultiBodyConstraints() - 1; i >= 0; i--)
{
btMultiBodyConstraint* mbconstraint = m_data->m_dynamicsWorld->getMultiBodyConstraint(i);
mbconstraints.push_back(mbconstraint);
m_data->m_dynamicsWorld->removeMultiBodyConstraint(mbconstraint);
}
#endif
for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
{
btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
@ -2878,12 +2922,14 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
m_data->m_dynamicsWorld->removeCollisionObject(obj);
delete obj;
}
#ifndef USE_DISCRETE_DYNAMICS_WORLD
for (i = m_data->m_dynamicsWorld->getNumMultibodies() - 1; i >= 0; i--)
{
btMultiBody* mb = m_data->m_dynamicsWorld->getMultiBody(i);
m_data->m_dynamicsWorld->removeMultiBody(mb);
delete mb;
}
#endif
#ifndef SKIP_DEFORMABLE_BODY
for (int j = 0; j < m_data->m_lf.size(); j++)
{
@ -3052,14 +3098,18 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb)
//motor->setRhsClamp(gRhsClamp);
//motor->setMaxAppliedImpulse(0);
mb->getLink(mbLinkIndex).m_userPtr = motor;
#ifndef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_dynamicsWorld->addMultiBodyConstraint(motor);
#endif
motor->finalizeMultiDof();
}
if (mb->getLink(mbLinkIndex).m_jointType == btMultibodyLink::eSpherical)
{
btMultiBodySphericalJointMotor* motor = new btMultiBodySphericalJointMotor(mb, mbLinkIndex, 1000 * maxMotorImpulse);
mb->getLink(mbLinkIndex).m_userPtr = motor;
#ifndef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_dynamicsWorld->addMultiBodyConstraint(motor);
#endif
motor->finalizeMultiDof();
}
}
@ -3166,11 +3216,15 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
}
}
UrdfVisualShapeCache* cachedVisualShapesPtr = m_data->m_cachedVUrdfisualShapes[fileName];
ConvertURDF2Bullet(u2b, creation, rootTrans, m_data->m_dynamicsWorld, useMultiBody, u2b.getPathPrefix(), flags, cachedVisualShapesPtr);
}
else
{
ConvertURDF2Bullet(u2b, creation, rootTrans, m_data->m_dynamicsWorld, useMultiBody, u2b.getPathPrefix(), flags);
}
mb = creation.getBulletMultiBody();
@ -3788,9 +3842,10 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar
}
}
}
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_GENERIC_ROBOT)
{
std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName;
int loggerUid = m_data->m_stateLoggersUniqueId++;
@ -3848,6 +3903,7 @@ bool PhysicsServerCommandProcessor::processStateLoggingCommand(const struct Shar
serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED;
serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid;
}
#endif
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_VR_CONTROLLERS)
{
std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName;
@ -4733,7 +4789,11 @@ bool PhysicsServerCommandProcessor::processCreateCollisionShapeCommand(const str
bool hasStatus = true;
serverStatusOut.m_type = CMD_CREATE_COLLISION_SHAPE_FAILED;
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btWorldImporter* worldImporter = new btWorldImporter(m_data->m_dynamicsWorld);
#else
btMultiBodyWorldImporter* worldImporter = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld);
#endif
btCollisionShape* shape = 0;
b3AlignedObjectArray<UrdfCollision> urdfCollisionObjects;
@ -7093,8 +7153,8 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
motor->setRhsClamp(clientCmd.m_sendDesiredStateCommandArgument.m_rhsClamp[velIndex]);
}
bool hasDesiredPosOrVel = false;
btScalar kp = 0.f;
btScalar kd = 0.f;
btVector3 kp(0, 0, 0);
btVector3 kd(0, 0, 0);
btVector3 desiredVelocity(0, 0, 0);
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_QDOT) != 0)
{
@ -7103,7 +7163,7 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 1],
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex + 2]);
kd = 0.1;
kd.setValue(0.1, 0.1, 0.1);
}
btQuaternion desiredPosition(0, 0, 0, 1);
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[posIndex] & SIM_DESIRED_STATE_HAS_Q) != 0)
@ -7114,38 +7174,122 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 1],
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 2],
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex + 3]);
kp = 0.1;
kp.setValue(0.1, 0.1, 0.1);
}
if (hasDesiredPosOrVel)
{
bool useMultiDof = true;
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KP) != 0)
{
kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex];
kp.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0]);
}
if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_KP) != 0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_KP) != 0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_KP) != 0)
)
{
kp.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 1],
clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex + 2]);
} else
{
useMultiDof = false;
}
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KD) != 0)
{
kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex];
kd.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0]);
}
motor->setVelocityTarget(desiredVelocity, kd);
//todo: instead of clamping, combine the motor and limit
//and combine handling of limit force and motor force.
if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_KD) != 0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_KD) != 0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_KD) != 0))
{
kd.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 1],
clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex + 2]);
} else
{
useMultiDof = false;
}
//clamp position
//if (mb->getLink(link).m_jointLowerLimit <= mb->getLink(link).m_jointUpperLimit)
//{
// btClamp(desiredPosition, mb->getLink(link).m_jointLowerLimit, mb->getLink(link).m_jointUpperLimit);
//}
motor->setPositionTarget(desiredPosition, kp);
btVector3 maxImp(
1000000.f * m_data->m_physicsDeltaTime,
1000000.f * m_data->m_physicsDeltaTime,
1000000.f * m_data->m_physicsDeltaTime);
btScalar maxImp = 1000000.f * m_data->m_physicsDeltaTime;
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
{
maxImp.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime,
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime,
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime);
}
if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE) != 0)
maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex] * m_data->m_physicsDeltaTime;
if (((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) &&
((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0))
{
maxImp.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 0] * m_data->m_physicsDeltaTime,
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 1] * m_data->m_physicsDeltaTime,
clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex + 2] * m_data->m_physicsDeltaTime);
} else
{
useMultiDof = false;
}
if (useMultiDof)
{
motor->setVelocityTargetMultiDof(desiredVelocity, kd);
motor->setPositionTargetMultiDof(desiredPosition, kp);
motor->setMaxAppliedImpulseMultiDof(maxImp);
} else
{
motor->setVelocityTarget(desiredVelocity, kd[0]);
//todo: instead of clamping, combine the motor and limit
//and combine handling of limit force and motor force.
motor->setMaxAppliedImpulse(maxImp);
//clamp position
//if (mb->getLink(link).m_jointLowerLimit <= mb->getLink(link).m_jointUpperLimit)
//{
// btClamp(desiredPosition, mb->getLink(link).m_jointLowerLimit, mb->getLink(link).m_jointUpperLimit);
//}
motor->setPositionTarget(desiredPosition, kp[0]);
motor->setMaxAppliedImpulse(maxImp[0]);
}
btVector3 damping(1.f, 1.f, 1.f);
if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_DAMPING) != 0) {
if (
(clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+0] & SIM_DESIRED_STATE_HAS_DAMPING)&&
(clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+1] & SIM_DESIRED_STATE_HAS_DAMPING)&&
(clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex+2] & SIM_DESIRED_STATE_HAS_DAMPING)
)
{
damping.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 1],
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 2]);
} else
{
damping.setValue(
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0],
clientCmd.m_sendDesiredStateCommandArgument.m_damping[velIndex + 0]);
}
}
motor->setDamping(damping);
}
numMotors++;
}
@ -9433,6 +9577,24 @@ bool PhysicsServerCommandProcessor::processRequestCollisionInfoCommand(const str
return hasStatus;
}
bool PhysicsServerCommandProcessor::performCollisionDetectionCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
BT_PROFILE("CMD_PERFORM_COLLISION_DETECTION");
if (m_data->m_verboseOutput)
{
b3Printf("Perform Collision Detection command");
b3Printf("CMD_PERFORM_COLLISION_DETECTION clientCmd = %d\n", clientCmd.m_sequenceNumber);
}
m_data->m_dynamicsWorld->performDiscreteCollisionDetection();
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_PERFORM_COLLISION_DETECTION_COMPLETED;
return true;
}
bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
bool hasStatus = true;
@ -9444,6 +9606,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S
b3Printf("Step simulation request");
b3Printf("CMD_STEP_FORWARD_SIMULATION clientCmd = %d\n", clientCmd.m_sequenceNumber);
}
#ifndef USE_DISCRETE_DYNAMICS_WORLD
///todo(erwincoumans) move this damping inside Bullet
for (int i = 0; i < m_data->m_dynamicsWorld->getNumMultibodies(); i++)
{
@ -9458,7 +9621,7 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S
}
}
}
#endif
btScalar deltaTimeScaled = m_data->m_physicsDeltaTime * simTimeScalingFactor;
int numSteps = 0;
@ -9483,8 +9646,9 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S
serverCmd.m_forwardDynamicsAnalyticsArgs.m_numSteps = numSteps;
btAlignedObjectArray<btSolverAnalyticsData> islandAnalyticsData;
#ifndef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_dynamicsWorld->getAnalyticsData(islandAnalyticsData);
#endif
serverCmd.m_forwardDynamicsAnalyticsArgs.m_numIslands = islandAnalyticsData.size();
int numIslands = btMin(islandAnalyticsData.size(), MAX_ISLANDS_ANALYTICS);
@ -9555,7 +9719,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
if (bodyUniqueId >= 0)
{
InternalBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (body && body->m_multiBody)
{
btMultiBody* mb = body->m_multiBody;
@ -9741,6 +9905,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
}
}
}
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS)
{
@ -9875,6 +10040,7 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
}
}
else
#endif
{
btRigidBody* rb = 0;
if (body && body->m_rigidBody)
@ -10401,7 +10567,11 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
btConstraintSolver* oldSolver = m_data->m_dynamicsWorld->getConstraintSolver();
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btSequentialImpulseConstraintSolver* newSolver = 0;
#else
btMultiBodyConstraintSolver* newSolver = 0;
#endif
switch (clientCmd.m_physSimParamArgs.m_constraintSolverType)
{
@ -10414,7 +10584,12 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
case eConstraintSolverLCP_PGS:
{
btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel();
#ifdef USE_DISCRETE_DYNAMICS_WORLD
newSolver = new btMLCPSolver(mlcp);
#else
newSolver = new btMultiBodyMLCPConstraintSolver(mlcp);
#endif
b3Printf("PyBullet: Constraint Solver: MLCP + PGS\n");
break;
}
@ -10438,7 +10613,11 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
{
delete oldSolver;
#ifdef USE_DISCRETE_DYNAMICS_WORLD
m_data->m_dynamicsWorld->setConstraintSolver(newSolver);
#else
m_data->m_dynamicsWorld->setMultiBodyConstraintSolver(newSolver);
#endif
m_data->m_solver = newSolver;
printf("switched solver\n");
}
@ -10718,6 +10897,12 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe
scratch_m.resize(nLinks + 1);
mb->updateCollisionObjectWorldTransforms(scratch_q, scratch_m);
m_data->m_dynamicsWorld->updateSingleAabb(mb->getBaseCollider());
for (int i=0;i<mb->getNumLinks();i++)
{
m_data->m_dynamicsWorld->updateSingleAabb(mb->getLinkCollider(i));
}
}
if (body && body->m_rigidBody)
@ -10742,6 +10927,7 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe
body->m_rigidBody->getWorldTransform().setRotation(baseOrn);
body->m_rigidBody->setAngularVelocity(baseAngVel);
}
m_data->m_dynamicsWorld->updateSingleAabb(body->m_rigidBody);
}
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
if (body && body->m_softBody)
@ -10768,6 +10954,7 @@ bool PhysicsServerCommandProcessor::processInitPoseCommand(const struct SharedMe
}
body->m_softBody->transformTo(tr);
}
m_data->m_dynamicsWorld->updateSingleAabb(body->m_softBody);
}
#endif
syncPhysicsToGraphics2();
@ -10840,7 +11027,11 @@ bool PhysicsServerCommandProcessor::processCreateRigidBodyCommand(const struct S
shapeType = clientCmd.m_createBoxShapeArguments.m_collisionShapeType;
}
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btWorldImporter* worldImporter = new btWorldImporter(m_data->m_dynamicsWorld);
#else
btMultiBodyWorldImporter* worldImporter = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld);
#endif
m_data->m_worldImporters.push_back(worldImporter);
btCollisionShape* shape = 0;
@ -11585,6 +11776,7 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId);
if (bodyHandle)
{
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (bodyHandle->m_multiBody)
{
serverCmd.m_removeObjectArgs.m_bodyUniqueIds[serverCmd.m_removeObjectArgs.m_numBodies++] = bodyUniqueId;
@ -11654,6 +11846,7 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
bodyHandle->m_multiBody = 0;
serverCmd.m_type = CMD_REMOVE_BODY_COMPLETED;
}
#endif
if (bodyHandle->m_rigidBody)
{
if (m_data->m_pluginManager.getRenderInterface())
@ -11731,7 +11924,11 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
for (int i = 0; i < m_data->m_worldImporters.size(); i++)
{
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btWorldImporter* importer = m_data->m_worldImporters[i];
#else
btMultiBodyWorldImporter* importer = m_data->m_worldImporters[i];
#endif
for (int c = 0; c < importer->getNumCollisionShapes(); c++)
{
if (importer->getCollisionShapeByIndex(c) == handle->m_collisionShape)
@ -11747,7 +11944,11 @@ bool PhysicsServerCommandProcessor::processRemoveBodyCommand(const struct Shared
}
if (foundIndex >= 0)
{
#ifdef USE_DISCRETE_DYNAMICS_WORLD
btWorldImporter* importer = m_data->m_worldImporters[foundIndex];
#else
btMultiBodyWorldImporter* importer = m_data->m_worldImporters[foundIndex];
#endif
m_data->m_worldImporters.removeAtIndex(foundIndex);
importer->deleteAllData();
delete importer;
@ -11901,6 +12102,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str
{
btScalar defaultMaxForce = 500.0;
InternalBodyData* parentBody = m_data->m_bodyHandles.getHandle(clientCmd.m_userConstraintArguments.m_parentBodyIndex);
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (parentBody && parentBody->m_multiBody)
{
if ((clientCmd.m_userConstraintArguments.m_parentJointIndex >= -1) && clientCmd.m_userConstraintArguments.m_parentJointIndex < parentBody->m_multiBody->getNumLinks())
@ -12054,6 +12256,7 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str
}
}
else
#endif
{
InternalBodyData* childBody = clientCmd.m_userConstraintArguments.m_childBodyIndex >= 0 ? m_data->m_bodyHandles.getHandle(clientCmd.m_userConstraintArguments.m_childBodyIndex) : 0;
@ -12301,12 +12504,14 @@ bool PhysicsServerCommandProcessor::processCreateUserConstraintCommand(const str
InteralUserConstraintData* userConstraintPtr = m_data->m_userConstraints.find(userConstraintUidRemove);
if (userConstraintPtr)
{
#ifndef USE_DISCRETE_DYNAMICS_WORLD
if (userConstraintPtr->m_mbConstraint)
{
m_data->m_dynamicsWorld->removeMultiBodyConstraint(userConstraintPtr->m_mbConstraint);
delete userConstraintPtr->m_mbConstraint;
m_data->m_userConstraints.remove(userConstraintUidRemove);
}
#endif//USE_DISCRETE_DYNAMICS_WORLD
if (userConstraintPtr->m_rbConstraint)
{
m_data->m_dynamicsWorld->removeConstraint(userConstraintPtr->m_rbConstraint);
@ -13654,12 +13859,14 @@ bool PhysicsServerCommandProcessor::processRemoveStateCommand(const struct Share
bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
{
BT_PROFILE("CMD_RESTORE_STATE");
bool hasStatus = true;
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_RESTORE_STATE_FAILED;
#ifndef USE_DISCRETE_DYNAMICS_WORLD
btMultiBodyWorldImporter* importer = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld);
importer->setImporterFlags(eRESTORE_EXISTING_OBJECTS);
bool ok = false;
@ -13727,7 +13934,7 @@ bool PhysicsServerCommandProcessor::processRestoreStateCommand(const struct Shar
{
serverCmd.m_type = CMD_RESTORE_STATE_COMPLETED;
}
#endif
return hasStatus;
}
@ -13739,6 +13946,7 @@ bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct Shared
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_BULLET_LOADING_FAILED;
#ifndef USE_DISCRETE_DYNAMICS_WORLD
//btBulletWorldImporter* importer = new btBulletWorldImporter(m_data->m_dynamicsWorld);
btMultiBodyWorldImporter* importer = new btMultiBodyWorldImporter(m_data->m_dynamicsWorld);
@ -13817,6 +14025,7 @@ bool PhysicsServerCommandProcessor::processLoadBulletCommand(const struct Shared
m_data->m_guiHelper->autogenerateGraphicsObjects(m_data->m_dynamicsWorld);
}
}
#endif
return hasStatus;
}
@ -14034,6 +14243,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
hasStatus = processForwardDynamicsCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_PERFORM_COLLISION_DETECTION:
{
hasStatus = performCollisionDetectionCommand(clientCmd, serverStatusOut, bufferServerToClient, bufferSizeInBytes);
break;
}
case CMD_REQUEST_INTERNAL_DATA:
{

View File

@ -55,6 +55,7 @@ protected:
bool processProfileTimingCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processRequestCollisionInfoCommand(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 performCollisionDetectionCommand(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 processChangeDynamicsInfoCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);
bool processSetAdditionalSearchPathCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes);

View File

@ -465,6 +465,8 @@ struct SendDesiredStateArgs
//or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode
//indexed by degree of freedom, 6 dof base, and then dofs for each link
double m_desiredStateForceTorque[MAX_DEGREE_OF_FREEDOM];
double m_damping[MAX_DEGREE_OF_FREEDOM];
};
enum EnumSimDesiredStateUpdateFlags
@ -475,6 +477,7 @@ enum EnumSimDesiredStateUpdateFlags
SIM_DESIRED_STATE_HAS_KP = 8,
SIM_DESIRED_STATE_HAS_MAX_FORCE = 16,
SIM_DESIRED_STATE_HAS_RHS_CLAMP = 32,
SIM_DESIRED_STATE_HAS_DAMPING = 64,
};
enum EnumSimParamUpdateFlags
@ -1057,6 +1060,7 @@ struct b3CreateMultiBodyArgs
int m_flags;
int m_numBatchObjects;
const char* m_linkNames[MAX_CREATE_MULTI_BODY_LINKS];
};
struct b3CreateMultiBodyResultArgs

View File

@ -115,7 +115,8 @@ enum EnumSharedMemoryClientCommand
CMD_REMOVE_USER_DATA,
CMD_COLLISION_FILTER,
CMD_REQUEST_MESH_DATA,
CMD_PERFORM_COLLISION_DETECTION,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
};
@ -239,6 +240,7 @@ enum EnumSharedMemoryServerStatus
CMD_REQUEST_MESH_DATA_COMPLETED,
CMD_REQUEST_MESH_DATA_FAILED,
CMD_PERFORM_COLLISION_DETECTION_COMPLETED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};

View File

@ -2431,7 +2431,8 @@ int b3RobotSimulatorClientAPI_NoDirect::createMultiBody(struct b3RobotSimulatorC
doubleLinkInertialFrameOrientation,
linkParentIndex,
linkJointType,
doubleLinkJointAxis);
doubleLinkJointAxis,
0);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);

View File

@ -136,7 +136,7 @@ std::string base64_decode(std::string const& encoded_string, bool remove_linebre
std::string copy(encoded_string);
size_t pos=0;
while ((pos = copy.find("\n", pos)) != std::string::npos) {
while ((pos = copy.find('\n', pos)) != std::string::npos) {
copy.erase(pos, 1);
}

View File

@ -149,7 +149,7 @@ Vec3f Model::vert(int iface, int nthvert)
void Model::load_texture(std::string filename, const char *suffix, TGAImage &img)
{
std::string texfile(filename);
size_t dot = texfile.find_last_of(".");
size_t dot = texfile.find_last_of('.');
if (dot != std::string::npos)
{
texfile = texfile.substr(0, dot) + std::string(suffix);

View File

@ -13,15 +13,19 @@ IF(BUILD_PYBULLET_NUMPY)
)
ENDIF()
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN )
SET(pybullet3_SRCS
pybullet.c
)
IF(ENABLE_VHACD)
ADD_DEFINITIONS(-DBT_ENABLE_VHACD)
INCLUDE_DIRECTORIES(
../../Extras/VHACD/inc
../../Extras/VHACD/public
)
ENDIF(ENABLE_VHACD)
SET(pybullet_SRCS
pybullet.c
)
IF(BUILD_CLSOCKET)

View File

@ -0,0 +1 @@

View File

@ -7,7 +7,6 @@ dt = 1e-3
iters = 2000
import pybullet_data
p.setAdditionalSearchPath(pybullet_data.getDataPath())
physicsClient = p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()

View File

@ -70,43 +70,34 @@ class PDControllerStableMultiDof(object):
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
p = Kp.dot(qError)
# Compute -Kp(q + qdot - qdes)
p_term = Kp.dot(qError - qdot*timeStep)
# Compute -Kd(qdot - qdotdes)
d_term = Kd.dot(qdoterr)
#np.savetxt("pb_qError.csv", qError, delimiter=",")
#np.savetxt("pb_p.csv", p, delimiter=",")
d = Kd.dot(qdoterr)
#np.savetxt("pb_d.csv", d, delimiter=",")
#np.savetxt("pbqdoterr.csv", qdoterr, delimiter=",")
M1 = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1)
M2 = np.array(M1)
#np.savetxt("M2.csv", M2, delimiter=",")
M = (M2 + Kd * timeStep)
#np.savetxt("pbM_tKd.csv",M, delimiter=",")
c1 = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1)
c = np.array(c1)
#np.savetxt("pbC.csv",c, delimiter=",")
A = M
#p = [0]*43
b = p + d - c
#np.savetxt("pb_acc.csv",b, delimiter=",")
qddot = np.linalg.solve(A, b)
tau = p + d - Kd.dot(qddot) * timeStep
#print("len(tau)=",len(tau))
# Compute Inertia matrix M(q)
M = self._pb.calculateMassMatrix(bodyUniqueId, q1, flags=1)
M = np.array(M)
# Given: M(q) * qddot + C(q, qdot) = T_ext + T_int
# Compute Coriolis and External (Gravitational) terms G = C - T_ext
G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations, flags=1)
G = np.array(G)
# Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions
qddot = np.linalg.solve(a=(M + Kd * timeStep),
b=p_term + d_term - G)
# Compute control generalized forces (T_int)
tau = p_term + d_term - Kd.dot(qddot) * timeStep
# Clip generalized forces to actuator limits
maxF = np.array(maxForces)
forces = np.clip(tau, -maxF, maxF)
return forces
generalized_forces = np.clip(tau, -maxF, maxF)
return generalized_forces
class PDControllerStable(object):
"""
Implementation based on: Tan, J., Liu, K., & Turk, G. (2011). "Stable proportional-derivative controllers"
DOI: 10.1109/MCG.2011.30
"""
def __init__(self, pb):
self._pb = pb
@ -121,28 +112,36 @@ class PDControllerStable(object):
q1.append(jointStates[i][0])
qdot1.append(jointStates[i][1])
zeroAccelerations.append(0)
q = np.array(q1)
qdot = np.array(qdot1)
qdes = np.array(desiredPositions)
qdotdes = np.array(desiredVelocities)
qError = qdes - q
qdotError = qdotdes - qdot
Kp = np.diagflat(kps)
Kd = np.diagflat(kds)
p = Kp.dot(qError)
d = Kd.dot(qdotError)
forces = p + d
M1 = self._pb.calculateMassMatrix(bodyUniqueId, q1)
M2 = np.array(M1)
M = (M2 + Kd * timeStep)
c1 = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations)
c = np.array(c1)
A = M
b = -c + p + d
qddot = np.linalg.solve(A, b)
tau = p + d - Kd.dot(qddot) * timeStep
# Compute -Kp(q + qdot - qdes)
p_term = Kp.dot(qError - qdot*timeStep)
# Compute -Kd(qdot - qdotdes)
d_term = Kd.dot(qdotError)
# Compute Inertia matrix M(q)
M = self._pb.calculateMassMatrix(bodyUniqueId, q1)
M = np.array(M)
# Given: M(q) * qddot + C(q, qdot) = T_ext + T_int
# Compute Coriolis and External (Gravitational) terms G = C - T_ext
G = self._pb.calculateInverseDynamics(bodyUniqueId, q1, qdot1, zeroAccelerations)
G = np.array(G)
# Obtain estimated generalized accelerations, considering Coriolis and Gravitational forces, and stable PD actions
qddot = np.linalg.solve(a=(M + Kd * timeStep),
b=(-G + p_term + d_term))
# Compute control generalized forces (T_int)
tau = p_term + d_term - (Kd.dot(qddot) * timeStep)
# Clip generalized forces to actuator limits
maxF = np.array(maxForces)
forces = np.clip(tau, -maxF, maxF)
#print("c=",c)
return tau
generalized_forces = np.clip(tau, -maxF, maxF)
return generalized_forces

View File

@ -0,0 +1,182 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from TwoJointRobot.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="TwoJointRobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_01_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_12_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_21_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_23_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_1">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<link name="link_2">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<joint name="link_01" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_01_cyl"/>
<child link="link_1"/>
</joint>
<joint name="link_12" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_1"/>
<child link="link_12_cyl"/>
</joint>
<joint name="link_21" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_21_cyl"/>
<child link="link_2"/>
</joint>
<joint name="link_23" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_2"/>
<child link="link_23_cyl"/>
</joint>
<joint name="joint_1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3" upper="+3" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
<parent link="base_link"/>
<child link="link_01_cyl"/>
</joint>
<joint name="joint_2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3" upper="+3" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0.0 0. 0.05"/>
<parent link="link_12_cyl"/>
<child link="link_21_cyl"/>
</joint>
</robot>

View File

@ -0,0 +1,110 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from TwoJointRobot_woCyl.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="TwoJointRobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.025"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_23_cyl">
<visual>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.075"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</collision>
<inertial>
<mass value="0.2"/>
<inertia ixx="0.000322916666667" ixy="0.0" ixz="0.0" iyy="0.000322916666667" iyz="0.0" izz="0.0005625"/>
</inertial>
</link>
<link name="link_1">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="blue"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<link name="link_2">
<visual>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<material name="white"/>
</visual>
<collision>
<geometry>
<box size="1.0 0.1 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.00208333333333" ixy="0.0125" ixz="0.00625" iyy="0.167083333333" iyz="0.000625" izz="0.168333333333"/>
</inertial>
</link>
<joint name="joint_1" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3.14" upper="3.14" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="0 0 0.075"/>
<parent link="base_link"/>
<child link="link_1"/>
</joint>
<joint name="joint_2" type="revolute">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="-3.14" upper="3.14" velocity="5"/>
<dynamics damping="0" friction="0"/>
<origin rpy="0 0 0" xyz="1.0 0. 0.05"/>
<parent link="link_1"/>
<child link="link_2"/>
</joint>
<joint name="link_23" type="fixed">
<origin rpy="0 0 0" xyz="1.0 0 0"/>
<parent link="link_2"/>
<child link="link_23_cyl"/>
</joint>
</robot>

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 32 KiB

View File

@ -0,0 +1,13 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 94.117647
Ka 1.000000 1.000000 1.000000
Kd 0.640000 0.640000 0.640000
Ks 0.500000 0.500000 0.500000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2
map_Kd cube.png

View File

@ -0,0 +1,89 @@
# Blender v2.79 (sub 0) OBJ File: ''
# www.blender.org
mtllib cloth_z_up.mtl
o Plane_Plane.001
v 1.000000 -0.500000 -0.000000
v 0.500000 -1.000000 -0.000000
v 0.500000 -0.500000 -0.000000
v 0.000000 -0.500000 -0.000000
v -0.500000 -1.000000 -0.000000
v -0.500000 -0.500000 -0.000000
v -0.000000 0.500000 0.000000
v -0.500000 0.000000 -0.000000
v -0.500000 0.500000 0.000000
v 1.000000 0.500000 0.000000
v 0.500000 0.000000 0.000000
v 0.500000 0.500000 0.000000
v 0.000000 0.000000 0.000000
v 0.500000 1.000000 0.000000
v -0.000000 1.000000 0.000000
v 1.000000 1.000000 0.000000
v -1.000000 0.000000 -0.000000
v -1.000000 0.500000 0.000000
v -0.500000 1.000000 0.000000
v -1.000000 1.000000 0.000000
v -1.000000 -1.000000 -0.000000
v -1.000000 -0.500000 -0.000000
v 0.000000 -1.000000 -0.000000
v 1.000000 0.000000 0.000000
v 1.000000 -1.000000 -0.000000
vt 0.976031 1.084981
vt 0.738016 1.669965
vt 0.738016 1.084981
vt 0.499998 1.084981
vt 0.261984 1.669965
vt 0.261984 1.084981
vt 0.499998 -0.084982
vt 0.261984 0.500000
vt 0.261984 -0.084982
vt 0.976031 -0.084982
vt 0.738016 0.500000
vt 0.738016 -0.084982
vt 0.499998 0.500000
vt 0.738016 -0.669965
vt 0.499998 -0.669965
vt 0.976031 -0.669965
vt 0.023969 0.500000
vt 0.023969 -0.084982
vt 0.261984 -0.669965
vt 0.023969 -0.669965
vt 0.023969 1.669965
vt 0.023969 1.084981
vt 0.499998 1.669965
vt 0.976031 0.500000
vt 0.976031 1.669965
vn 0.0000 0.0000 -1.0000
usemtl None
s 1
f 1/1/1 2/2/1 3/3/1
f 4/4/1 5/5/1 6/6/1
f 7/7/1 8/8/1 9/9/1
f 10/10/1 11/11/1 12/12/1
f 12/12/1 13/13/1 7/7/1
f 14/14/1 7/7/1 15/15/1
f 16/16/1 12/12/1 14/14/1
f 9/9/1 17/17/1 18/18/1
f 19/19/1 18/18/1 20/20/1
f 15/15/1 9/9/1 19/19/1
f 6/6/1 21/21/1 22/22/1
f 8/8/1 22/22/1 17/17/1
f 13/13/1 6/6/1 8/8/1
f 3/3/1 23/23/1 4/4/1
f 11/11/1 4/4/1 13/13/1
f 24/24/1 3/3/1 11/11/1
f 1/1/1 25/25/1 2/2/1
f 4/4/1 23/23/1 5/5/1
f 7/7/1 13/13/1 8/8/1
f 10/10/1 24/24/1 11/11/1
f 12/12/1 11/11/1 13/13/1
f 14/14/1 12/12/1 7/7/1
f 16/16/1 10/10/1 12/12/1
f 9/9/1 8/8/1 17/17/1
f 19/19/1 9/9/1 18/18/1
f 15/15/1 7/7/1 9/9/1
f 6/6/1 5/5/1 21/21/1
f 8/8/1 6/6/1 22/22/1
f 13/13/1 4/4/1 6/6/1
f 3/3/1 2/2/1 23/23/1
f 11/11/1 3/3/1 4/4/1
f 24/24/1 1/1/1 3/3/1

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cloth_z_up.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,80 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
NUM_MOTORS = 12
NOISY_READING = True
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"]
robot_sensors.IMUSensor.noisy_reading = %NOISY_READING
robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS
robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING
robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203
robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203
sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()]
Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0"
Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1"
Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2"
Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3"
Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4"
Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5"
Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6"
Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7"
Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8"
Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9"
Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10"
Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11"
Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
locomotion_gym_config.LocomotionGymConfig.actions = [
@Act0/locomotion_gym_config.ScalarField(),
@Act1/locomotion_gym_config.ScalarField(),
@Act2/locomotion_gym_config.ScalarField(),
@Act3/locomotion_gym_config.ScalarField(),
@Act4/locomotion_gym_config.ScalarField(),
@Act5/locomotion_gym_config.ScalarField(),
@Act6/locomotion_gym_config.ScalarField(),
@Act7/locomotion_gym_config.ScalarField(),
@Act8/locomotion_gym_config.ScalarField(),
@Act9/locomotion_gym_config.ScalarField(),
@Act10/locomotion_gym_config.ScalarField(),
@Act11/locomotion_gym_config.ScalarField()]

View File

@ -0,0 +1,116 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.robots.laikago
URDF_ROOT = "urdf/"
ABDUCTION_P_GAIN = 220.0
ABDUCTION_D_GAIN = 0.3
HIP_P_GAIN = 220.0
HIP_D_GAIN = 2.0
KNEE_P_GAIN = 220.0
KNEE_D_GAIN = 2.0
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
NUM_MOTORS = 12
NOISY_READING = True
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"]
robot_sensors.IMUSensor.noisy_reading = %NOISY_READING
robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS
robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING
robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203
robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203
sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()]
Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0"
Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1"
Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2"
Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3"
Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4"
Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5"
Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6"
Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7"
Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8"
Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9"
Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10"
Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11"
Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
locomotion_gym_config.LocomotionGymConfig.actions = [
@Act0/locomotion_gym_config.ScalarField(),
@Act1/locomotion_gym_config.ScalarField(),
@Act2/locomotion_gym_config.ScalarField(),
@Act3/locomotion_gym_config.ScalarField(),
@Act4/locomotion_gym_config.ScalarField(),
@Act5/locomotion_gym_config.ScalarField(),
@Act6/locomotion_gym_config.ScalarField(),
@Act7/locomotion_gym_config.ScalarField(),
@Act8/locomotion_gym_config.ScalarField(),
@Act9/locomotion_gym_config.ScalarField(),
@Act10/locomotion_gym_config.ScalarField(),
@Act11/locomotion_gym_config.ScalarField()]
laikago.Laikago.urdf_root = %URDF_ROOT
laikago.Laikago.time_step = %SIM_TIME_STEP
laikago.Laikago.action_repeat = %NUM_ACTION_REPEAT
laikago.Laikago.self_collision_enabled = False
laikago.Laikago.control_latency = 0.002
laikago.Laikago.pd_latency = 0.0
laikago.Laikago.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN]
laikago.Laikago.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN]
laikago.Laikago.sensors = %sensors
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago.Laikago
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()

View File

@ -0,0 +1,149 @@
#-*-Python-*-
# NOTE: Should be run with >=10CPU for decent performance.
import pybullet_envs.minitaur.agents.baseline_controller.torque_stance_leg_controller
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.mpc_locomotion_wrapper
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.sensors.camera_sensor
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.last_action_sensor
import pybullet_envs.minitaur.envs_v2.sensors.toe_position_sensor
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions
import pybullet_envs.minitaur.envs_v2.utilities.noise_generators
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.robot_config
# Configure the dynamic robot
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 4 # Control frequency will be 100 Hz
########################################
# Configure the sensors
########################################
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, -6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, 6283.18554688, 6283.18554688]
# Add noise to the IMU sensor and toe position sensor
IMUNoise/noise_generators.NormalNoise.scale = (0.025, 0.025, 0.1, 0.1)
TOENoise/noise_generators.NormalNoise.scale = (0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005)
imu_sensor.IMUSensor.noise_generator = @IMUNoise/noise_generators.NormalNoise()
toe_position_sensor.ToePositionSensor.noise_generator = @TOENoise/noise_generators.NormalNoise()
frontCamera/camera_sensor.CameraSensor.camera_translation_from_base = (0.197, 0.0, -0.115)
frontCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982)
frontCamera/camera_sensor.CameraSensor.parent_link_id = -1
frontCamera/camera_sensor.CameraSensor.resolution = (32, 24)
frontCamera/camera_sensor.CameraSensor.sensor_latency = 0.03
frontCamera/camera_sensor.CameraSensor.name = "frontCam"
frontCamera/camera_sensor.CameraSensor.fov_degree = 75
frontCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH
frontCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0
rearCamera/camera_sensor.CameraSensor.camera_translation_from_base = (-0.092, 0.0, -0.105)
rearCamera/camera_sensor.CameraSensor.camera_rotation_from_base = (-0.4996018, 0.4999998, 0.4999998, 0.5003982)
rearCamera/camera_sensor.CameraSensor.parent_link_id = -1
rearCamera/camera_sensor.CameraSensor.resolution = (32, 24)
rearCamera/camera_sensor.CameraSensor.sensor_latency = 0.03
rearCamera/camera_sensor.CameraSensor.name = "rearCam"
rearCamera/camera_sensor.CameraSensor.fov_degree = 75
rearCamera/camera_sensor.CameraSensor.camera_mode = %sim_camera.CameraMode.DEPTH
rearCamera/camera_sensor.CameraSensor.camera_update_frequency_hz = 30.0
sensors = [@imu_sensor.IMUSensor(), @last_action_sensor.LastActionSensor(), @toe_position_sensor.ToePositionSensor(), @frontCamera/camera_sensor.CameraSensor(), @rearCamera/camera_sensor.CameraSensor()]
laikago_v2.Laikago.sensors = %sensors
########################################
# Specify the motor model and its parameters
########################################
LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203
LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203
laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS
laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS
laikago/robot_config.MotorLimits.torque_lower_limits = -30
laikago/robot_config.MotorLimits.torque_upper_limits = 30
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.HYBRID
laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
hybrid_motor_model.HybridMotorModel.kp = 250
hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0)
########################################
# Setup the terrain randomization and simulation parameters
########################################
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
########################################
# Setup the task and terminal condition parameters
########################################
terminal_conditions.maxstep_terminal_condition.max_step = 2000
terminal_conditions.default_terminal_condition_for_laikago_v2.max_roll = 0.25
terminal_conditions.default_terminal_condition_for_laikago_v2.max_pitch = 1.0
terminal_conditions.default_terminal_condition_for_laikago_v2.min_height = 0.15
terminal_conditions.default_terminal_condition_for_laikago_v2.enforce_foot_contacts = True
# Setup the terminal condition
terminal_conditions.logical_any_terminal_condition.conditions = [
@terminal_conditions.default_terminal_condition_for_laikago_v2,
@terminal_conditions.maxstep_terminal_condition,
]
simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition
env_loader.load.wrapper_classes = [
@mpc_locomotion_wrapper.MPCLocomotionWrapper,
]
########################################
# Configure the MPC-related parameters
########################################
torque_stance_leg_controller.TorqueStanceLegController.qp_weights = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0)
torque_stance_leg_controller.TorqueStanceLegController.body_inertia = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, 0.636175)
torque_stance_leg_controller.TorqueStanceLegController.friction_coeffs = (0.45, 0.45, 0.45, 0.45)
########################################
# Configure the foothold wrapper parameters and action space
########################################
mpc_locomotion_wrapper.MPCLocomotionWrapper.foot_friction_coeff = 1.0
mpc_locomotion_wrapper.MPCLocomotionWrapper.locomotion_gait = %mpc_locomotion_wrapper.Gait.TROT
mpc_locomotion_wrapper.MPCLocomotionWrapper.control_frequency=20
mpc_locomotion_wrapper.MPCLocomotionWrapper.target_horizontal_com_velocity_heuristic = @mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic()
mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic.gains = (-0.25, -0.1)
mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_target_action_range = ((-0.05, -0.05, -0.03), (0.1, 0.05, 0.03))
mpc_locomotion_wrapper.MPCLocomotionWrapper.pitch_action_range = (-0.2, 0.2)
mpc_locomotion_wrapper.MPCLocomotionWrapper.roll_action_range = (-0.05, 0.05)
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_velocity_action_range = ((-0.05, -0.05), (0.05, 0.05))
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_twist_action_range = (-0.2, 0.2)
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_height_action_range = (0.42, 0.48)
mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_clearance_action_range = (0.05, 0.1)
imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator.use_sensor_interface = False

View File

@ -0,0 +1,142 @@
#-*-Python-*-
# NOTE: Should be run with >=10CPU for decent performance.
import pybullet_envs.minitaur.agents.baseline_controller.torque_stance_leg_controller
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.mpc_locomotion_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.random_stepstone_scene
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.last_action_sensor
import pybullet_envs.minitaur.envs_v2.sensors.toe_position_sensor
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions
import pybullet_envs.minitaur.envs_v2.utilities.noise_generators
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.robot_config
# Configure the dynamic robot
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 4 # Control frequency will be 100 Hz
########################################
# Configure the sensors
########################################
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203, -6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203, 6283.18554688, 6283.18554688]
# Add noise to the IMU sensor and toe position sensor
# IMUNoise/noise_generators.NormalNoise.scale = (0.025, 0.025, 0.1, 0.1)
# TOENoise/noise_generators.NormalNoise.scale = (0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005, 0.0025, 0.0025, 0.005)
# imu_sensor.IMUSensor.noise_generator = @IMUNoise/noise_generators.NormalNoise()
# toe_position_sensor.ToePositionSensor.noise_generator = @TOENoise/noise_generators.NormalNoise()
sensors = [@imu_sensor.IMUSensor(), @last_action_sensor.LastActionSensor(), @toe_position_sensor.ToePositionSensor()]
laikago_v2.Laikago.sensors = %sensors
########################################
# Specify the motor model and its parameters
########################################
LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203
LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203
laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS
laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS
laikago/robot_config.MotorLimits.torque_lower_limits = -30
laikago/robot_config.MotorLimits.torque_upper_limits = 30
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.HYBRID
laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
hybrid_motor_model.HybridMotorModel.kp = 250
hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0)
########################################
# Setup the terrain randomization and simulation parameters
########################################
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
locomotion_gym_env.LocomotionGymEnv.scene = @random_stepstone_scene.RandomStepstoneScene()
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
random_stepstone_scene.RandomStepstoneScene.random_seed = 13
random_stepstone_scene.RandomStepstoneScene.gap_length_lower_bound = 0.07
random_stepstone_scene.RandomStepstoneScene.gap_length_upper_bound = 0.15
random_stepstone_scene.RandomStepstoneScene.stone_width = 0.6
########################################
# Setup the task and terminal condition parameters
########################################
terminal_conditions.maxstep_terminal_condition.max_step = 2000
terminal_conditions.default_terminal_condition_for_laikago_v2.max_roll = 0.25
terminal_conditions.default_terminal_condition_for_laikago_v2.max_pitch = 1.0
terminal_conditions.default_terminal_condition_for_laikago_v2.min_height = 0.15
terminal_conditions.default_terminal_condition_for_laikago_v2.enforce_foot_contacts = True
# Setup the terminal condition
terminal_conditions.logical_any_terminal_condition.conditions = [
@terminal_conditions.default_terminal_condition_for_laikago_v2,
@terminal_conditions.maxstep_terminal_condition,
]
simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition
simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.0015
time_ordered_buffer.TimeOrderedBuffer.error_on_duplicate_timestamp = False
time_ordered_buffer.TimeOrderedBuffer.replace_value_on_duplicate_timestamp = True
time_ordered_buffer.TimeOrderedBuffer.error_on_timestamp_reversal = False
observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper.observation_excluded = ('frontCam', 'rearCam')
env_loader.load.wrapper_classes = [
@mpc_locomotion_wrapper.MPCLocomotionWrapper,
@observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper,
]
########################################
# Configure the MPC-related parameters
########################################
torque_stance_leg_controller.TorqueStanceLegController.qp_weights = (5, 5, 0.2, 0, 0, 10, 0.5, 0.5, 0.2, 0.2, 0.2, 0.1, 0)
torque_stance_leg_controller.TorqueStanceLegController.body_inertia = (0.183375, 0, 0, 0, 0.6267, 0, 0, 0, 0.636175)
torque_stance_leg_controller.TorqueStanceLegController.friction_coeffs = (0.45, 0.45, 0.45, 0.45)
########################################
# Configure the foothold wrapper parameters and action space
########################################
mpc_locomotion_wrapper.MPCLocomotionWrapper.foot_friction_coeff = 1.0
mpc_locomotion_wrapper.MPCLocomotionWrapper.locomotion_gait = %mpc_locomotion_wrapper.Gait.TROT
mpc_locomotion_wrapper.MPCLocomotionWrapper.control_frequency=20
mpc_locomotion_wrapper.MPCLocomotionWrapper.target_horizontal_com_velocity_heuristic = @mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic()
mpc_locomotion_wrapper.InverseRaibertTargetHorizontalComVelocityHeuristic.gains = (-0.25, -0.1)
mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_target_action_range = ((-0.05, -0.05, -0.03), (0.1, 0.05, 0.03))
mpc_locomotion_wrapper.MPCLocomotionWrapper.pitch_action_range = (-0.2, 0.2)
mpc_locomotion_wrapper.MPCLocomotionWrapper.roll_action_range = (-0.05, 0.05)
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_velocity_action_range = ((-0.05, -0.05), (0.05, 0.05))
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_twist_action_range = (-0.2, 0.2)
mpc_locomotion_wrapper.MPCLocomotionWrapper.base_height_action_range = (0.42, 0.48)
mpc_locomotion_wrapper.MPCLocomotionWrapper.swing_clearance_action_range = (0.05, 0.1)
imu_based_com_velocity_estimator.IMUBasedCOMVelocityEstimator.use_sensor_interface = False

View File

@ -0,0 +1,133 @@
#-*-Python-*-
# NOTE: Should be run with >=10CPU for decent performance.
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop
import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.robots.laikago
URDF_ROOT = "urdf/"
ABDUCTION_P_GAIN = 220.0
ABDUCTION_D_GAIN = 0.3
HIP_P_GAIN = 220.0
HIP_D_GAIN = 2.0
KNEE_P_GAIN = 220.0
KNEE_D_GAIN = 2.0
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.sensors.robot_sensors
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
NUM_MOTORS = 12
NOISY_READING = True
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
robot_sensors.IMUSensor.channels = ["R", "P", "dR", "dP"]
robot_sensors.IMUSensor.noisy_reading = %NOISY_READING
robot_sensors.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
robot_sensors.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
robot_sensors.MotorAngleSensor.num_motors = %NUM_MOTORS
robot_sensors.MotorAngleSensor.noisy_reading = %NOISY_READING
robot_sensors.MotorAngleSensor.lower_bound = -6.28318548203
robot_sensors.MotorAngleSensor.upper_bound = 6.28318548203
sensors = [@robot_sensors.IMUSensor(), @robot_sensors.MotorAngleSensor()]
Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0"
Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1"
Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2"
Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3"
Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4"
Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5"
Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6"
Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7"
Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8"
Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9"
Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10"
Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11"
Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
locomotion_gym_config.LocomotionGymConfig.actions = [
@Act0/locomotion_gym_config.ScalarField(),
@Act1/locomotion_gym_config.ScalarField(),
@Act2/locomotion_gym_config.ScalarField(),
@Act3/locomotion_gym_config.ScalarField(),
@Act4/locomotion_gym_config.ScalarField(),
@Act5/locomotion_gym_config.ScalarField(),
@Act6/locomotion_gym_config.ScalarField(),
@Act7/locomotion_gym_config.ScalarField(),
@Act8/locomotion_gym_config.ScalarField(),
@Act9/locomotion_gym_config.ScalarField(),
@Act10/locomotion_gym_config.ScalarField(),
@Act11/locomotion_gym_config.ScalarField()]
laikago.Laikago.urdf_root = %URDF_ROOT
laikago.Laikago.time_step = %SIM_TIME_STEP
laikago.Laikago.action_repeat = %NUM_ACTION_REPEAT
laikago.Laikago.self_collision_enabled = False
laikago.Laikago.control_latency = 0.002
laikago.Laikago.pd_latency = 0.0
laikago.Laikago.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN]
laikago.Laikago.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN]
laikago.Laikago.sensors = %sensors
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago.Laikago
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv.trajectory_generator = @simple_openloop.LaikagoPoseOffsetGenerator()
env_loader.load.wrapper_classes = [
@observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper,
@trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv]

View File

@ -0,0 +1,65 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop
import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.robot_config
# Specify the gym env parameters
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 4
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
# Specify the world.
URDF_ROOT = ""
scene_base.SceneBase.data_root = %URDF_ROOT
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
# Specify the task.
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
# Specify the sensors. Sensors determine the observation space.
# Sensors can either be mounted on robots (see below), or passed to envs
# i.e. like ambient sensors, or provided by tasks (task specific measures).
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE,
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
# We use the default confirugration for MotorAngleSensor, which reads limits from the robot.
SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()]
# Specify the motor limits, and motor control mode.
LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203
LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203
laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS
laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION
laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here.
hybrid_motor_model.HybridMotorModel.kp = 2400
hybrid_motor_model.HybridMotorModel.kd = 5
# Finally, mount sensors specified above to the Laikago.
laikago_v2.Laikago.sensors = %SENSORS

View File

@ -0,0 +1,48 @@
#-*-Python-*-
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.robots.minitaur_motor_model_v2
import pybullet_envs.minitaur.robots.minitaur_v2
import pybullet_envs.minitaur.robots.robot_config
UPPER_BOUND = 1.0
LOWER_BOUND = -1.0
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 20
NUM_MOTORS = 8
NOISY_READING = True
SENSOR_LATENCY = 0.02
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND
robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND
minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION
minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits()
minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel
minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003
minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0
minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
motor_angle_sensor.MotorAngleSensor.sensor_latency = %SENSOR_LATENCY
motor_angle_sensor.MotorAngleSensor.lower_bound = -6.28318548203
motor_angle_sensor.MotorAngleSensor.upper_bound = 6.28318548203
minitaur_v2.Minitaur.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()]

View File

@ -0,0 +1,63 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.robots.minitaur_v2
import pybullet_envs.minitaur.robots.robot_config
import pybullet_envs.minitaur.robots.robot_urdf_loader
URDF_ROOT = "urdf/"
#-*-Python-*-
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.robots.minitaur_motor_model_v2
import pybullet_envs.minitaur.robots.minitaur_v2
import pybullet_envs.minitaur.robots.robot_config
UPPER_BOUND = 1.0
LOWER_BOUND = -1.0
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 20
NUM_MOTORS = 8
NOISY_READING = True
SENSOR_LATENCY = 0.02
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND
robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND
minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION
minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits()
minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel
minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003
minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0
minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
motor_angle_sensor.MotorAngleSensor.sensor_latency = %SENSOR_LATENCY
motor_angle_sensor.MotorAngleSensor.lower_bound = -6.28318548203
motor_angle_sensor.MotorAngleSensor.upper_bound = 6.28318548203
minitaur_v2.Minitaur.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()]
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
locomotion_gym_env.LocomotionGymEnv.robot_class = @minitaur_v2.Minitaur
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()

View File

@ -0,0 +1,80 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.simple_openloop
import pybullet_envs.minitaur.envs_v2.env_wrappers.trajectory_generator_wrapper_env
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.sensors.accelerometer_sensor
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.time_ordered_buffer
# Specify the gym env parameters
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
# Specify the robot
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS = 6.28318548203
LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS = -6.28318548203
laikago/robot_config.MotorLimits.angle_lower_limits = %LAIKAGO_MOTOR_ANGLE_LOWER_LIMITS
laikago/robot_config.MotorLimits.angle_upper_limits = %LAIKAGO_MOTOR_ANGLE_UPPER_LIMITS
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION
# Specify the motor model parameters. Notice that we don't need to specify the control mode
# and motor limits here, as they will be passed from the robot interface.
hybrid_motor_model.HybridMotorModel.kp = 220
hybrid_motor_model.HybridMotorModel.kd = (0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0, 0.3, 2.0, 2.0)
# This will make sure the hybrid motor model does not throw error during reset, when the timestamp is alwasy zero.
time_ordered_buffer.TimeOrderedBuffer.error_on_duplicate_timestamp = False
time_ordered_buffer.TimeOrderedBuffer.replace_value_on_duplicate_timestamp = True
# Add the sensors
laikago_v2.Laikago.sensors = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor(), @accelerometer_sensor.AccelerometerSensor()]
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE,
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
# Specify the scene
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
simple_scene.SimpleScene.data_root = "third_party/bullet/data"
# Specify the task.
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.default_terminal_condition_for_laikago
accelerometer_sensor.AccelerometerSensor.lower_bound = [-50.0, -50.0, -50.0]
accelerometer_sensor.AccelerometerSensor.upper_bound = [50.0, 50.0, 50.0]
accelerometer_sensor.AccelerometerSensor.sensor_latency = 0.01
imu_sensor.IMUSensor.sensor_latency = 0.1
# Define the wrappers needed
env_loader.load.wrapper_classes = [
@trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv,
]
trajectory_generator_wrapper_env.TrajectoryGeneratorWrapperEnv.trajectory_generator = @simple_openloop.LaikagoPoseOffsetGenerator()

View File

@ -0,0 +1,66 @@
#import pybullet_data
#MYPATH = pybullet_data.getDataPath()+'/configs_v2/robots/laikago.gin'
#MYPATH = 'D:/dev/bullet3/examples/pybullet\gym/pybullet_data/configs_v2/robots/laikago.gin'
#include '$MYPATH/ambiguous.gin'
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.scene_base
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.robot_config
URDF_ROOT = ""
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE,
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
# We use the default confirugration for MotorAngleSensor, which reads limits from the robot.
SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()]
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
# Specify the scene.
scene_base.SceneBase.data_root = %URDF_ROOT
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
# Specify the motor limits, and motor control mode.
laikago/robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND
laikago/robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION
laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here.
hybrid_motor_model.HybridMotorModel.kp = 220
hybrid_motor_model.HybridMotorModel.kd = 2
laikago_v2.Laikago.sensors = %SENSORS
laikago_v2.Laikago.sensors = [@imu_sensor.IMUSensor()]

View File

@ -0,0 +1,9 @@
import pybullet_data as pd
include pd.getDataPath()+'/configs_v2/robots/mini_cheetah.gin'
include pd.getDataPath()+'/configs_v2/sensors/imu.gin'
#include 'robotics/reinforcement_learning/minitaur/envs_v2/configs_v2/robots/mini_cheetah.gin'
#include 'robotics/reinforcement_learning/minitaur/envs_v2/configs_v2/sensors/imu.gin'
mini_cheetah.MiniCheetah.sensors = [@robot_sensors.IMUSensor()]

View File

@ -0,0 +1,58 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.scene_base
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
import pybullet_envs.minitaur.envs_v2.sensors.imu_sensor
import pybullet_envs.minitaur.envs_v2.sensors.motor_angle_sensor
import pybullet_envs.minitaur.robots.hybrid_motor_model
import pybullet_envs.minitaur.robots.laikago_v2
import pybullet_envs.minitaur.robots.robot_config
URDF_ROOT = ""
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
imu_sensor.IMUSensor.channels = [
%imu_sensor.IMUChannel.ROLL,
%imu_sensor.IMUChannel.PITCH,
%imu_sensor.IMUChannel.ROLL_RATE,
%imu_sensor.IMUChannel.PITCH_RATE,
]
imu_sensor.IMUSensor.lower_bound = [-6.28318548203, -6.28318548203,
-6283.18554688, -6283.18554688]
imu_sensor.IMUSensor.upper_bound = [6.28318548203, 6.28318548203,
6283.18554688, 6283.18554688]
# We use the default confirugration for MotorAngleSensor, which reads limits from the robot.
SENSORS = [@imu_sensor.IMUSensor(), @motor_angle_sensor.MotorAngleSensor()]
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
# Specify the scene.
scene_base.SceneBase.data_root = %URDF_ROOT
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()
# Specify the motor limits, and motor control mode.
laikago/robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND
laikago/robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND
laikago_v2.Laikago.motor_limits = @laikago/robot_config.MotorLimits()
laikago_v2.Laikago.motor_control_mode = %robot_config.MotorControlMode.POSITION
laikago_v2.Laikago.motor_model_class = @hybrid_motor_model.HybridMotorModel
locomotion_gym_env.LocomotionGymEnv.robot_class = @laikago_v2.Laikago
# Specify the motor model parameters. Notice that we don't need to specify the control mode or motor limits here.
hybrid_motor_model.HybridMotorModel.kp = 220
hybrid_motor_model.HybridMotorModel.kd = 2
laikago_v2.Laikago.sensors = %SENSORS

View File

@ -0,0 +1,98 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.robots.mini_cheetah
import pybullet_data as pd
URDF_ROOT = pd.getDataPath()+"/urdf/"
ABDUCTION_P_GAIN = 100.0
ABDUCTION_D_GAIN = 1.0
HIP_P_GAIN = 30
HIP_D_GAIN = 2.0
KNEE_P_GAIN = 50
KNEE_D_GAIN = 2.0
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 2
NUM_MOTORS = 12
NOISY_READING = True
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
Act0/locomotion_gym_config.ScalarField.name = "motor_angle_0"
Act0/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act0/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act1/locomotion_gym_config.ScalarField.name = "motor_angle_1"
Act1/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act1/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act2/locomotion_gym_config.ScalarField.name = "motor_angle_2"
Act2/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act2/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act3/locomotion_gym_config.ScalarField.name = "motor_angle_3"
Act3/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act3/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act4/locomotion_gym_config.ScalarField.name = "motor_angle_4"
Act4/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act4/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act5/locomotion_gym_config.ScalarField.name = "motor_angle_5"
Act5/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act5/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act6/locomotion_gym_config.ScalarField.name = "motor_angle_6"
Act6/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act6/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act7/locomotion_gym_config.ScalarField.name = "motor_angle_7"
Act7/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act7/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act8/locomotion_gym_config.ScalarField.name = "motor_angle_8"
Act8/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act8/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act9/locomotion_gym_config.ScalarField.name = "motor_angle_9"
Act9/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act9/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act10/locomotion_gym_config.ScalarField.name = "motor_angle_10"
Act10/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act10/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
Act11/locomotion_gym_config.ScalarField.name = "motor_angle_11"
Act11/locomotion_gym_config.ScalarField.upper_bound = %UPPER_BOUND
Act11/locomotion_gym_config.ScalarField.lower_bound = %LOWER_BOUND
locomotion_gym_config.LocomotionGymConfig.actions = [
@Act0/locomotion_gym_config.ScalarField(),
@Act1/locomotion_gym_config.ScalarField(),
@Act2/locomotion_gym_config.ScalarField(),
@Act3/locomotion_gym_config.ScalarField(),
@Act4/locomotion_gym_config.ScalarField(),
@Act5/locomotion_gym_config.ScalarField(),
@Act6/locomotion_gym_config.ScalarField(),
@Act7/locomotion_gym_config.ScalarField(),
@Act8/locomotion_gym_config.ScalarField(),
@Act9/locomotion_gym_config.ScalarField(),
@Act10/locomotion_gym_config.ScalarField(),
@Act11/locomotion_gym_config.ScalarField()]
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
mini_cheetah.MiniCheetah.urdf_root = %URDF_ROOT
mini_cheetah.MiniCheetah.time_step = %SIM_TIME_STEP
mini_cheetah.MiniCheetah.action_repeat = %NUM_ACTION_REPEAT
mini_cheetah.MiniCheetah.self_collision_enabled = False
mini_cheetah.MiniCheetah.control_latency = 0.002
mini_cheetah.MiniCheetah.pd_latency = 0.0
mini_cheetah.MiniCheetah.motor_kp = [%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN,
%ABDUCTION_P_GAIN, %HIP_P_GAIN, %KNEE_P_GAIN]
mini_cheetah.MiniCheetah.motor_kd = [%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN,
%ABDUCTION_D_GAIN, %HIP_D_GAIN, %KNEE_D_GAIN]
locomotion_gym_env.LocomotionGymEnv.robot_class = @mini_cheetah.MiniCheetah

View File

@ -0,0 +1,31 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_config
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.robots.minitaur_motor_model_v2
import pybullet_envs.minitaur.robots.minitaur_v2
URDF_ROOT = "robotics/reinforcement_learning/minitaur/robots/data/urdf/"
UPPER_BOUND = 6.28318548203
LOWER_BOUND = -6.28318548203
SIM_TIME_STEP = 0.001
NUM_ACTION_REPEAT = 6
NUM_MOTORS = 8
NOISY_READING = True
locomotion_gym_config.SimulationParameters.sim_time_step_s = %SIM_TIME_STEP
locomotion_gym_config.SimulationParameters.num_action_repeat = %NUM_ACTION_REPEAT
locomotion_gym_config.SimulationParameters.enable_rendering = False
locomotion_gym_config.LocomotionGymConfig.simulation_parameters = @locomotion_gym_config.SimulationParameters()
locomotion_gym_env.LocomotionGymEnv.gym_config = @locomotion_gym_config.LocomotionGymConfig()
minitaur_v2.Minitaur.motor_control_mode = %robot_config.MotorControlMode.POSITION
minitaur_v2.Minitaur.motor_limits = @robot_config.MotorLimits()
minitaur_v2.Minitaur.motor_model_class = @minitaur_motor_model_v2.MinitaurMotorModel
minitaur_motor_model_v2.MinitaurMotorModel.pd_latency = 0.003
minitaur_motor_model_v2.MinitaurMotorModel.kp = 1.0
minitaur_motor_model_v2.MinitaurMotorModel.kd = 0.015
locomotion_gym_env.LocomotionGymEnv.robot_class = @minitaur_v2.Minitaur
robot_config.MotorLimits.angle_lower_limits = %LOWER_BOUND
robot_config.MotorLimits.angle_upper_limits = %UPPER_BOUND

View File

@ -0,0 +1,4 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.scenes.simple_scene
locomotion_gym_env.LocomotionGymEnv.scene = @simple_scene.SimpleScene()

View File

@ -0,0 +1,3 @@
import pybullet_envs.minitaur.envs_v2.scenes.stair_scene
# Specify the scene (overwrite the setting from laikago_reactive.gin)
locomotion_gym_env.LocomotionGymEnv.scene = @stair_scene.StairScene()

View File

@ -0,0 +1,4 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()

View File

@ -0,0 +1,8 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()
simple_locomotion_task.SimpleForwardTask.energy_penalty_coef = 0.002
simple_locomotion_task.SimpleForwardTask.min_com_height = 0.3
simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.002

View File

@ -0,0 +1,11 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions
terminal_conditions.maxstep_terminal_condition.max_step = 1500
# Setup the terminal condition to not to terminate early when the robot falls.
terminal_conditions.logical_any_terminal_condition.conditions = [
@terminal_conditions.maxstep_terminal_condition,
]
simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.logical_any_terminal_condition
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()

View File

@ -0,0 +1,12 @@
import pybullet_envs.minitaur.envs_v2.locomotion_gym_env
import pybullet_envs.minitaur.envs_v2.tasks.simple_locomotion_task
import pybullet_envs.minitaur.envs_v2.tasks.terminal_conditions
terminal_conditions.maxstep_terminal_condition.max_step = 1500
simple_locomotion_task.SimpleForwardTask.terminal_condition = @terminal_conditions.default_terminal_condition_for_laikago_v2
simple_locomotion_task.SimpleForwardTask.divide_with_dt = True
simple_locomotion_task.SimpleForwardTask.clip_velocity = 0.4
simple_locomotion_task.SimpleForwardTask.energy_penalty_coef = 0
locomotion_gym_env.LocomotionGymEnv.task = @simple_locomotion_task.SimpleForwardTask()

View File

@ -0,0 +1,18 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = 1
pmtg_wrapper_env.PmtgWrapperEnv.intensity_upper_bound = 1.0
pmtg_wrapper_env.PmtgWrapperEnv.max_delta_time = 4.0
pmtg_wrapper_env.PmtgWrapperEnv.min_delta_time = 2.0
pmtg_wrapper_env.PmtgWrapperEnv.residual_range = 0.35
pmtg_wrapper_env.PmtgWrapperEnv.integrator_coupling_mode = "all coupled"
pmtg_wrapper_env.PmtgWrapperEnv.walk_height_coupling_mode = "all coupled"
pmtg_wrapper_env.PmtgWrapperEnv.variable_swing_stance_ratio = 1
pmtg_wrapper_env.PmtgWrapperEnv.init_gait = "walk"
env_loader.load.wrapper_classes = [
@pmtg_wrapper_env.PmtgWrapperEnv,
@observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper]

View File

@ -0,0 +1,6 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True
env_loader.load.wrapper_classes = [@pmtg_wrapper_env.PmtgWrapperEnv]

View File

@ -0,0 +1,10 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_enable = True
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_high_cut = 0.5
env_loader.load.wrapper_classes = [
@pmtg_wrapper_env.PmtgWrapperEnv,
@observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper]

View File

@ -0,0 +1,18 @@
import pybullet_envs.minitaur.envs_v2.env_loader
import pybullet_envs.minitaur.envs_v2.env_wrappers.observation_dictionary_to_array_wrapper
import pybullet_envs.minitaur.envs_v2.env_wrappers.pmtg_wrapper_env
pmtg_wrapper_env.PmtgWrapperEnv.init_leg_phase_offsets = [0, 0.5, 0.5, 0]
pmtg_wrapper_env.PmtgWrapperEnv.integrator_coupling_mode = 'all coupled'
pmtg_wrapper_env.PmtgWrapperEnv.intensity_upper_bound = 0.5
pmtg_wrapper_env.PmtgWrapperEnv.max_delta_time = 4
pmtg_wrapper_env.PmtgWrapperEnv.min_delta_time = 1
pmtg_wrapper_env.PmtgWrapperEnv.residual_range = 0.2
pmtg_wrapper_env.PmtgWrapperEnv.variable_swing_stance_ratio = False
pmtg_wrapper_env.PmtgWrapperEnv.walk_height_coupling_mode = 'null'
pmtg_wrapper_env.PmtgWrapperEnv.action_filter_high_cut = 0.5
env_loader.load.wrapper_classes = [
@pmtg_wrapper_env.PmtgWrapperEnv,
@observation_dictionary_to_array_wrapper.ObservationDictionaryToArrayWrapper]

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cube.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,29 @@
<?xml version="1.0" ?>
<robot name="cube">
<link name="baseLink">
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="cube.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision group="0" mask="0">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,28 @@
<robot name="mug">
<link name="base_link">
<contact>
<lateral_friction value="1.0"/>
</contact>
<inertial>
<origin xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin xyz="0 0 0"/>
<geometry>
<mesh filename="mug.obj"/>
</geometry>
<material name="mug">
<color rgba="1 0.2 0.2 1"/>
<specular rgb="1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<mesh filename="mug_col.obj"/>
</geometry>
</collision>
</link>
</robot>

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

@ -0,0 +1,22 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="base_link">
<contact>
<rolling_friction value="0.001"/>
<spinning_friction value="0.001"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.005"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="baseLink">
<contact>
<rolling_friction value="0.03"/>
<spinning_friction value="0.03"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="10.0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
</geometry>
<material name="red_transparent">
<color rgba="1 0 0 0.5"/>
<specular rgb="11 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.5"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

View File

@ -0,0 +1,32 @@
# Blender v2.78 (sub 0) OBJ File: ''
# www.blender.org
mtllib stone.mtl
o Cube
v -0.246350 -0.246483 -0.000624
v -0.151407 -0.176325 0.172867
v -0.246350 0.249205 -0.000624
v -0.151407 0.129477 0.172867
v 0.249338 -0.246483 -0.000624
v 0.154395 -0.176325 0.172867
v 0.249338 0.249205 -0.000624
v 0.154395 0.129477 0.172867
vn -0.8772 0.0000 0.4801
vn 0.0000 0.8230 0.5680
vn 0.8772 0.0000 0.4801
vn 0.0000 -0.9271 0.3749
vn 0.0000 0.0000 -1.0000
vn 0.0000 0.0000 1.0000
usemtl None
s off
f 1//1 4//1 3//1
f 4//2 7//2 3//2
f 8//3 5//3 7//3
f 6//4 1//4 5//4
f 7//5 1//5 3//5
f 4//6 6//6 8//6
f 1//1 2//1 4//1
f 4//2 8//2 7//2
f 8//3 6//3 5//3
f 6//4 2//4 1//4
f 7//5 5//5 1//5
f 4//6 2//6 6//6

View File

@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<lateral_friction value="0.5"/>
<rolling_friction value="0.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0.07 0.05 0.03"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
</geometry>
<material name="red">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
</geometry>
</collision>
</link>
</robot>

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 12 KiB

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd ../cube.png

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot name="torus">
<deformable name="torus">
<inertial>
<mass value="3" />
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<collision_margin value="0.006"/>
<repulsion_stiffness value="800.0"/>
<friction value= "0.5"/>
<neohookean mu= "180" lambda= "600" damping= "0.01" />
<visual filename="torus.vtk"/>
</deformable>
</robot>

View File

@ -0,0 +1,14 @@
URDF created by Erwin Coumans
Bullet Continuous Collision Detection and Physics Library
http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2
map_Kd ../checker_grid.jpg

View File

@ -0,0 +1,949 @@
# Blender v2.78 (sub 0) OBJ File: ''
# www.blender.org
mtllib concave_box.mtl
o Cube_Cube.003
v 0.252358 -0.051546 0.073254
v 0.196823 -0.040500 0.026785
v 0.133463 -0.027897 -0.007745
v 0.064714 -0.014222 -0.029009
v 0.237323 -0.101112 0.073254
v 0.185009 -0.079443 0.026785
v 0.125326 -0.054721 -0.007745
v 0.060565 -0.027897 -0.029009
v 0.212906 -0.146792 0.073254
v 0.165826 -0.115334 0.026785
v 0.112112 -0.079443 -0.007745
v 0.053829 -0.040500 -0.029009
v 0.180047 -0.186831 0.073254
v 0.140008 -0.146792 0.026785
v 0.094329 -0.101112 -0.007745
v 0.044763 -0.051546 -0.029009
v 0.140008 -0.219690 0.073254
v 0.108550 -0.172609 0.026785
v 0.072660 -0.118895 -0.007745
v 0.033716 -0.060612 -0.029009
v -0.006783 -0.000000 -0.036189
v 0.094329 -0.244106 0.073254
v 0.072660 -0.191793 0.026785
v 0.047938 -0.132109 -0.007745
v 0.021113 -0.067349 -0.029009
v 0.044763 -0.259142 0.073254
v 0.033716 -0.203606 0.026785
v 0.021113 -0.140246 -0.007745
v 0.007438 -0.071497 -0.029009
v -0.006783 -0.264218 0.073254
v -0.006783 -0.207595 0.026785
v -0.006783 -0.142994 -0.007745
v -0.006783 -0.072898 -0.029009
v -0.058330 -0.259142 0.073254
v -0.047283 -0.203606 0.026785
v -0.034680 -0.140246 -0.007745
v -0.021005 -0.071497 -0.029009
v -0.107895 -0.244106 0.073254
v -0.086227 -0.191793 0.026785
v -0.061505 -0.132109 -0.007745
v -0.034680 -0.067349 -0.029009
v -0.153575 -0.219690 0.073254
v -0.122117 -0.172609 0.026785
v -0.086227 -0.118895 -0.007745
v -0.047283 -0.060612 -0.029009
v -0.193614 -0.186831 0.073254
v -0.153575 -0.146792 0.026785
v -0.107895 -0.101112 -0.007745
v -0.058330 -0.051546 -0.029009
v -0.226473 -0.146792 0.073254
v -0.179392 -0.115334 0.026785
v -0.125679 -0.079443 -0.007745
v -0.067396 -0.040500 -0.029009
v -0.250889 -0.101112 0.073254
v -0.198576 -0.079443 0.026785
v -0.138893 -0.054721 -0.007745
v -0.074132 -0.027897 -0.029009
v -0.265925 -0.051546 0.073254
v -0.210390 -0.040500 0.026785
v -0.147030 -0.027897 -0.007745
v -0.078280 -0.014222 -0.029009
v -0.271002 0.000000 0.073254
v -0.214378 0.000000 0.026785
v -0.149777 -0.000000 -0.007745
v -0.079681 -0.000000 -0.029009
v -0.265925 0.051546 0.073254
v -0.210390 0.040500 0.026785
v -0.147030 0.027897 -0.007745
v -0.078280 0.014222 -0.029009
v -0.250889 0.101112 0.073254
v -0.198576 0.079443 0.026785
v -0.138893 0.054721 -0.007745
v -0.074132 0.027897 -0.029009
v -0.226473 0.146792 0.073254
v -0.179392 0.115334 0.026785
v -0.125679 0.079443 -0.007745
v -0.067396 0.040500 -0.029009
v -0.193614 0.186831 0.073254
v -0.153575 0.146792 0.026785
v -0.107895 0.101112 -0.007745
v -0.058330 0.051546 -0.029009
v -0.153575 0.219690 0.073254
v -0.122117 0.172609 0.026785
v -0.086227 0.118895 -0.007745
v -0.047283 0.060612 -0.029009
v -0.107895 0.244106 0.073254
v -0.086227 0.191793 0.026785
v -0.061505 0.132109 -0.007745
v -0.034680 0.067349 -0.029009
v -0.058330 0.259141 0.073254
v -0.047283 0.203606 0.026785
v -0.034680 0.140246 -0.007745
v -0.021005 0.071497 -0.029009
v -0.006783 0.264218 0.073254
v -0.006783 0.207595 0.026785
v -0.006783 0.142994 -0.007745
v -0.006783 0.072898 -0.029009
v 0.044763 0.259141 0.073254
v 0.033716 0.203606 0.026785
v 0.021113 0.140246 -0.007745
v 0.007438 0.071497 -0.029009
v 0.094329 0.244106 0.073254
v 0.072660 0.191793 0.026785
v 0.047938 0.132109 -0.007745
v 0.021113 0.067349 -0.029009
v 0.140008 0.219689 0.073254
v 0.108550 0.172609 0.026785
v 0.072660 0.118895 -0.007745
v 0.033716 0.060612 -0.029009
v 0.180047 0.186831 0.073254
v 0.140008 0.146792 0.026785
v 0.094328 0.101112 -0.007745
v 0.044763 0.051546 -0.029009
v 0.212906 0.146792 0.073254
v 0.165825 0.115334 0.026785
v 0.112112 0.079443 -0.007745
v 0.053829 0.040500 -0.029009
v 0.237322 0.101112 0.073254
v 0.185009 0.079443 0.026785
v 0.125326 0.054721 -0.007745
v 0.060565 0.027897 -0.029009
v 0.252358 0.051546 0.073254
v 0.196823 0.040500 0.026785
v 0.133463 0.027897 -0.007745
v 0.064713 0.014222 -0.029009
v 0.257435 -0.000000 0.073254
v 0.200811 -0.000000 0.026785
v 0.136210 -0.000000 -0.007745
v 0.066114 -0.000000 -0.029009
v -1.000000 1.000000 -0.100000
v -1.000000 1.000000 0.100000
v 1.000000 1.000000 -0.100000
v 1.000000 1.000000 0.100000
v -1.000000 -1.000000 -0.100000
v -1.000000 -1.000000 0.100000
v 1.000000 -1.000000 -0.100000
v 1.000000 -1.000000 0.100000
v -0.006783 -0.286168 0.100000
v -0.062612 -0.280669 0.100000
v 0.195568 -0.202351 0.100000
v 0.231157 -0.158987 0.100000
v 0.257601 -0.109512 0.100000
v 0.195568 0.202351 0.100000
v -0.209135 0.202351 0.100000
v 0.273886 -0.055829 0.100000
v 0.273886 0.055829 0.100000
v 0.257601 0.109512 0.100000
v 0.152203 0.237940 0.100000
v -0.209135 -0.202351 0.100000
v -0.165770 -0.237940 0.100000
v -0.244724 -0.158986 0.100000
v -0.116295 -0.264385 0.100000
v -0.244723 0.158986 0.100000
v -0.165770 0.237940 0.100000
v -0.116295 0.264385 0.100000
v 0.231156 0.158986 0.100000
v -0.271168 -0.109512 0.100000
v -0.287453 0.055829 0.100000
v -0.292951 0.000000 0.100000
v 0.279384 -0.000000 0.100000
v 0.102728 -0.264385 0.100000
v 0.049045 0.280669 0.100000
v 0.049045 -0.280669 0.100000
v -0.287453 -0.055829 0.100000
v -0.062612 0.280669 0.100000
v -0.006783 0.286168 0.100000
v 0.152203 -0.237940 0.100000
v 0.102728 0.264385 0.100000
v -0.271168 0.109512 0.100000
vt 0.5258 0.8663
vt 0.5000 1.0000
vt 0.5000 0.8663
vt 0.5202 0.6339
vt 0.5000 0.6339
vt 0.5139 0.4613
vt 0.5000 0.4613
vt 0.5071 0.3550
vt 0.5000 0.3550
vt 0.5000 0.4966
vt 0.5071 0.5324
vt 0.5000 0.5331
vt 0.5139 0.5303
vt 0.5506 0.8663
vt 0.5279 1.0000
vt 0.5274 0.4613
vt 0.5139 0.3550
vt 0.5734 0.8663
vt 0.5548 1.0000
vt 0.5577 0.6339
vt 0.5397 0.6339
vt 0.5397 0.4613
vt 0.5202 0.3550
vt 0.5202 0.5269
vt 0.5258 0.5224
vt 0.6012 1.0000
vt 0.5795 1.0000
vt 0.5734 0.6339
vt 0.5506 0.4613
vt 0.5258 0.3550
vt 0.5700 0.6339
vt 0.5700 0.8663
vt 0.5900 0.8663
vt 0.5363 0.4613
vt 0.5472 0.4613
vt 0.5169 0.3550
vt 0.5224 0.3550
vt 0.5303 0.5169
vt 0.5978 1.0000
vt 0.5514 1.0000
vt 0.5761 1.0000
vt 0.5543 0.6339
vt 0.5472 0.8663
vt 0.5363 0.6339
vt 0.5240 0.4613
vt 0.5337 0.5106
vt 0.5224 0.8663
vt 0.5106 0.4613
vt 0.5106 0.3550
vt 0.5357 0.5037
vt 0.4966 1.0000
vt 0.5245 1.0000
vt 0.5169 0.6339
vt 0.4966 0.8663
vt 0.4966 0.6339
vt 0.5037 0.3550
vt 0.4966 0.4613
vt 0.5364 0.4966
vt 0.4827 0.4613
vt 0.4895 0.3550
vt 0.4966 0.3550
vt 0.5357 0.4895
vt 0.4708 0.8663
vt 0.4461 0.8663
vt 0.4687 1.0000
vt 0.4764 0.6339
vt 0.4569 0.6339
vt 0.4692 0.4613
vt 0.5337 0.4827
vt 0.4827 0.3550
vt 0.4569 0.4613
vt 0.5303 0.4764
vt 0.4232 0.8663
vt 0.4419 1.0000
vt 0.4389 0.6339
vt 0.4032 0.8663
vt 0.4171 1.0000
vt 0.4232 0.6339
vt 0.4708 0.3550
vt 0.4764 0.3550
vt 0.5258 0.4708
vt 0.5202 0.3550
vt 0.5506 0.4613
vt 0.5258 0.3550
vt 0.5202 0.4663
vt 0.5734 0.8663
vt 0.6012 1.0000
vt 0.5934 0.8663
vt 0.5734 0.6339
vt 0.5577 0.6339
vt 0.5506 0.8663
vt 0.5795 1.0000
vt 0.5274 0.4613
vt 0.5397 0.4613
vt 0.5139 0.4629
vt 0.5071 0.4609
vt 0.5279 1.0000
vt 0.5548 1.0000
vt 0.5202 0.6339
vt 0.5397 0.6339
vt 0.5139 0.4613
vt 0.5071 0.3550
vt 0.5139 0.3550
vt 0.5000 0.8663
vt 0.5258 0.8663
vt 0.5000 0.6339
vt 0.5000 0.4613
vt 0.5000 0.4602
vt 0.4929 0.4609
vt 0.4742 0.8663
vt 0.5000 1.0000
vt 0.4798 0.6339
vt 0.4861 0.4613
vt 0.4929 0.3550
vt 0.5000 0.3550
vt 0.4603 0.6339
vt 0.4726 0.4613
vt 0.4861 0.4629
vt 0.4494 0.8663
vt 0.4721 1.0000
vt 0.4266 0.8663
vt 0.4452 1.0000
vt 0.4603 0.4613
vt 0.4861 0.3550
vt 0.4798 0.4663
vt 0.4266 0.6339
vt 0.4423 0.6339
vt 0.4742 0.3550
vt 0.4798 0.3550
vt 0.4742 0.4708
vt 0.4066 0.8663
vt 0.4205 1.0000
vt 0.4232 0.8663
vt 0.3954 1.0000
vt 0.4032 0.8663
vt 0.4389 0.6339
vt 0.4232 0.6339
vt 0.4569 0.4613
vt 0.4461 0.4613
vt 0.4708 0.3550
vt 0.4697 0.4764
vt 0.4569 0.6339
vt 0.4827 0.3550
vt 0.4764 0.3550
vt 0.4663 0.4827
vt 0.4461 0.8663
vt 0.4171 1.0000
vt 0.4708 0.8663
vt 0.4419 1.0000
vt 0.4764 0.6339
vt 0.4827 0.4613
vt 0.4692 0.4613
vt 0.4895 0.3550
vt 0.4643 0.4895
vt 0.4966 0.3550
vt 0.4636 0.4966
vt 0.4966 0.8663
vt 0.4687 1.0000
vt 0.4966 0.6339
vt 0.5224 0.8663
vt 0.4966 1.0000
vt 0.5169 0.6339
vt 0.4966 0.4613
vt 0.5037 0.3550
vt 0.4643 0.5037
vt 0.5106 0.3550
vt 0.5106 0.4613
vt 0.4663 0.5106
vt 0.5472 0.8663
vt 0.5245 1.0000
vt 0.5363 0.6339
vt 0.5240 0.4613
vt 0.5700 0.8663
vt 0.5514 1.0000
vt 0.5363 0.4613
vt 0.5169 0.3550
vt 0.4697 0.5169
vt 0.4742 0.5224
vt 0.5900 0.8663
vt 0.5761 1.0000
vt 0.5700 0.6339
vt 0.5543 0.6339
vt 0.5224 0.3550
vt 0.4423 0.6339
vt 0.4066 0.8663
vt 0.4266 0.6339
vt 0.4603 0.4613
vt 0.4494 0.4613
vt 0.4798 0.3550
vt 0.4742 0.3550
vt 0.4798 0.5269
vt 0.4266 0.8663
vt 0.3988 1.0000
vt 0.4494 0.8663
vt 0.4205 1.0000
vt 0.4603 0.6339
vt 0.4861 0.3550
vt 0.4861 0.5303
vt 0.4798 0.6339
vt 0.4861 0.4613
vt 0.4726 0.4613
vt 0.4929 0.3550
vt 0.4929 0.5324
vt 0.4742 0.8663
vt 0.4452 1.0000
vt 0.4721 1.0000
vt 0.0000 1.0000
vt 1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt 1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt -1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 1.0000
vt -1.0000 0.0000
vt 0.0000 0.0000
vt 0.0000 -1.0000
vt -1.0000 0.0000
vt -0.5279 -0.3631
vt -0.5000 -0.3603
vt -0.5000 0.3535
vt -0.5279 0.3563
vt -1.0000 0.0000
vt 0.5934 0.8663
vt 0.3954 1.0000
vt 0.4461 0.4613
vt 0.4494 0.4613
vt 0.3988 1.0000
vt 0.5978 1.0000
vt 0.5472 0.4613
vt 1.0000 1.0000
vt 1.0000 1.0000
vt -1.0000 1.0000
vt -1.0000 1.0000
vt 1.0000 -1.0000
vt -1.0000 -1.0000
vt -0.6431 -0.5034
vt -0.6403 -0.4755
vt -0.3569 -0.5034
vt 0.0000 -1.0000
vt 0.0000 0.0000
vt -0.3597 -0.4755
vt -0.6322 -0.4486
vt -0.6190 -0.4239
vt -0.3678 -0.4486
vt -0.3810 -0.4239
vt -0.6012 -0.4022
vt -0.5795 -0.3844
vt -0.3988 -0.4022
vt -0.4205 -0.3844
vt -0.5548 -0.3712
vt -0.4452 -0.3712
vt -0.4721 -0.3631
vt 0.0000 0.0000
vt -0.3569 0.4966
vt -0.3597 0.4687
vt -0.3678 0.4419
vt -0.6403 0.4687
vt -0.6431 0.4966
vt -0.6322 0.4419
vt -0.3810 0.4171
vt -0.3988 0.3954
vt -0.6190 0.4171
vt -0.6012 0.3954
vt -0.4205 0.3776
vt -0.4452 0.3644
vt -0.5795 0.3776
vt -0.5548 0.3644
vt -0.4721 0.3563
vn -0.7708 0.0759 0.6326
vn -0.6332 0.0624 0.7715
vn -0.4709 0.0464 0.8810
vn -0.2902 0.0286 0.9565
vn -0.0980 0.0097 0.9951
vn -0.0942 0.0286 0.9951
vn -0.7412 0.2248 0.6326
vn -0.6088 0.1847 0.7715
vn -0.4528 0.1374 0.8810
vn -0.2790 0.0846 0.9565
vn -0.6831 0.3651 0.6326
vn -0.5611 0.2999 0.7715
vn -0.4173 0.2230 0.8810
vn -0.2571 0.1374 0.9565
vn -0.0869 0.0464 0.9951
vn -0.0761 0.0625 0.9951
vn -0.5987 0.4913 0.6326
vn -0.4918 0.4036 0.7715
vn -0.3658 0.3002 0.8810
vn -0.2254 0.1850 0.9565
vn -0.4036 0.4918 0.7715
vn -0.3002 0.3658 0.8810
vn -0.1850 0.2254 0.9565
vn -0.0625 0.0761 0.9951
vn -0.4913 0.5987 0.6326
vn -0.3651 0.6831 0.6326
vn -0.2999 0.5611 0.7715
vn -0.2230 0.4173 0.8810
vn -0.1374 0.2571 0.9565
vn -0.0464 0.0869 0.9951
vn -0.1847 0.6088 0.7715
vn -0.1374 0.4528 0.8810
vn -0.0846 0.2790 0.9565
vn -0.0286 0.0942 0.9951
vn -0.2248 0.7412 0.6326
vn -0.0759 0.7708 0.6326
vn -0.0624 0.6332 0.7715
vn -0.0464 0.4709 0.8810
vn -0.0286 0.2902 0.9565
vn -0.0097 0.0980 0.9951
vn 0.0464 0.4709 0.8810
vn 0.0286 0.2902 0.9565
vn 0.0097 0.0980 0.9951
vn 0.0759 0.7708 0.6326
vn 0.0624 0.6332 0.7715
vn 0.2248 0.7412 0.6326
vn 0.1847 0.6088 0.7715
vn 0.1374 0.4528 0.8810
vn 0.0846 0.2790 0.9565
vn 0.0286 0.0942 0.9951
vn 0.1374 0.2571 0.9565
vn 0.0464 0.0869 0.9951
vn 0.3651 0.6831 0.6326
vn 0.2999 0.5611 0.7715
vn 0.2230 0.4173 0.8810
vn 0.4913 0.5987 0.6326
vn 0.4036 0.4918 0.7715
vn 0.3002 0.3658 0.8810
vn 0.1850 0.2254 0.9565
vn 0.0625 0.0761 0.9951
vn 0.2254 0.1850 0.9565
vn 0.0761 0.0625 0.9951
vn 0.5987 0.4913 0.6326
vn 0.4918 0.4036 0.7715
vn 0.3658 0.3002 0.8810
vn 0.6831 0.3651 0.6326
vn 0.5611 0.2999 0.7715
vn 0.4173 0.2230 0.8810
vn 0.2571 0.1374 0.9565
vn 0.0869 0.0464 0.9951
vn 0.0942 0.0286 0.9951
vn 0.7412 0.2248 0.6326
vn 0.6088 0.1847 0.7715
vn 0.4528 0.1374 0.8810
vn 0.2790 0.0846 0.9565
vn 0.7708 0.0759 0.6326
vn 0.6332 0.0624 0.7715
vn 0.4709 0.0464 0.8810
vn 0.2902 0.0286 0.9565
vn 0.0980 0.0097 0.9951
vn 0.0980 -0.0097 0.9951
vn 0.7708 -0.0759 0.6326
vn 0.6332 -0.0624 0.7715
vn 0.4709 -0.0464 0.8810
vn 0.2902 -0.0286 0.9565
vn 0.6088 -0.1847 0.7715
vn 0.4528 -0.1374 0.8810
vn 0.2790 -0.0846 0.9565
vn 0.0942 -0.0286 0.9951
vn 0.7412 -0.2248 0.6326
vn 0.6831 -0.3651 0.6326
vn 0.5611 -0.2999 0.7715
vn 0.4173 -0.2230 0.8810
vn 0.2571 -0.1374 0.9565
vn 0.0869 -0.0464 0.9951
vn 0.3658 -0.3002 0.8810
vn 0.2254 -0.1850 0.9565
vn 0.0761 -0.0625 0.9951
vn 0.5987 -0.4913 0.6326
vn 0.4918 -0.4036 0.7715
vn 0.4913 -0.5987 0.6326
vn 0.4036 -0.4918 0.7715
vn 0.3002 -0.3658 0.8810
vn 0.1850 -0.2254 0.9565
vn 0.0625 -0.0761 0.9951
vn 0.2230 -0.4173 0.8810
vn 0.1374 -0.2571 0.9565
vn 0.0464 -0.0869 0.9951
vn 0.3651 -0.6831 0.6326
vn 0.2999 -0.5611 0.7715
vn 0.2248 -0.7412 0.6326
vn 0.1847 -0.6088 0.7715
vn 0.1374 -0.4528 0.8810
vn 0.0846 -0.2790 0.9565
vn 0.0286 -0.0942 0.9951
vn 0.0286 -0.2902 0.9565
vn 0.0097 -0.0980 0.9951
vn 0.0759 -0.7708 0.6326
vn 0.0624 -0.6332 0.7715
vn 0.0464 -0.4709 0.8810
vn -0.0759 -0.7708 0.6326
vn -0.0624 -0.6332 0.7715
vn -0.0464 -0.4709 0.8810
vn -0.0286 -0.2902 0.9565
vn -0.0097 -0.0980 0.9951
vn -0.0846 -0.2790 0.9565
vn -0.0286 -0.0942 0.9951
vn -0.2248 -0.7412 0.6326
vn -0.1847 -0.6088 0.7715
vn -0.1374 -0.4528 0.8810
vn -0.3651 -0.6831 0.6326
vn -0.2999 -0.5611 0.7715
vn -0.2231 -0.4173 0.8810
vn -0.1374 -0.2571 0.9565
vn -0.0464 -0.0869 0.9951
vn -0.0625 -0.0761 0.9951
vn -0.4913 -0.5987 0.6326
vn -0.4036 -0.4918 0.7715
vn -0.3002 -0.3658 0.8810
vn -0.1850 -0.2254 0.9565
vn -0.4918 -0.4036 0.7715
vn -0.3658 -0.3002 0.8810
vn -0.2254 -0.1850 0.9565
vn -0.0761 -0.0625 0.9951
vn -0.5987 -0.4913 0.6326
vn -0.6831 -0.3651 0.6326
vn -0.5611 -0.2999 0.7715
vn -0.4173 -0.2231 0.8810
vn -0.2571 -0.1374 0.9565
vn -0.0869 -0.0464 0.9951
vn -0.6088 -0.1847 0.7715
vn -0.4528 -0.1374 0.8810
vn -0.2790 -0.0846 0.9565
vn -0.0942 -0.0286 0.9951
vn -0.7412 -0.2248 0.6326
vn -0.7708 -0.0759 0.6326
vn -0.6332 -0.0624 0.7715
vn -0.4709 -0.0464 0.8810
vn -0.2902 -0.0286 0.9565
vn -0.0980 -0.0097 0.9951
vn 0.0000 1.0000 0.0000
vn 1.0000 0.0000 0.0000
vn 0.0000 -1.0000 0.0000
vn -1.0000 0.0000 0.0000
vn 0.0000 0.0000 -1.0000
vn -0.0000 0.0000 1.0000
vn 0.2231 0.4173 0.8810
vn 0.4173 -0.2231 0.8810
vn -0.4173 -0.2230 0.8810
usemtl None
s off
f 1/1/1 160/2/1 126/3/1
f 2/4/2 126/3/2 127/5/2
f 3/6/3 127/5/3 128/7/3
f 4/8/4 128/7/4 129/9/4
f 21/10/5 4/11/5 129/12/5
f 21/10/6 8/13/6 4/11/6
f 5/14/7 145/15/7 1/1/7
f 2/4/8 5/14/8 1/1/8
f 7/16/9 2/4/9 3/6/9
f 8/17/10 3/6/10 4/8/10
f 9/18/11 142/19/11 5/14/11
f 10/20/12 5/14/12 6/21/12
f 11/22/13 6/21/13 7/16/13
f 12/23/14 7/16/14 8/17/14
f 21/10/15 12/24/15 8/13/15
f 21/10/16 16/25/16 12/24/16
f 9/18/17 140/26/17 141/27/17
f 14/28/18 9/18/18 10/20/18
f 15/29/19 10/20/19 11/22/19
f 16/30/20 11/22/20 12/23/20
f 14/31/21 17/32/21 13/33/21
f 19/34/22 14/31/22 15/35/22
f 20/36/23 15/35/23 16/37/23
f 21/10/24 20/38/24 16/25/24
f 17/32/25 140/39/25 13/33/25
f 17/32/26 161/40/26 167/41/26
f 18/42/27 22/43/27 17/32/27
f 19/34/28 23/44/28 18/42/28
f 20/36/29 24/45/29 19/34/29
f 21/10/30 25/46/30 20/38/30
f 23/44/31 26/47/31 22/43/31
f 28/48/32 23/44/32 24/45/32
f 25/49/33 28/48/33 24/45/33
f 21/10/34 29/50/34 25/46/34
f 26/47/35 161/40/35 22/43/35
f 26/47/36 138/51/36 163/52/36
f 27/53/37 30/54/37 26/47/37
f 28/48/38 31/55/38 27/53/38
f 29/56/39 32/57/39 28/48/39
f 21/10/40 33/58/40 29/50/40
f 36/59/41 31/55/41 32/57/41
f 37/60/42 32/57/42 33/61/42
f 21/10/43 37/62/43 33/58/43
f 34/63/44 138/51/44 30/54/44
f 31/55/45 34/63/45 30/54/45
f 38/64/46 139/65/46 34/63/46
f 35/66/47 38/64/47 34/63/47
f 36/59/48 39/67/48 35/66/48
f 37/60/49 40/68/49 36/59/49
f 21/10/50 41/69/50 37/62/50
f 41/70/51 44/71/51 40/68/51
f 21/10/52 45/72/52 41/69/52
f 42/73/53 152/74/53 38/64/53
f 43/75/54 38/64/54 39/67/54
f 44/71/55 39/67/55 40/68/55
f 46/76/56 150/77/56 42/73/56
f 43/75/57 46/76/57 42/73/57
f 44/71/58 47/78/58 43/75/58
f 49/79/59 44/71/59 45/80/59
f 21/10/60 49/81/60 45/72/60
f 53/82/61 48/83/61 49/84/61
f 21/10/62 53/85/62 49/81/62
f 50/86/63 149/87/63 46/88/63
f 47/89/64 50/86/64 46/88/64
f 48/83/65 51/90/65 47/89/65
f 54/91/66 151/92/66 50/86/66
f 51/90/67 54/91/67 50/86/67
f 56/93/68 51/90/68 52/94/68
f 53/82/69 56/93/69 52/94/69
f 21/10/70 57/95/70 53/85/70
f 21/10/71 61/96/71 57/95/71
f 54/91/72 164/97/72 157/98/72
f 59/99/73 54/91/73 55/100/73
f 60/101/74 55/100/74 56/93/74
f 61/102/75 56/93/75 57/103/75
f 62/104/76 164/97/76 58/105/76
f 63/106/77 58/105/77 59/99/77
f 64/107/78 59/99/78 60/101/78
f 61/102/79 64/107/79 60/101/79
f 21/10/80 65/108/80 61/96/80
f 21/10/81 69/109/81 65/108/81
f 66/110/82 159/111/82 62/104/82
f 67/112/83 62/104/83 63/106/83
f 68/113/84 63/106/84 64/107/84
f 69/114/85 64/107/85 65/115/85
f 71/116/86 66/110/86 67/112/86
f 72/117/87 67/112/87 68/113/87
f 69/114/88 72/117/88 68/113/88
f 21/10/89 73/118/89 69/109/89
f 70/119/90 158/120/90 66/110/90
f 74/121/91 169/122/91 70/119/91
f 71/116/92 74/121/92 70/119/92
f 76/123/93 71/116/93 72/117/93
f 73/124/94 76/123/94 72/117/94
f 21/10/95 77/125/95 73/118/95
f 76/123/96 79/126/96 75/127/96
f 81/128/97 76/123/97 77/129/97
f 21/10/98 81/130/98 77/125/98
f 78/131/99 153/132/99 74/121/99
f 79/126/100 74/121/100 75/127/100
f 82/133/101 144/134/101 78/135/101
f 83/136/102 78/135/102 79/137/102
f 84/138/103 79/137/103 80/139/103
f 81/140/104 84/138/104 80/139/104
f 21/10/105 85/141/105 81/130/105
f 84/138/106 87/142/106 83/136/106
f 89/143/107 84/138/107 85/144/107
f 21/10/108 89/145/108 85/141/108
f 86/146/109 154/147/109 82/133/109
f 87/142/110 82/133/110 83/136/110
f 90/148/111 155/149/111 86/146/111
f 91/150/112 86/146/112 87/142/112
f 92/151/113 87/142/113 88/152/113
f 93/153/114 88/152/114 89/143/114
f 21/10/115 93/154/115 89/145/115
f 97/155/116 92/151/116 93/153/116
f 21/10/117 97/156/117 93/154/117
f 94/157/118 165/158/118 90/148/118
f 95/159/119 90/148/119 91/150/119
f 92/151/120 95/159/120 91/150/120
f 98/160/121 166/161/121 94/157/121
f 99/162/122 94/157/122 95/159/122
f 96/163/123 99/162/123 95/159/123
f 101/164/124 96/163/124 97/155/124
f 21/10/125 101/165/125 97/156/125
f 105/166/126 100/167/126 101/164/126
f 21/10/127 105/168/127 101/165/127
f 102/169/128 162/170/128 98/160/128
f 103/171/129 98/160/129 99/162/129
f 104/172/130 99/162/130 100/167/130
f 106/173/131 168/174/131 102/169/131
f 103/171/132 106/173/132 102/169/132
f 108/175/133 103/171/133 104/172/133
f 109/176/134 104/172/134 105/166/134
f 21/10/135 109/177/135 105/168/135
f 21/10/136 113/178/136 109/177/136
f 110/179/137 148/180/137 106/173/137
f 111/181/138 106/173/138 107/182/138
f 108/175/139 111/181/139 107/182/139
f 113/183/140 108/175/140 109/176/140
f 115/184/141 110/185/141 111/186/141
f 116/187/142 111/186/142 112/188/142
f 117/189/143 112/188/143 113/190/143
f 21/10/144 117/191/144 113/178/144
f 114/192/145 143/193/145 110/185/145
f 118/194/146 156/195/146 114/192/146
f 119/196/147 114/192/147 115/184/147
f 116/187/148 119/196/148 115/184/148
f 121/197/149 116/187/149 117/189/149
f 21/10/150 121/198/150 117/191/150
f 123/199/151 118/194/151 119/196/151
f 124/200/152 119/196/152 120/201/152
f 125/202/153 120/201/153 121/197/153
f 21/10/154 125/203/154 121/198/154
f 122/204/155 147/205/155 118/194/155
f 126/3/156 146/206/156 122/204/156
f 127/5/157 122/204/157 123/199/157
f 128/7/158 123/199/158 124/200/158
f 129/9/159 124/200/159 125/202/159
f 21/10/160 129/12/160 125/203/160
f 131/207/161 132/208/161 130/209/161
f 133/210/162 136/211/162 132/212/162
f 137/213/163 134/214/163 136/215/163
f 135/216/164 130/217/164 134/218/164
f 136/211/165 130/219/165 132/212/165
f 133/220/166 146/221/166 160/222/166
f 159/223/166 158/224/166 131/225/166
f 1/1/1 145/15/1 160/2/1
f 2/4/2 1/1/2 126/3/2
f 3/6/3 2/4/3 127/5/3
f 4/8/4 3/6/4 128/7/4
f 5/14/7 142/19/7 145/15/7
f 2/4/8 6/21/8 5/14/8
f 7/16/9 6/21/9 2/4/9
f 8/17/10 7/16/10 3/6/10
f 9/18/11 141/27/11 142/19/11
f 10/20/12 9/18/12 5/14/12
f 11/22/13 10/20/13 6/21/13
f 12/23/14 11/22/14 7/16/14
f 9/18/17 13/226/17 140/26/17
f 14/28/18 13/226/18 9/18/18
f 15/29/19 14/28/19 10/20/19
f 16/30/20 15/29/20 11/22/20
f 14/31/21 18/42/21 17/32/21
f 19/34/22 18/42/22 14/31/22
f 20/36/23 19/34/23 15/35/23
f 17/32/25 167/41/25 140/39/25
f 17/32/26 22/43/26 161/40/26
f 18/42/27 23/44/27 22/43/27
f 19/34/28 24/45/28 23/44/28
f 20/36/29 25/49/29 24/45/29
f 23/44/31 27/53/31 26/47/31
f 28/48/32 27/53/32 23/44/32
f 25/49/33 29/56/33 28/48/33
f 26/47/35 163/52/35 161/40/35
f 26/47/36 30/54/36 138/51/36
f 27/53/37 31/55/37 30/54/37
f 28/48/38 32/57/38 31/55/38
f 29/56/39 33/61/39 32/57/39
f 36/59/41 35/66/41 31/55/41
f 37/60/42 36/59/42 32/57/42
f 34/63/44 139/65/44 138/51/44
f 31/55/45 35/66/45 34/63/45
f 38/64/46 152/74/46 139/65/46
f 35/66/47 39/67/47 38/64/47
f 36/59/48 40/68/48 39/67/48
f 37/60/49 41/70/49 40/68/49
f 41/70/51 45/80/51 44/71/51
f 42/73/53 150/77/53 152/74/53
f 43/75/54 42/73/54 38/64/54
f 44/71/167 43/75/167 39/67/167
f 46/76/56 149/227/56 150/77/56
f 43/75/57 47/78/57 46/76/57
f 44/71/58 48/228/58 47/78/58
f 49/79/59 48/228/59 44/71/59
f 53/82/61 52/94/61 48/83/61
f 50/86/63 151/92/63 149/87/63
f 47/89/64 51/90/64 50/86/64
f 48/83/65 52/94/65 51/90/65
f 54/91/66 157/98/66 151/92/66
f 51/90/67 55/100/67 54/91/67
f 56/93/68 55/100/68 51/90/68
f 53/82/69 57/103/69 56/93/69
f 54/91/72 58/105/72 164/97/72
f 59/99/73 58/105/73 54/91/73
f 60/101/74 59/99/74 55/100/74
f 61/102/75 60/101/75 56/93/75
f 62/104/76 159/111/76 164/97/76
f 63/106/77 62/104/77 58/105/77
f 64/107/78 63/106/78 59/99/78
f 61/102/79 65/115/79 64/107/79
f 66/110/82 158/120/82 159/111/82
f 67/112/83 66/110/83 62/104/83
f 68/113/84 67/112/84 63/106/84
f 69/114/85 68/113/85 64/107/85
f 71/116/86 70/119/86 66/110/86
f 72/117/87 71/116/87 67/112/87
f 69/114/88 73/124/88 72/117/88
f 70/119/90 169/122/90 158/120/90
f 74/121/91 153/132/91 169/122/91
f 71/116/92 75/127/92 74/121/92
f 76/123/168 75/127/168 71/116/168
f 73/124/94 77/129/94 76/123/94
f 76/123/96 80/229/96 79/126/96
f 81/128/97 80/229/97 76/123/97
f 78/131/99 144/230/99 153/132/99
f 79/126/100 78/131/100 74/121/100
f 82/133/101 154/147/101 144/134/101
f 83/136/102 82/133/102 78/135/102
f 84/138/103 83/136/103 79/137/103
f 81/140/104 85/144/104 84/138/104
f 84/138/106 88/152/106 87/142/106
f 89/143/107 88/152/107 84/138/107
f 86/146/109 155/149/109 154/147/109
f 87/142/110 86/146/110 82/133/110
f 90/148/111 165/158/111 155/149/111
f 91/150/112 90/148/112 86/146/112
f 92/151/113 91/150/113 87/142/113
f 93/153/114 92/151/114 88/152/114
f 97/155/116 96/163/116 92/151/116
f 94/157/118 166/161/118 165/158/118
f 95/159/119 94/157/119 90/148/119
f 92/151/120 96/163/120 95/159/120
f 98/160/121 162/170/121 166/161/121
f 99/162/122 98/160/122 94/157/122
f 96/163/123 100/167/123 99/162/123
f 101/164/124 100/167/124 96/163/124
f 105/166/126 104/172/126 100/167/126
f 102/169/128 168/174/128 162/170/128
f 103/171/129 102/169/129 98/160/129
f 104/172/130 103/171/130 99/162/130
f 106/173/131 148/180/131 168/174/131
f 103/171/132 107/182/132 106/173/132
f 108/175/133 107/182/133 103/171/133
f 109/176/134 108/175/134 104/172/134
f 110/179/137 143/231/137 148/180/137
f 111/181/138 110/179/138 106/173/138
f 108/175/139 112/232/139 111/181/139
f 113/183/140 112/232/140 108/175/140
f 115/184/141 114/192/141 110/185/141
f 116/187/142 115/184/142 111/186/142
f 117/189/143 116/187/143 112/188/143
f 114/192/145 156/195/145 143/193/145
f 118/194/146 147/205/146 156/195/146
f 119/196/147 118/194/147 114/192/147
f 116/187/169 120/201/169 119/196/169
f 121/197/149 120/201/149 116/187/149
f 123/199/151 122/204/151 118/194/151
f 124/200/152 123/199/152 119/196/152
f 125/202/153 124/200/153 120/201/153
f 122/204/155 146/206/155 147/205/155
f 126/3/156 160/2/156 146/206/156
f 127/5/157 126/3/157 122/204/157
f 128/7/158 127/5/158 123/199/158
f 129/9/159 128/7/159 124/200/159
f 131/207/161 133/233/161 132/208/161
f 133/210/162 137/234/162 136/211/162
f 137/213/163 135/235/163 134/214/163
f 135/216/164 131/236/164 130/217/164
f 136/211/165 134/237/165 130/219/165
f 133/220/166 131/238/166 166/239/166
f 133/220/166 166/239/166 162/240/166
f 138/241/166 135/242/166 137/243/166
f 163/244/166 138/241/166 137/243/166
f 133/220/166 162/240/166 168/245/166
f 133/220/166 168/245/166 148/246/166
f 161/247/166 163/244/166 137/243/166
f 167/248/166 161/247/166 137/243/166
f 133/220/166 148/246/166 143/249/166
f 133/220/166 143/249/166 156/250/166
f 140/251/166 167/248/166 137/243/166
f 141/252/166 140/251/166 137/243/166
f 137/243/166 133/220/166 160/222/166
f 133/220/166 156/250/166 147/253/166
f 142/254/166 141/252/166 137/243/166
f 145/255/166 142/254/166 137/243/166
f 133/220/166 147/253/166 146/221/166
f 160/222/166 145/255/166 137/243/166
f 135/256/166 138/257/166 139/258/166
f 135/256/166 139/258/166 152/259/166
f 165/260/166 166/261/166 131/225/166
f 155/262/166 165/260/166 131/225/166
f 135/256/166 152/259/166 150/263/166
f 135/256/166 150/263/166 149/264/166
f 154/265/166 155/262/166 131/225/166
f 144/266/166 154/265/166 131/225/166
f 135/256/166 149/264/166 151/267/166
f 135/256/166 151/267/166 157/268/166
f 153/269/166 144/266/166 131/225/166
f 169/270/166 153/269/166 131/225/166
f 131/225/166 135/256/166 159/223/166
f 135/256/166 157/268/166 164/271/166
f 158/224/166 169/270/166 131/225/166
f 135/256/166 164/271/166 159/223/166

View File

@ -0,0 +1,30 @@
<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="base_link">
<contact>
<rolling_friction value="0.001"/>
<spinning_friction value="0.001"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="concave_box.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cdf filename="concave_box.cdf" scale="1 1 1"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 1
newmtl Material.002
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.017444 0.640000 0.032216
Ks 0.034126 0.500000 0.031333
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,64 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib cube.mtl
o Cube.001_Cube.002
v -0.231854 0.040516 -0.056463
v -0.231854 0.040516 -0.121937
v -0.144556 0.040516 -0.121937
v -0.144556 0.040516 -0.056463
v -0.231854 0.127815 -0.056463
v -0.231854 0.127815 -0.121937
v -0.144556 0.127815 -0.121937
v -0.144556 0.127815 -0.056463
v -0.231854 0.040516 -0.056463
v -0.231854 0.040516 -0.121937
v -0.144556 0.040516 -0.121937
v -0.144556 0.040516 -0.056463
v -0.231854 0.127815 -0.056463
v -0.231854 0.127815 -0.121937
v -0.144556 0.127815 -0.121937
v -0.144556 0.127815 -0.056463
vt 1.044600 0.042083
vt 1.044600 -0.957917
vt 0.044600 -0.957917
vt 1.905897 0.042083
vt 1.905897 -0.957917
vt 0.905898 -0.957917
vt -0.955400 0.042083
vt -0.955400 -0.957917
vt -0.094102 0.042083
vt -0.094102 -0.957917
vt 0.905898 1.044600
vt 1.905897 1.044600
vt 1.905897 0.044600
vt -0.094102 1.044600
vt -0.094102 0.044600
vt 0.044600 0.042083
vt 0.905898 0.042083
vt 0.905898 0.044600
usemtl Material.002
s off
f 6/1 2/2 1/3
f 7/4 3/5 2/6
f 8/7 4/8 3/3
f 5/9 1/10 4/6
f 2/11 3/12 4/13
f 7/11 6/14 5/15
f 14/1 10/2 9/3
f 15/4 11/5 10/6
f 16/7 12/8 11/3
f 13/9 9/10 12/6
f 10/11 11/12 12/13
f 15/11 14/14 13/15
f 5/16 6/1 1/3
f 6/17 7/4 2/6
f 7/16 8/7 3/3
f 8/17 5/9 4/6
f 1/18 2/11 4/13
f 8/18 7/11 5/15
f 13/16 14/1 9/3
f 14/17 15/4 10/6
f 15/16 16/7 11/3
f 16/17 13/9 12/6
f 9/18 10/11 12/13
f 16/18 15/11 13/15

View File

@ -0,0 +1,11 @@
# Blender MTL File: 'shape_sort.blend'
# Material Count: 1
newmtl Material.001
Ns 96.078431
Ka 0.000000 0.000000 0.000000
Kd 0.013473 0.018536 0.640000
Ks 0.500000 0.500000 0.500000
Ni 1.000000
d 1.000000
illum 2

View File

@ -0,0 +1,282 @@
# Blender v2.71 (sub 0) OBJ File: 'shape_sort.blend'
# www.blender.org
mtllib cylinder.mtl
o Cylinder.001
v -0.291246 0.045696 0.165546
v -0.214241 0.045696 0.165546
v -0.291246 0.034429 0.166100
v -0.214241 0.034429 0.166100
v -0.291246 0.023595 0.167744
v -0.214241 0.023595 0.167744
v -0.291246 0.013610 0.170412
v -0.214241 0.013610 0.170412
v -0.291246 0.004859 0.174003
v -0.214241 0.004858 0.174003
v -0.291246 -0.002324 0.178379
v -0.214241 -0.002324 0.178379
v -0.291246 -0.007661 0.183372
v -0.214241 -0.007661 0.183372
v -0.291246 -0.010947 0.188789
v -0.214241 -0.010947 0.188789
v -0.291246 -0.012057 0.194422
v -0.214241 -0.012057 0.194422
v -0.291246 -0.010947 0.200056
v -0.214241 -0.010947 0.200056
v -0.291246 -0.007661 0.205473
v -0.214241 -0.007661 0.205473
v -0.291246 -0.002324 0.210465
v -0.214241 -0.002324 0.210465
v -0.291246 0.004859 0.214841
v -0.214241 0.004858 0.214841
v -0.291246 0.013610 0.218432
v -0.214241 0.013610 0.218432
v -0.291246 0.023595 0.221101
v -0.214241 0.023595 0.221101
v -0.291246 0.034429 0.222744
v -0.214241 0.034429 0.222744
v -0.291246 0.045696 0.223299
v -0.214241 0.045696 0.223299
v -0.291246 0.056963 0.222744
v -0.214241 0.056963 0.222744
v -0.291246 0.067797 0.221101
v -0.214241 0.067797 0.221101
v -0.291246 0.077782 0.218432
v -0.214241 0.077782 0.218432
v -0.291246 0.086534 0.214841
v -0.214241 0.086534 0.214841
v -0.291246 0.093716 0.210465
v -0.214241 0.093716 0.210465
v -0.291246 0.099053 0.205473
v -0.214241 0.099053 0.205473
v -0.291246 0.102340 0.200056
v -0.214241 0.102340 0.200056
v -0.291246 0.103449 0.194422
v -0.214241 0.103449 0.194422
v -0.291246 0.102340 0.188789
v -0.214241 0.102340 0.188789
v -0.291246 0.099053 0.183371
v -0.214241 0.099053 0.183371
v -0.291246 0.093716 0.178379
v -0.214241 0.093716 0.178379
v -0.291246 0.086534 0.174003
v -0.214241 0.086534 0.174003
v -0.291246 0.077782 0.170412
v -0.214241 0.077782 0.170412
v -0.291246 0.067797 0.167744
v -0.214241 0.067797 0.167744
v -0.291246 0.056963 0.166100
v -0.214241 0.056963 0.166100
vt 0.306049 0.488177
vt 0.092448 0.519423
vt 0.067655 0.516411
vt 0.270128 0.485165
vt 0.049219 0.513369
vt 0.232794 0.482123
vt 0.034123 0.510414
vt 0.020864 0.507658
vt 0.163092 0.476412
vt 0.008587 0.505209
vt 0.133302 0.473963
vt 1.008587 0.505209
vt 0.996728 0.503160
vt 1.106812 0.471914
vt 0.984865 0.501590
vt 1.082707 0.470344
vt 0.972628 0.500559
vt 0.959652 0.500107
vt 1.036012 0.468861
vt 0.945535 0.500252
vt 1.008811 0.469006
vt 0.929810 0.500987
vt 0.972352 0.469741
vt 0.911918 0.502285
vt 0.913273 0.471038
vt 0.891203 0.504095
vt 0.866959 0.506348
vt 0.698338 0.475102
vt 0.838607 0.508958
vt 0.630535 0.477711
vt 0.806049 0.511823
vt 0.592448 0.480577
vt 0.770128 0.514835
vt 0.732794 0.517877
vt 0.549219 0.486631
vt 0.696491 0.520833
vt 0.534123 0.489586
vt 0.663092 0.523588
vt 0.520864 0.492342
vt 0.633302 0.526037
vt 0.508586 0.494791
vt 0.606812 0.528086
vt 0.496728 0.496840
vt 0.582707 0.529656
vt 0.559695 0.530687
vt 0.472628 0.499441
vt 0.536012 0.531139
vt 0.459652 0.499893
vt 0.508810 0.530994
vt 0.445535 0.499748
vt 0.472352 0.530259
vt 0.413273 0.528962
vt 0.411918 0.497715
vt 0.310810 0.527152
vt 0.391202 0.495905
vt 0.198337 0.524898
vt 1.020864 0.507658
vt 1.034123 0.510414
vt 0.130535 0.522289
vt 0.366959 0.493652
vt 1.391202 0.495905
vt 0.196491 0.479167
vt 1.133302 0.473963
vt 1.059695 0.469313
vt 0.810811 0.472848
vt 0.567655 0.483589
vt 0.484865 0.498410
vt 0.429810 0.499013
vt 1.092448 0.519423
vt 1.067655 0.516411
vt 1.198337 0.524898
vt 1.413273 0.528962
vt 1.310810 0.527152
vt 1.472352 0.530259
vt 1.130535 0.522289
vt 1.049219 0.513369
vt 0.338607 0.491042
vt 1.270128 0.485165
vt 1.306049 0.488177
vt 1.196491 0.479167
vt 1.232794 0.482123
vt 1.163092 0.476412
vt 1.366959 0.493652
vt 1.338607 0.491042
vt 1.429810 0.499013
vt 1.411918 0.497715
vt 1.445535 0.499748
vt 1.459652 0.499893
usemtl Material.001
s off
f 1/1 2/2 4/3
f 3/4 4/3 6/5
f 5/6 6/5 8/7
f 8/7 10/8 9/9
f 10/8 12/10 11/11
f 12/12 14/13 13/14
f 14/13 16/15 15/16
f 15/16 16/15 18/17
f 18/17 20/18 19/19
f 20/18 22/20 21/21
f 22/20 24/22 23/23
f 24/22 26/24 25/25
f 25/25 26/24 28/26
f 28/26 30/27 29/28
f 30/27 32/29 31/30
f 32/29 34/31 33/32
f 33/32 34/31 36/33
f 36/33 38/34 37/35
f 38/34 40/36 39/37
f 40/36 42/38 41/39
f 42/38 44/40 43/41
f 44/40 46/42 45/43
f 45/43 46/42 48/44
f 48/44 50/45 49/46
f 50/45 52/47 51/48
f 52/47 54/49 53/50
f 53/50 54/49 56/51
f 56/51 58/52 57/53
f 58/52 60/54 59/55
f 59/55 60/54 62/56
f 26/24 10/57 8/58
f 64/59 2/2 1/1
f 61/60 62/56 64/59
f 37/35 39/37 59/61
f 3/4 1/1 4/3
f 5/6 3/4 6/5
f 7/62 5/6 8/7
f 7/62 8/7 9/9
f 9/9 10/8 11/11
f 11/63 12/12 13/14
f 13/14 14/13 15/16
f 17/64 15/16 18/17
f 17/64 18/17 19/19
f 19/19 20/18 21/21
f 21/21 22/20 23/23
f 23/23 24/22 25/25
f 27/65 25/25 28/26
f 27/65 28/26 29/28
f 29/28 30/27 31/30
f 31/30 32/29 33/32
f 35/66 33/32 36/33
f 35/66 36/33 37/35
f 37/35 38/34 39/37
f 39/37 40/36 41/39
f 41/39 42/38 43/41
f 43/41 44/40 45/43
f 47/67 45/43 48/44
f 47/67 48/44 49/46
f 49/46 50/45 51/48
f 51/48 52/47 53/50
f 55/68 53/50 56/51
f 55/68 56/51 57/53
f 57/53 58/52 59/55
f 61/60 59/55 62/56
f 2/69 34/31 4/70
f 38/34 36/33 62/71
f 58/72 40/36 60/73
f 54/49 44/40 56/74
f 50/45 48/44 52/47
f 46/42 54/49 48/44
f 14/13 22/20 20/18
f 12/12 10/57 24/22
f 2/69 64/75 34/31
f 30/27 6/76 32/29
f 26/24 8/58 28/26
f 63/77 61/60 64/59
f 64/75 36/33 34/31
f 14/13 20/18 16/15
f 44/40 42/38 56/74
f 40/36 38/34 60/73
f 38/34 62/71 60/73
f 10/57 26/24 24/22
f 48/44 54/49 52/47
f 34/31 32/29 4/70
f 8/58 6/76 28/26
f 54/49 46/42 44/40
f 20/18 18/17 16/15
f 42/38 58/72 56/74
f 63/77 64/59 1/1
f 32/29 6/76 4/70
f 12/12 24/22 14/13
f 58/72 42/38 40/36
f 36/33 64/75 62/71
f 24/22 22/20 14/13
f 6/76 30/27 28/26
f 3/78 31/30 1/79
f 7/80 29/28 5/81
f 11/63 23/23 9/82
f 15/16 21/21 13/14
f 15/16 17/64 19/19
f 61/83 63/84 35/66
f 27/65 7/80 25/25
f 41/39 55/85 57/86
f 35/66 63/84 33/32
f 53/87 55/85 43/41
f 43/41 55/85 41/39
f 47/67 53/87 45/43
f 47/67 49/46 51/88
f 59/61 39/37 57/86
f 29/28 31/30 5/81
f 7/80 27/65 29/28
f 45/43 53/87 43/41
f 47/67 51/88 53/87
f 61/83 37/35 59/61
f 31/30 3/78 5/81
f 15/16 19/19 21/21
f 21/21 23/23 13/14
f 39/37 41/39 57/86
f 7/80 9/82 25/25
f 1/79 31/30 33/32
f 23/23 11/63 13/14
f 9/82 23/23 25/25
f 37/35 61/83 35/66
f 63/84 1/79 33/32

Some files were not shown because too many files have changed in this diff Show More