Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
@@ -291,8 +291,6 @@ IF (OPENGL_FOUND)
|
||||
MESSAGE(${OPENGL_LIBRARIES})
|
||||
ELSE (OPENGL_FOUND)
|
||||
MESSAGE("OPENGL NOT FOUND")
|
||||
SET(OPENGL_gl_LIBRARY opengl32)
|
||||
SET(OPENGL_glu_LIBRARY glu32)
|
||||
ENDIF (OPENGL_FOUND)
|
||||
|
||||
|
||||
@@ -472,6 +470,7 @@ list (APPEND BULLET_LIBRARIES BulletInverseDynamics)
|
||||
list (APPEND BULLET_LIBRARIES BulletCollision)
|
||||
list (APPEND BULLET_LIBRARIES BulletDynamics)
|
||||
list (APPEND BULLET_LIBRARIES BulletSoftBody)
|
||||
list (APPEND BULLET_LIBRARIES bullet_c_api)
|
||||
set (BULLET_USE_FILE ${BULLET_CONFIG_CMAKE_PATH}/UseBullet.cmake)
|
||||
configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/BulletConfig.cmake.in
|
||||
${CMAKE_CURRENT_BINARY_DIR}/BulletConfig.cmake
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
SUBDIRS( HelloWorld BasicDemo )
|
||||
IF(BUILD_BULLET3)
|
||||
SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint )
|
||||
SUBDIRS( ExampleBrowser RobotSimulator SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK ThirdPartyLibs/clsocket OpenGLWindow TwoJoint c_api)
|
||||
ENDIF()
|
||||
|
||||
IF(BUILD_PYBULLET)
|
||||
|
||||
@@ -9,9 +9,9 @@
|
||||
#include "../../CommonInterfaces/CommonFileIOInterface.h"
|
||||
#include "../ImportURDFDemo/UrdfFindMeshFile.h"
|
||||
#include <string>
|
||||
#include "../../Utils/b3ResourcePath.h"
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include "../../Utils/b3ResourcePath.h"
|
||||
#include "../ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "../ImportURDFDemo/UrdfParser.h"
|
||||
#include "../ImportURDFDemo/urdfStringSplit.h"
|
||||
@@ -1453,17 +1453,15 @@ bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger,
|
||||
}
|
||||
else
|
||||
{
|
||||
int maxPathLen = 1024;
|
||||
fu.extractPath(relativeFileName, m_data->m_pathPrefix, maxPathLen);
|
||||
//read file
|
||||
int fileId = m_data->m_fileIO->fileOpen(relativeFileName,"r");
|
||||
|
||||
std::fstream xml_file(relativeFileName, std::fstream::in);
|
||||
while (xml_file.good())
|
||||
char destBuffer[8192];
|
||||
while (m_data->m_fileIO->readLine(fileId, destBuffer, 8192))
|
||||
{
|
||||
std::string line;
|
||||
std::getline(xml_file, line);
|
||||
xml_string += (line + "\n");
|
||||
xml_string += (std::string(destBuffer) + "\n");
|
||||
}
|
||||
xml_file.close();
|
||||
m_data->m_fileIO->fileClose(fileId);
|
||||
|
||||
if (parseMJCFString(xml_string.c_str(), logger))
|
||||
{
|
||||
|
||||
@@ -72,18 +72,22 @@ void Reset(Tree& tree, Jacobian* m_ikJacobian)
|
||||
|
||||
// Update target positions
|
||||
|
||||
void UpdateTargets(double T2, Tree& treeY)
|
||||
void UpdateTargets(double T, Tree& treeY)
|
||||
{
|
||||
double T = T2 / 5.;
|
||||
targetaa[0].Set(0.6 * b3Sin(0), 0.6 * b3Cos(0), 0.5 + 0.4 * b3Sin(3 * T));
|
||||
targetaa[0].Set(2.0f + 1.5*sin(3 * T) * 2, -0.5 + 1.0f + 0.2*sin(7 * T) * 2, 0.3f + 0.7*sin(5 * T) * 2);
|
||||
targetaa[1].Set(0.5f + 0.4*sin(4 * T) * 2, -0.5 + 0.9f + 0.3*sin(4 * T) * 2, -0.2f + 1.0*sin(3 * T) * 2);
|
||||
targetaa[2].Set(-0.5f + 0.8*sin(6 * T) * 2, -0.5 + 1.1f + 0.2*sin(7 * T) * 2, 0.3f + 0.5*sin(8 * T) * 2);
|
||||
targetaa[3].Set(-1.6f + 0.8*sin(4 * T) * 2, -0.5 + 0.8f + 0.3*sin(4 * T) * 2, -0.2f + 0.3*sin(3 * T) * 2);
|
||||
|
||||
}
|
||||
|
||||
// Does a single update (on one kind of tree)
|
||||
// Does a single update (on one kind of m_ikTree)
|
||||
void DoUpdateStep(double Tstep, Tree& treeY, Jacobian* jacob, int ikMethod)
|
||||
{
|
||||
B3_PROFILE("IK_DoUpdateStep");
|
||||
if (SleepCounter == 0)
|
||||
{
|
||||
T += Tstep;
|
||||
T += Tstep*0.1;
|
||||
UpdateTargets(T, treeY);
|
||||
}
|
||||
|
||||
@@ -142,7 +146,7 @@ class InverseKinematicsExample : public CommonExampleInterface
|
||||
Jacobian* m_ikJacobian;
|
||||
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
int m_targetInstance;
|
||||
b3AlignedObjectArray<int> m_targetInstances;
|
||||
enum
|
||||
{
|
||||
numCubesX = 20,
|
||||
@@ -152,10 +156,9 @@ class InverseKinematicsExample : public CommonExampleInterface
|
||||
public:
|
||||
InverseKinematicsExample(CommonGraphicsApp* app, int option)
|
||||
: m_app(app),
|
||||
m_ikMethod(option),
|
||||
m_targetInstance(-1)
|
||||
m_ikMethod(option)
|
||||
{
|
||||
m_app->setUpAxis(2);
|
||||
m_app->setUpAxis(1);
|
||||
|
||||
{
|
||||
b3Vector3 extents = b3MakeVector3(100, 100, 100);
|
||||
@@ -166,7 +169,7 @@ public:
|
||||
|
||||
b3Vector4 color0 = b3MakeVector4(0.4, 0.4, 0.4, 1);
|
||||
b3Vector4 color1 = b3MakeVector4(0.6, 0.6, 0.6, 1);
|
||||
m_app->registerGrid(xres, yres, color0, color1);
|
||||
//m_app->registerGrid(xres, yres, color0, color1);
|
||||
}
|
||||
|
||||
///create some graphics proxy for the tracking target
|
||||
@@ -177,8 +180,11 @@ public:
|
||||
pos[app->getUpAxis()] = 1;
|
||||
b3Quaternion orn(0, 0, 0, 1);
|
||||
b3Vector4 color = b3MakeVector4(1., 0.3, 0.3, 1);
|
||||
b3Vector3 scaling = b3MakeVector3(.02, .02, .02);
|
||||
m_targetInstance = m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling);
|
||||
b3Vector3 scaling = b3MakeVector3(.1, .1, .1);
|
||||
m_targetInstances.push_back(m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling));
|
||||
m_targetInstances.push_back(m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling));
|
||||
m_targetInstances.push_back(m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling));
|
||||
m_targetInstances.push_back(m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling));
|
||||
}
|
||||
m_app->m_renderer->writeTransforms();
|
||||
}
|
||||
@@ -215,17 +221,17 @@ public:
|
||||
act.setRotation(rot);
|
||||
act.setOrigin(b3MakeVector3(node->r.x, node->r.y, node->r.z));
|
||||
}
|
||||
void MyDrawTree(Node* node, const b3Transform& tr)
|
||||
void MyDrawTree(Node* node, const b3Transform& tr, const b3Transform& parentTr)
|
||||
{
|
||||
b3Vector3 lineColor = b3MakeVector3(0, 0, 0);
|
||||
|
||||
int lineWidth = 2;
|
||||
if (node != 0)
|
||||
{
|
||||
// glPushMatrix();
|
||||
b3Vector3 pos = b3MakeVector3(tr.getOrigin().x, tr.getOrigin().y, tr.getOrigin().z);
|
||||
b3Vector3 color = b3MakeVector3(0, 1, 0);
|
||||
b3Vector3 color1 = b3MakeVector3(0, 1, 0);
|
||||
int pointSize = 10;
|
||||
m_app->m_renderer->drawPoint(pos, color, pointSize);
|
||||
m_app->m_renderer->drawPoint(pos, color1, pointSize);
|
||||
|
||||
m_app->m_renderer->drawLine(pos, pos + 0.05 * tr.getBasis().getColumn(0), b3MakeVector3(1, 0, 0), lineWidth);
|
||||
m_app->m_renderer->drawLine(pos, pos + 0.05 * tr.getBasis().getColumn(1), b3MakeVector3(0, 1, 0), lineWidth);
|
||||
@@ -236,25 +242,29 @@ public:
|
||||
|
||||
m_app->m_renderer->drawLine(pos, pos + 0.1 * axisWorld, b3MakeVector3(.2, 0.2, 0.7), 5);
|
||||
|
||||
//node->DrawNode(node == root); // Recursively draw node and update ModelView matrix
|
||||
if (node->left)
|
||||
{
|
||||
b3Transform act;
|
||||
getLocalTransform(node->left, act);
|
||||
|
||||
b3Transform trl = tr * act;
|
||||
m_app->m_renderer->drawLine(tr.getOrigin(), trl.getOrigin(), lineColor, lineWidth);
|
||||
MyDrawTree(node->left, trl); // Draw tree of children recursively
|
||||
}
|
||||
// glPopMatrix();
|
||||
if (node->right)
|
||||
{
|
||||
b3Transform act;
|
||||
getLocalTransform(node->right, act);
|
||||
b3Transform trr = tr * act;
|
||||
m_app->m_renderer->drawLine(tr.getOrigin(), trr.getOrigin(), lineColor, lineWidth);
|
||||
MyDrawTree(node->right, trr); // Draw right siblings recursively
|
||||
b3Transform ptrr = parentTr * act;
|
||||
b3Vector3 lineColor = b3MakeVector3(0, 1, 0);
|
||||
m_app->m_renderer->drawLine(tr.getOrigin(), ptrr.getOrigin(), lineColor, lineWidth);
|
||||
MyDrawTree(node->right, ptrr, parentTr); // Draw right siblings recursively
|
||||
}
|
||||
|
||||
//node->DrawNode(node == root); // Recursively draw node and update ModelView matrix
|
||||
if (node->left)
|
||||
{
|
||||
b3Transform act;
|
||||
getLocalTransform(node->left, act);
|
||||
b3Vector3 lineColor = b3MakeVector3(1, 0, 0);
|
||||
b3Transform trl = tr * act;
|
||||
m_app->m_renderer->drawLine(tr.getOrigin(), trl.getOrigin(), lineColor, lineWidth);
|
||||
MyDrawTree(node->left, trl, tr); // Draw m_ikTree of children recursively
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
virtual void stepSimulation(float deltaTime)
|
||||
@@ -265,12 +275,15 @@ public:
|
||||
{
|
||||
b3Transform act;
|
||||
getLocalTransform(m_ikTree.GetRoot(), act);
|
||||
MyDrawTree(m_ikTree.GetRoot(), act);
|
||||
MyDrawTree(m_ikTree.GetRoot(), act, b3Transform::getIdentity());
|
||||
|
||||
b3Vector3 pos = b3MakeVector3(targetaa[0].x, targetaa[0].y, targetaa[0].z);
|
||||
for (int i = 0; i < m_targetInstances.size(); i++)
|
||||
{
|
||||
b3Vector3 pos = b3MakeVector3(targetaa[i].x, targetaa[i].y, targetaa[i].z);
|
||||
b3Quaternion orn(0, 0, 0, 1);
|
||||
|
||||
m_app->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, m_targetInstance);
|
||||
m_app->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, m_targetInstances[i]);
|
||||
}
|
||||
m_app->m_renderer->writeTransforms();
|
||||
m_app->m_renderer->renderScene();
|
||||
}
|
||||
@@ -309,40 +322,117 @@ public:
|
||||
|
||||
void InverseKinematicsExample::BuildKukaIIWAShape()
|
||||
{
|
||||
//const VectorR3& unitx = VectorR3::UnitX;
|
||||
m_ikNodes.resize(29);
|
||||
const VectorR3& unitx = VectorR3::UnitX;
|
||||
const VectorR3& unity = VectorR3::UnitY;
|
||||
const VectorR3& unitz = VectorR3::UnitZ;
|
||||
const VectorR3 unit1(sqrt(14.0) / 8.0, 1.0 / 8.0, 7.0 / 8.0);
|
||||
const VectorR3& zero = VectorR3::Zero;
|
||||
VectorR3 p0(0.0f, -1.5f, 0.0f);
|
||||
VectorR3 p1(0.0f, -1.0f, 0.0f);
|
||||
VectorR3 p2(0.0f, -0.5f, 0.0f);
|
||||
VectorR3 p3(0.5f*Root2Inv, -0.5 + 0.5*Root2Inv, 0.0f);
|
||||
VectorR3 p4(0.5f*Root2Inv + 0.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 0.5f*0.5, 0.0f);
|
||||
VectorR3 p5(0.5f*Root2Inv + 1.0f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.0f*0.5, 0.0f);
|
||||
VectorR3 p6(0.5f*Root2Inv + 1.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.5f*0.5, 0.0f);
|
||||
VectorR3 p7(0.5f*Root2Inv + 0.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 0.5f*HalfRoot3, 0.0f);
|
||||
VectorR3 p8(0.5f*Root2Inv + 1.0f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.0f*HalfRoot3, 0.0f);
|
||||
VectorR3 p9(0.5f*Root2Inv + 1.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.5f*HalfRoot3, 0.0f);
|
||||
VectorR3 p10(-0.5f*Root2Inv, -0.5 + 0.5*Root2Inv, 0.0f);
|
||||
VectorR3 p11(-0.5f*Root2Inv - 0.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 0.5f*HalfRoot3, 0.0f);
|
||||
VectorR3 p12(-0.5f*Root2Inv - 1.0f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.0f*HalfRoot3, 0.0f);
|
||||
VectorR3 p13(-0.5f*Root2Inv - 1.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.5f*HalfRoot3, 0.0f);
|
||||
VectorR3 p14(-0.5f*Root2Inv - 0.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 0.5f*0.5, 0.0f);
|
||||
VectorR3 p15(-0.5f*Root2Inv - 1.0f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.0f*0.5, 0.0f);
|
||||
VectorR3 p16(-0.5f*Root2Inv - 1.5f*HalfRoot3, -0.5 + 0.5*Root2Inv + 1.5f*0.5, 0.0f);
|
||||
|
||||
float minTheta = -4 * PI;
|
||||
float maxTheta = 4 * PI;
|
||||
|
||||
m_ikNodes.resize(8); //7DOF+additional endeffector
|
||||
|
||||
m_ikNodes[0] = new Node(VectorR3(0.100000, 0.000000, 0.087500), unitz, 0.08, JOINT, -1e30, 1e30, RADIAN(0.));
|
||||
m_ikNodes[0] = new Node(p0, unit1, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertRoot(m_ikNodes[0]);
|
||||
|
||||
m_ikNodes[1] = new Node(VectorR3(0.100000, -0.000000, 0.290000), unity, 0.08, JOINT, -0.5, 0.4, RADIAN(0.));
|
||||
m_ikNodes[1] = new Node(p1, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[0], m_ikNodes[1]);
|
||||
|
||||
m_ikNodes[2] = new Node(VectorR3(0.100000, -0.000000, 0.494500), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.));
|
||||
m_ikNodes[2] = new Node(p1, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[1], m_ikNodes[2]);
|
||||
|
||||
m_ikNodes[3] = new Node(VectorR3(0.100000, 0.000000, 0.710000), -unity, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.));
|
||||
m_ikNodes[3] = new Node(p2, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[2], m_ikNodes[3]);
|
||||
|
||||
m_ikNodes[4] = new Node(VectorR3(0.100000, 0.000000, 0.894500), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[3], m_ikNodes[4]);
|
||||
m_ikNodes[4] = new Node(p2, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertRightSibling(m_ikNodes[3], m_ikNodes[4]);
|
||||
|
||||
m_ikNodes[5] = new Node(VectorR3(0.100000, 0.000000, 1.110000), unity, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[4], m_ikNodes[5]);
|
||||
m_ikNodes[5] = new Node(p3, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[3], m_ikNodes[5]);
|
||||
|
||||
m_ikNodes[6] = new Node(VectorR3(0.100000, 0.000000, 1.191000), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[5], m_ikNodes[6]);
|
||||
m_ikNodes[6] = new Node(p3, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertRightSibling(m_ikNodes[5], m_ikNodes[6]);
|
||||
|
||||
m_ikNodes[7] = new Node(p3, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[5], m_ikNodes[7]);
|
||||
|
||||
m_ikNodes[8] = new Node(p4, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[7], m_ikNodes[8]);
|
||||
|
||||
m_ikNodes[9] = new Node(p5, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[8], m_ikNodes[9]);
|
||||
|
||||
m_ikNodes[10] = new Node(p5, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[9], m_ikNodes[10]);
|
||||
|
||||
m_ikNodes[11] = new Node(p6, zero, 0.08, EFFECTOR);
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[10], m_ikNodes[11]);
|
||||
|
||||
m_ikNodes[12] = new Node(p3, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[6], m_ikNodes[12]);
|
||||
|
||||
m_ikNodes[13] = new Node(p7, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[12], m_ikNodes[13]);
|
||||
|
||||
m_ikNodes[14] = new Node(p8, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[13], m_ikNodes[14]);
|
||||
|
||||
m_ikNodes[15] = new Node(p8, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[14], m_ikNodes[15]);
|
||||
|
||||
m_ikNodes[16] = new Node(p9, zero, 0.08, EFFECTOR);
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[15], m_ikNodes[16]);
|
||||
|
||||
m_ikNodes[17] = new Node(p10, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[4], m_ikNodes[17]);
|
||||
|
||||
m_ikNodes[18] = new Node(p10, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[17], m_ikNodes[18]);
|
||||
|
||||
m_ikNodes[19] = new Node(p10, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertRightSibling(m_ikNodes[17], m_ikNodes[19]);
|
||||
|
||||
m_ikNodes[20] = new Node(p11, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[18], m_ikNodes[20]);
|
||||
|
||||
m_ikNodes[21] = new Node(p12, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[20], m_ikNodes[21]);
|
||||
|
||||
m_ikNodes[22] = new Node(p12, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[21], m_ikNodes[22]);
|
||||
|
||||
m_ikNodes[23] = new Node(p13, zero, 0.08, EFFECTOR);
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[22], m_ikNodes[23]);
|
||||
|
||||
m_ikNodes[24] = new Node(p10, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[19], m_ikNodes[24]);
|
||||
|
||||
m_ikNodes[25] = new Node(p14, unitz, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[24], m_ikNodes[25]);
|
||||
|
||||
m_ikNodes[26] = new Node(p15, unitx, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[25], m_ikNodes[26]);
|
||||
|
||||
m_ikNodes[27] = new Node(p15, unity, 0.08, JOINT, RADIAN(-180.), RADIAN(180.), RADIAN(30.));
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[26], m_ikNodes[27]);
|
||||
|
||||
m_ikNodes[28] = new Node(p16, zero, 0.08, EFFECTOR);
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[27], m_ikNodes[28]);
|
||||
|
||||
m_ikNodes[7] = new Node(VectorR3(0.100000, 0.000000, 1.20000), zero, 0.08, EFFECTOR);
|
||||
m_ikTree.InsertLeftChild(m_ikNodes[6], m_ikNodes[7]);
|
||||
}
|
||||
|
||||
class CommonExampleInterface* InverseKinematicsExampleCreateFunc(struct CommonExampleOptions& options)
|
||||
|
||||
@@ -472,8 +472,8 @@ void Jacobian::CalcDeltaThetasSDLS()
|
||||
// Calculate response vector dTheta that is the SDLS solution.
|
||||
// Delta target values are the dS values
|
||||
int nRows = J.GetNumRows();
|
||||
// TODO: Modify it to work with multiple end effectors.
|
||||
int numEndEffectors = 1;
|
||||
|
||||
int numEndEffectors = m_tree->GetNumEffector();
|
||||
int nCols = J.GetNumColumns();
|
||||
dTheta.SetZero();
|
||||
|
||||
|
||||
210
examples/c_api/CMakeLists.txt
Normal file
210
examples/c_api/CMakeLists.txt
Normal file
@@ -0,0 +1,210 @@
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
|
||||
)
|
||||
|
||||
|
||||
SET(
|
||||
bullet_c_api_SRCS
|
||||
../../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/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
|
||||
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
|
||||
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
../../examples/TinyRenderer/model.cpp
|
||||
../../examples/TinyRenderer/tgaimage.cpp
|
||||
../../examples/TinyRenderer/our_gl.cpp
|
||||
../../examples/TinyRenderer/TinyRenderer.cpp
|
||||
../../examples/SharedMemory/InProcessMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsClient.cpp
|
||||
../../examples/SharedMemory/PhysicsClient.h
|
||||
../../examples/SharedMemory/PhysicsServer.cpp
|
||||
../../examples/SharedMemory/PhysicsServer.h
|
||||
../../examples/SharedMemory/PhysicsServerExample.cpp
|
||||
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
|
||||
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsServerSharedMemory.h
|
||||
../../examples/SharedMemory/PhysicsDirect.cpp
|
||||
../../examples/SharedMemory/PhysicsDirect.h
|
||||
../../examples/SharedMemory/PhysicsDirectC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsDirectC_API.h
|
||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
|
||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
|
||||
../../examples/SharedMemory/b3PluginManager.cpp
|
||||
../../examples/SharedMemory/b3PluginManager.h
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory.h
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
|
||||
../../examples/SharedMemory/PhysicsClientC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientC_API.h
|
||||
../../examples/SharedMemory/Win32SharedMemory.cpp
|
||||
../../examples/SharedMemory/Win32SharedMemory.h
|
||||
../../examples/SharedMemory/PosixSharedMemory.cpp
|
||||
../../examples/SharedMemory/PosixSharedMemory.h
|
||||
../../examples/Utils/b3ResourcePath.cpp
|
||||
../../examples/Utils/b3ResourcePath.h
|
||||
../../examples/Utils/RobotLoggingUtil.cpp
|
||||
../../examples/Utils/RobotLoggingUtil.h
|
||||
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
|
||||
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
|
||||
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
|
||||
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
|
||||
../../examples/ThirdPartyLibs/stb_image/stb_image_write.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(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
|
||||
IF(WIN32)
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(-DWIN32)
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
|
||||
ELSE(WIN32)
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(${OSDEF})
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
ENDIF(WIN32)
|
||||
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
SET(
|
||||
bullet_c_api_SRCS
|
||||
${bullet_c_api_SRCS}
|
||||
../../examples/SharedMemory/PhysicsClientUDP.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP.h
|
||||
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
|
||||
../../examples/ThirdPartyLibs/enet/win32.c
|
||||
../../examples/ThirdPartyLibs/enet/unix.c
|
||||
../../examples/ThirdPartyLibs/enet/callbacks.c
|
||||
../../examples/ThirdPartyLibs/enet/compress.c
|
||||
../../examples/ThirdPartyLibs/enet/host.c
|
||||
../../examples/ThirdPartyLibs/enet/list.c
|
||||
../../examples/ThirdPartyLibs/enet/packet.c
|
||||
../../examples/ThirdPartyLibs/enet/peer.c
|
||||
../../examples/ThirdPartyLibs/enet/protocol.c
|
||||
)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
SET(
|
||||
bullet_c_api_SRCS
|
||||
${bullet_c_api_SRCS}
|
||||
../../examples/SharedMemory/PhysicsClientTCP.cpp
|
||||
../../examples/SharedMemory/PhysicsClientTCP.h
|
||||
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
|
||||
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
|
||||
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
|
||||
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
|
||||
)
|
||||
ENDIF()
|
||||
|
||||
ADD_LIBRARY(bullet_c_api SHARED ${bullet_c_api_SRCS})
|
||||
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES PREFIX "")
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES POSTFIX "")
|
||||
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES VERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES SOVERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES DEBUG_POSTFIX "_d")
|
||||
|
||||
IF(WIN32)
|
||||
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
|
||||
TARGET_LINK_LIBRARIES(bullet_c_api ws2_32)
|
||||
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
TARGET_LINK_LIBRARIES(
|
||||
bullet_c_api
|
||||
BulletExampleBrowserLib
|
||||
BulletFileLoader
|
||||
BulletWorldImporter
|
||||
BulletSoftBody
|
||||
BulletDynamics
|
||||
BulletCollision
|
||||
BulletInverseDynamicsUtils
|
||||
BulletInverseDynamics
|
||||
LinearMath
|
||||
OpenGLWindow
|
||||
gwen
|
||||
BussIK
|
||||
Bullet3Common
|
||||
)
|
||||
|
||||
TARGET_LINK_LIBRARIES(bullet_c_api ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY})
|
||||
|
||||
IF (INSTALL_LIBS)
|
||||
IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
|
||||
#INSTALL of other files requires CMake 2.6
|
||||
IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
|
||||
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
|
||||
INSTALL(TARGETS bullet_c_api DESTINATION lib)
|
||||
ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
|
||||
INSTALL(TARGETS bullet_c_api RUNTIME DESTINATION bin
|
||||
LIBRARY DESTINATION lib${LIB_SUFFIX}
|
||||
ARCHIVE DESTINATION lib${LIB_SUFFIX})
|
||||
|
||||
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
|
||||
ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
|
||||
|
||||
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES FRAMEWORK true)
|
||||
|
||||
SET_TARGET_PROPERTIES(bullet_c_api PROPERTIES PUBLIC_HEADER "${Root_HDRS}")
|
||||
# Have to list out sub-directories manually:
|
||||
|
||||
|
||||
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
|
||||
ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
|
||||
ENDIF (INSTALL_LIBS)
|
||||
@@ -1,4 +1,3 @@
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples
|
||||
@@ -6,160 +5,17 @@ INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
|
||||
${PYTHON_INCLUDE_DIRS}
|
||||
)
|
||||
)
|
||||
IF(BUILD_PYBULLET_NUMPY)
|
||||
INCLUDE_DIRECTORIES(
|
||||
${PYTHON_NUMPY_INCLUDE_DIR}
|
||||
)
|
||||
INCLUDE_DIRECTORIES(${PYTHON_NUMPY_INCLUDE_DIR})
|
||||
ENDIF()
|
||||
|
||||
ADD_DEFINITIONS(-DSTATIC_LINK_SPD_PLUGIN)
|
||||
|
||||
SET(pybullet_SRCS
|
||||
SET(
|
||||
pybullet_SRCS
|
||||
pybullet.c
|
||||
../../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/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.h
|
||||
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
|
||||
../../examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.cpp
|
||||
../../examples/SharedMemory/IKTrajectoryHelper.h
|
||||
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.h
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
|
||||
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.h
|
||||
../../examples/OpenGLWindow/SimpleCamera.cpp
|
||||
../../examples/OpenGLWindow/SimpleCamera.h
|
||||
../../examples/TinyRenderer/geometry.cpp
|
||||
../../examples/TinyRenderer/model.cpp
|
||||
../../examples/TinyRenderer/tgaimage.cpp
|
||||
../../examples/TinyRenderer/our_gl.cpp
|
||||
../../examples/TinyRenderer/TinyRenderer.cpp
|
||||
../../examples/SharedMemory/InProcessMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsClient.cpp
|
||||
../../examples/SharedMemory/PhysicsClient.h
|
||||
../../examples/SharedMemory/PhysicsServer.cpp
|
||||
../../examples/SharedMemory/PhysicsServer.h
|
||||
../../examples/SharedMemory/PhysicsServerExample.cpp
|
||||
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
|
||||
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsServerSharedMemory.h
|
||||
../../examples/SharedMemory/PhysicsDirect.cpp
|
||||
../../examples/SharedMemory/PhysicsDirect.h
|
||||
../../examples/SharedMemory/PhysicsDirectC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsDirectC_API.h
|
||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
|
||||
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
|
||||
../../examples/SharedMemory/b3PluginManager.cpp
|
||||
../../examples/SharedMemory/b3PluginManager.h
|
||||
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory.h
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
|
||||
|
||||
../../examples/SharedMemory/PhysicsClientC_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientC_API.h
|
||||
../../examples/SharedMemory/Win32SharedMemory.cpp
|
||||
../../examples/SharedMemory/Win32SharedMemory.h
|
||||
../../examples/SharedMemory/PosixSharedMemory.cpp
|
||||
../../examples/SharedMemory/PosixSharedMemory.h
|
||||
../../examples/Utils/b3ResourcePath.cpp
|
||||
../../examples/Utils/b3ResourcePath.h
|
||||
../../examples/Utils/RobotLoggingUtil.cpp
|
||||
../../examples/Utils/RobotLoggingUtil.h
|
||||
|
||||
../../examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp
|
||||
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
|
||||
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
|
||||
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
|
||||
../../examples/ThirdPartyLibs/stb_image/stb_image_write.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(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
|
||||
IF(WIN32)
|
||||
LINK_LIBRARIES(
|
||||
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
|
||||
)
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(-DWIN32)
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
|
||||
ELSE(WIN32)
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
ADD_DEFINITIONS(${OSDEF})
|
||||
ENDIF(BUILD_PYBULLET_CLSOCKET)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
set(pybullet_SRCS ${pybullet_SRCS}
|
||||
../../examples/SharedMemory/PhysicsClientUDP.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP.h
|
||||
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
|
||||
../../examples/ThirdPartyLibs/enet/win32.c
|
||||
../../examples/ThirdPartyLibs/enet/unix.c
|
||||
../../examples/ThirdPartyLibs/enet/callbacks.c
|
||||
../../examples/ThirdPartyLibs/enet/compress.c
|
||||
../../examples/ThirdPartyLibs/enet/host.c
|
||||
../../examples/ThirdPartyLibs/enet/list.c
|
||||
../../examples/ThirdPartyLibs/enet/packet.c
|
||||
../../examples/ThirdPartyLibs/enet/peer.c
|
||||
../../examples/ThirdPartyLibs/enet/protocol.c
|
||||
)
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
|
||||
IF(BUILD_PYBULLET_CLSOCKET)
|
||||
set(pybullet_SRCS ${pybullet_SRCS}
|
||||
../../examples/SharedMemory/PhysicsClientTCP.cpp
|
||||
../../examples/SharedMemory/PhysicsClientTCP.h
|
||||
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
|
||||
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
|
||||
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
|
||||
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
|
||||
)
|
||||
ENDIF()
|
||||
|
||||
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
|
||||
|
||||
@@ -170,35 +26,41 @@ SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION})
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES DEBUG_POSTFIX "_d")
|
||||
|
||||
|
||||
IF(WIN32)
|
||||
IF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
|
||||
TARGET_LINK_LIBRARIES(pybullet ws2_32 )
|
||||
TARGET_LINK_LIBRARIES(pybullet ws2_32)
|
||||
ENDIF(BUILD_PYBULLET_ENET OR BUILD_PYBULLET_CLSOCKET)
|
||||
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd" )
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".pyd")
|
||||
ENDIF(WIN32)
|
||||
|
||||
IF (APPLE)
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".so" )
|
||||
IF(APPLE)
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES SUFFIX ".so")
|
||||
ENDIF()
|
||||
|
||||
TARGET_LINK_LIBRARIES(
|
||||
pybullet
|
||||
bullet_c_api
|
||||
)
|
||||
|
||||
|
||||
TARGET_LINK_LIBRARIES(pybullet BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common)
|
||||
|
||||
IF (WIN32)
|
||||
IF(WIN32)
|
||||
TARGET_LINK_LIBRARIES(pybullet ${PYTHON_LIBRARIES})
|
||||
ELSEIF (APPLE)
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES LINK_FLAGS "-undefined dynamic_lookup")
|
||||
ENDIF ()
|
||||
ELSEIF(APPLE)
|
||||
SET_TARGET_PROPERTIES(
|
||||
pybullet
|
||||
PROPERTIES LINK_FLAGS "-undefined dynamic_lookup"
|
||||
)
|
||||
ENDIF()
|
||||
# else Linux: dont link
|
||||
|
||||
IF(WIN32)
|
||||
SET(PYTHON_SITE_PACKAGES Lib/site-packages CACHE PATH "Python install path")
|
||||
ELSE()
|
||||
SET(PYTHON_SITE_PACKAGES lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages CACHE PATH "Python install path")
|
||||
SET(
|
||||
PYTHON_SITE_PACKAGES
|
||||
lib/python${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}/site-packages
|
||||
CACHE PATH "Python install path"
|
||||
)
|
||||
ENDIF()
|
||||
|
||||
INSTALL(TARGETS pybullet DESTINATION ${PYTHON_SITE_PACKAGES})
|
||||
|
||||
|
||||
10259
examples/pybullet/gym/pybullet_data/mini_cheetah/meshes/mini_abad.obj
Normal file
10259
examples/pybullet/gym/pybullet_data/mini_cheetah/meshes/mini_abad.obj
Normal file
File diff suppressed because it is too large
Load Diff
37168
examples/pybullet/gym/pybullet_data/mini_cheetah/meshes/mini_body.obj
Normal file
37168
examples/pybullet/gym/pybullet_data/mini_cheetah/meshes/mini_body.obj
Normal file
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,480 @@
|
||||
<?xml version="1.0" ?>
|
||||
<robot name="mini_cheetah" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<link name="body">
|
||||
<inertial>
|
||||
<mass value="3.3"/>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<inertia ixx="0.011253" ixy="0" ixz="0" iyy="0.362030" iyz="0" izz="0.042673"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_body.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_body.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!--!!!!!!!!!!!! Front Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
|
||||
<joint name="torso_to_abduct_fr_j" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin rpy="0 0 0" xyz="0.19 -0.049 0.0"/>
|
||||
<parent link="body"/>
|
||||
<child link="abduct_fr"/>
|
||||
</joint>
|
||||
<link name="abduct_fr">
|
||||
<inertial>
|
||||
<mass value="0.54"/>
|
||||
<origin xyz="0.0 0.036 0."/>
|
||||
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
|
||||
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="3.141592 0.0 1.5708" xyz="-0.055 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="3.141592 0 1.5708" xyz="-0.055 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="abduct_fr_to_thigh_fr_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/>
|
||||
<parent link="abduct_fr"/>
|
||||
<child link="thigh_fr"/>
|
||||
</joint>
|
||||
<link name="thigh_fr">
|
||||
<inertial>
|
||||
<mass value="0.634"/>
|
||||
<origin xyz="0.0 0.016 -0.02"/>
|
||||
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
|
||||
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="thigh_fr_to_knee_fr_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
|
||||
<parent link="thigh_fr"/>
|
||||
<child link="shank_fr"/>
|
||||
</joint>
|
||||
<link name="shank_fr">
|
||||
<inertial>
|
||||
<mass value="0.064"/>
|
||||
<origin xyz="0.0 0.0 -0.209"/>
|
||||
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="toe_fr">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.15"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="toe_fr_joint" type="fixed">
|
||||
<parent link="shank_fr"/>
|
||||
<child link="toe_fr"/>
|
||||
<origin xyz="0 0 -0.18"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<!--!!!!!!!!!!!! Front Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
|
||||
<joint name="torso_to_abduct_fl_j" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin rpy="0 0 0" xyz="0.19 0.049 0.0"/>
|
||||
<parent link="body"/>
|
||||
<child link="abduct_fl"/>
|
||||
</joint>
|
||||
<link name="abduct_fl">
|
||||
<inertial>
|
||||
<mass value="0.54"/>
|
||||
<origin xyz="0.0 0.036 0."/>
|
||||
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
|
||||
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0. 0. -1.5708" xyz="-0.055 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 -1.5708" xyz="-0.055 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="abduct_fl_to_thigh_fl_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/>
|
||||
<parent link="abduct_fl"/>
|
||||
<child link="thigh_fl"/>
|
||||
</joint>
|
||||
<link name="thigh_fl">
|
||||
<inertial>
|
||||
<mass value="0.634"/>
|
||||
<origin xyz="0.0 0.016 -0.02"/>
|
||||
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
|
||||
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="thigh_fl_to_knee_fl_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
|
||||
<parent link="thigh_fl"/>
|
||||
<child link="shank_fl"/>
|
||||
</joint>
|
||||
<link name="shank_fl">
|
||||
<inertial>
|
||||
<mass value="0.064"/>
|
||||
<origin xyz="0.0 0.0 -0.209"/>
|
||||
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="toe_fl">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.15"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="toe_fl_joint" type="fixed">
|
||||
<parent link="shank_fl"/>
|
||||
<child link="toe_fl"/>
|
||||
<origin xyz="0 0 -0.18"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<!--!!!!!!!!!!!! Hind Right Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
|
||||
<joint name="torso_to_abduct_hr_j" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin rpy="0 0 0" xyz="-0.19 -0.049 0.0"/>
|
||||
<parent link="body"/>
|
||||
<child link="abduct_hr"/>
|
||||
</joint>
|
||||
<link name="abduct_hr">
|
||||
<inertial>
|
||||
<mass value="0.54"/>
|
||||
<origin xyz="0.0 0.036 0."/>
|
||||
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
|
||||
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 0.0 1.5708" xyz="0.055 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 1.5708" xyz="0.055 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="abduct_hr_to_thigh_hr_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.062 0.00"/>
|
||||
<parent link="abduct_hr"/>
|
||||
<child link="thigh_hr"/>
|
||||
</joint>
|
||||
<link name="thigh_hr">
|
||||
<inertial>
|
||||
<mass value="0.634"/>
|
||||
<origin xyz="0.0 0.016 -0.02"/>
|
||||
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
|
||||
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="thigh_hr_to_knee_hr_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
|
||||
<parent link="thigh_hr"/>
|
||||
<child link="shank_hr"/>
|
||||
</joint>
|
||||
<link name="shank_hr">
|
||||
<inertial>
|
||||
<mass value="0.064"/>
|
||||
<origin xyz="0.0 0.0 -0.209"/>
|
||||
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="toe_hr">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.15"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="toe_hr_joint" type="fixed">
|
||||
<parent link="shank_hr"/>
|
||||
<child link="toe_hr"/>
|
||||
<origin xyz="0 0 -0.18"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<!--!!!!!!!!!!!! Hind Left Leg !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!-->
|
||||
<joint name="torso_to_abduct_hl_j" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin rpy="0 0 0" xyz="-0.19 0.049 0.0"/>
|
||||
<parent link="body"/>
|
||||
<child link="abduct_hl"/>
|
||||
</joint>
|
||||
<link name="abduct_hl">
|
||||
<inertial>
|
||||
<mass value="0.54"/>
|
||||
<origin xyz="0.0 0.036 0."/>
|
||||
<inertia ixx="0.000381" ixy="0.000058" ixz="0.00000045"
|
||||
iyy="0.000560" iyz="0.00000095" izz="0.000444"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="3.141592 0.0 -1.5708" xyz="0.055 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_abad.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="3.141592 0 -1.5708" xyz="0.055 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="abduct_hl_to_thigh_hl_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0.0 0.0" xyz="0.0 0.062 0.00"/>
|
||||
<parent link="abduct_hl"/>
|
||||
<child link="thigh_hl"/>
|
||||
</joint>
|
||||
<link name="thigh_hl">
|
||||
<inertial>
|
||||
<mass value="0.634"/>
|
||||
<origin xyz="0.0 0.016 -0.02"/>
|
||||
<inertia ixx="0.001983" ixy="0.000245" ixz="0.000013"
|
||||
iyy="0.002103" iyz="0.0000015" izz="0.000408"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 -1.5708 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_upper_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 -1.5708 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="thigh_hl_to_knee_hl_j" type="continuous">
|
||||
<axis xyz="0 -1 0"/>
|
||||
<origin rpy="0.0 0 0.0" xyz="0.0 0.0 -0.209"/>
|
||||
<parent link="thigh_hl"/>
|
||||
<child link="shank_hl"/>
|
||||
</joint>
|
||||
<link name="shank_hl">
|
||||
<inertial>
|
||||
<mass value="0.064"/>
|
||||
<origin xyz="0.0 0.0 -0.209"/>
|
||||
<inertia ixx="0.000245" ixy="0" ixz="0.0" iyy="0.000248" iyz="0" izz="0.000006"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0.0 3.141592 0.0" xyz="0.0 0.0 0.0"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/mini_lower_link.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 3.141592 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="toe_hl">
|
||||
<contact>
|
||||
<friction_anchor/>
|
||||
<stiffness value="30000.0"/>
|
||||
<damping value="1000.0"/>
|
||||
<spinning_friction value="0.3"/>
|
||||
<lateral_friction value="3.0"/>
|
||||
</contact>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
<material name="darkgray"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.015"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<mass value="0.15"/>
|
||||
<inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="toe_hl_joint" type="fixed">
|
||||
<parent link="shank_hl"/>
|
||||
<child link="toe_hl"/>
|
||||
<origin xyz="0 0 -0.18"/>
|
||||
<dynamics damping="0.0" friction="0.0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
|
||||
</robot>
|
||||
Binary file not shown.
@@ -1,29 +0,0 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.13"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.019 -0.019 -0.1502"/>
|
||||
<geometry>
|
||||
<mesh filename="channel.stl" scale="1.0 1.0 1.0"/>
|
||||
</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="0.038 0.038 0.305"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
Binary file not shown.
@@ -1,29 +0,0 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.081"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.0125"/>
|
||||
<geometry>
|
||||
<mesh filename="d435i.stl" scale="1.0 1.0 1.0"/>
|
||||
</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="0.09 0.025 0.025"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
Binary file not shown.
@@ -1,29 +0,0 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.13"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.037 0.0045 0"/>
|
||||
<geometry>
|
||||
<mesh filename="plate.stl" scale="1.0 1.0 1.0"/>
|
||||
</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="0.074 0.009 0.138"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
@@ -1,22 +0,0 @@
|
||||
import pybullet as p
|
||||
cin = p.connect(p.SHARED_MEMORY)
|
||||
if (cin < 0):
|
||||
cin = p.connect(p.GUI)
|
||||
objects = [p.loadURDF("plane.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
|
||||
objects = [p.loadURDF("quadruped/microtaur/microtaur.urdf", 0.858173,-0.698485,0.227967,-0.002864,0.000163,0.951778,0.306776)]
|
||||
ob = objects[0]
|
||||
jointPositions=[ 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.568555, 0.000000, -2.177277, 1.570089, 0.000000, -2.184705, 1.570229, 0.000000, -2.182261, 1.570008, 0.000000, -2.184197, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, -1.569978, 0.000000, 2.184092, -1.569669, 0.000000, 2.186906, -1.570584, 0.000000, 2.181503, -1.568404, 0.000000, 2.178427 ]
|
||||
for jointIndex in range (p.getNumJoints(ob)):
|
||||
p.resetJointState(ob,jointIndex,jointPositions[jointIndex])
|
||||
|
||||
cid0 = p.createConstraint(1,35,1,32,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.100000],[0.000000,0.010000,0.100000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000])
|
||||
p.changeConstraint(cid0,maxForce=1000.000000)
|
||||
cid1 = p.createConstraint(1,7,1,10,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.100000],[0.000000,0.010000,0.100000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000])
|
||||
p.changeConstraint(cid1,maxForce=1000.000000)
|
||||
cid2 = p.createConstraint(1,41,1,38,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.100000],[0.000000,0.010000,0.100000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000])
|
||||
p.changeConstraint(cid2,maxForce=1000.000000)
|
||||
cid3 = p.createConstraint(1,13,1,16,p.JOINT_POINT2POINT,[0.000000,0.000000,0.000000],[0.000000,0.005000,0.100000],[0.000000,0.010000,0.100000],[0.000000,0.000000,0.000000,1.000000],[0.000000,0.000000,0.000000,1.000000])
|
||||
p.changeConstraint(cid3,maxForce=1000.000000)
|
||||
p.setGravity(0.000000,0.000000,-10.000000)
|
||||
p.stepSimulation()
|
||||
p.disconnect()
|
||||
Binary file not shown.
@@ -1,29 +0,0 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="xavier">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.64"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="-0.045 -0.045 -0.018"/>
|
||||
<geometry>
|
||||
<mesh filename="xavier.stl" scale="1.0 1.0 1.0"/>
|
||||
</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="0.092 0.105 0.045"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
Binary file not shown.
@@ -1,29 +0,0 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<lateral_friction value="0.3"/>
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="0.082"/>
|
||||
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0.011 0"/>
|
||||
<geometry>
|
||||
<mesh filename="xm430w210.stl" scale="1.0 1.0 1.0"/>
|
||||
</geometry>
|
||||
<material name="black">
|
||||
<color rgba=".3 .3 .3 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="0.024 0.047 0.034"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
@@ -1,467 +0,0 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
|
||||
import time
|
||||
import math
|
||||
|
||||
|
||||
def drawInertiaBox(parentUid, parentLinkIndex, color):
|
||||
return
|
||||
dyn = p.getDynamicsInfo(parentUid, parentLinkIndex)
|
||||
mass = dyn[0]
|
||||
frictionCoeff = dyn[1]
|
||||
inertia = dyn[2]
|
||||
if (mass > 0):
|
||||
Ixx = inertia[0]
|
||||
Iyy = inertia[1]
|
||||
Izz = inertia[2]
|
||||
boxScaleX = 0.5 * math.sqrt(6 * (Izz + Iyy - Ixx) / mass)
|
||||
boxScaleY = 0.5 * math.sqrt(6 * (Izz + Ixx - Iyy) / mass)
|
||||
boxScaleZ = 0.5 * math.sqrt(6 * (Ixx + Iyy - Izz) / mass)
|
||||
|
||||
halfExtents = [boxScaleX, boxScaleY, boxScaleZ]
|
||||
pts = [[halfExtents[0], halfExtents[1], halfExtents[2]],
|
||||
[-halfExtents[0], halfExtents[1], halfExtents[2]],
|
||||
[halfExtents[0], -halfExtents[1], halfExtents[2]],
|
||||
[-halfExtents[0], -halfExtents[1], halfExtents[2]],
|
||||
[halfExtents[0], halfExtents[1], -halfExtents[2]],
|
||||
[-halfExtents[0], halfExtents[1], -halfExtents[2]],
|
||||
[halfExtents[0], -halfExtents[1], -halfExtents[2]],
|
||||
[-halfExtents[0], -halfExtents[1], -halfExtents[2]]]
|
||||
|
||||
p.addUserDebugLine(pts[0],
|
||||
pts[1],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[1],
|
||||
pts[3],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[3],
|
||||
pts[2],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[2],
|
||||
pts[0],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
|
||||
p.addUserDebugLine(pts[0],
|
||||
pts[4],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[1],
|
||||
pts[5],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[2],
|
||||
pts[6],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[3],
|
||||
pts[7],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
|
||||
p.addUserDebugLine(pts[4 + 0],
|
||||
pts[4 + 1],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[4 + 1],
|
||||
pts[4 + 3],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[4 + 3],
|
||||
pts[4 + 2],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
p.addUserDebugLine(pts[4 + 2],
|
||||
pts[4 + 0],
|
||||
color,
|
||||
1,
|
||||
parentObjectUniqueId=parentUid,
|
||||
parentLinkIndex=parentLinkIndex)
|
||||
|
||||
|
||||
toeConstraint = True
|
||||
useMaximalCoordinates = False
|
||||
useRealTime = 1
|
||||
|
||||
#the fixedTimeStep and numSolverIterations are the most important parameters to trade-off quality versus performance
|
||||
fixedTimeStep = 1. / 100
|
||||
numSolverIterations = 50
|
||||
|
||||
if (useMaximalCoordinates):
|
||||
fixedTimeStep = 1. / 500
|
||||
numSolverIterations = 200
|
||||
|
||||
speed = 10
|
||||
amplitude = 0.8
|
||||
jump_amp = 0.5
|
||||
maxForce = 3.5
|
||||
kneeFrictionForce = 0
|
||||
kp = 1
|
||||
kd = .5
|
||||
maxKneeForce = 1000
|
||||
|
||||
physId = p.connect(p.SHARED_MEMORY)
|
||||
|
||||
if (physId < 0):
|
||||
p.connect(p.GUI)
|
||||
#p.resetSimulation()
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
angle = 0 # pick in range 0..0.2 radians
|
||||
orn = p.getQuaternionFromEuler([0, angle, 0])
|
||||
p.loadURDF("plane.urdf", [0, 0, 0], orn)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=numSolverIterations)
|
||||
p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT,
|
||||
"genericlogdata.bin",
|
||||
maxLogDof=16,
|
||||
logFlags=p.STATE_LOG_JOINT_TORQUES)
|
||||
p.setTimeOut(4000000)
|
||||
|
||||
p.setGravity(0, 0, 0)
|
||||
p.setTimeStep(fixedTimeStep)
|
||||
|
||||
orn = p.getQuaternionFromEuler([0, 0, 0.4])
|
||||
p.setRealTimeSimulation(0)
|
||||
quadruped = p.loadURDF("quadruped/microtaur/microtaur.urdf", [1, -1, .3],
|
||||
orn,
|
||||
useFixedBase=False,
|
||||
useMaximalCoordinates=useMaximalCoordinates,
|
||||
flags=p.URDF_USE_IMPLICIT_CYLINDER)
|
||||
nJoints = p.getNumJoints(quadruped)
|
||||
|
||||
jointNameToId = {}
|
||||
for i in range(nJoints):
|
||||
jointInfo = p.getJointInfo(quadruped, i)
|
||||
jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0]
|
||||
|
||||
motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint']
|
||||
motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint']
|
||||
knee_front_rightL_joint = jointNameToId['knee_front_rightL_joint']
|
||||
hip_front_rightR_joint = jointNameToId['hip_front_rightR_joint']
|
||||
knee_front_rightR_joint = jointNameToId['knee_front_rightR_joint']
|
||||
motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint']
|
||||
motor_front_leftR_joint = jointNameToId['motor_front_leftR_joint']
|
||||
hip_front_leftR_joint = jointNameToId['hip_front_leftR_joint']
|
||||
knee_front_leftR_joint = jointNameToId['knee_front_leftR_joint']
|
||||
motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint']
|
||||
motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint']
|
||||
knee_front_leftL_joint = jointNameToId['knee_front_leftL_joint']
|
||||
motor_back_rightR_joint = jointNameToId['motor_back_rightR_joint']
|
||||
knee_back_rightR_joint = jointNameToId['knee_back_rightR_joint']
|
||||
motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint']
|
||||
motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint']
|
||||
knee_back_rightL_joint = jointNameToId['knee_back_rightL_joint']
|
||||
motor_back_leftR_joint = jointNameToId['motor_back_leftR_joint']
|
||||
knee_back_leftR_joint = jointNameToId['knee_back_leftR_joint']
|
||||
motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint']
|
||||
motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint']
|
||||
knee_back_leftL_joint = jointNameToId['knee_back_leftL_joint']
|
||||
|
||||
#fixtorso = p.createConstraint(-1,-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,0])
|
||||
|
||||
motordir = [-1, -1, -1, -1, 1, 1, 1, 1]
|
||||
halfpi = 1.57079632679
|
||||
twopi = 4 * halfpi
|
||||
kneeangle = -2.1834
|
||||
|
||||
dyn = p.getDynamicsInfo(quadruped, -1)
|
||||
mass = dyn[0]
|
||||
friction = dyn[1]
|
||||
localInertiaDiagonal = dyn[2]
|
||||
|
||||
print("localInertiaDiagonal", localInertiaDiagonal)
|
||||
|
||||
#this is a no-op, just to show the API
|
||||
p.changeDynamics(quadruped, -1, localInertiaDiagonal=localInertiaDiagonal)
|
||||
|
||||
#for i in range (nJoints):
|
||||
# p.changeDynamics(quadruped,i,localInertiaDiagonal=[0.000001,0.000001,0.000001])
|
||||
|
||||
drawInertiaBox(quadruped, -1, [1, 0, 0])
|
||||
#drawInertiaBox(quadruped,motor_front_rightR_joint, [1,0,0])
|
||||
|
||||
for i in range(nJoints):
|
||||
drawInertiaBox(quadruped, i, [0, 1, 0])
|
||||
|
||||
if (useMaximalCoordinates):
|
||||
steps = 400
|
||||
for aa in range(steps):
|
||||
p.setJointMotorControl2(quadruped, motor_front_leftL_joint, p.POSITION_CONTROL,
|
||||
motordir[0] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_front_leftR_joint, p.POSITION_CONTROL,
|
||||
motordir[1] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_back_leftL_joint, p.POSITION_CONTROL,
|
||||
motordir[2] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_back_leftR_joint, p.POSITION_CONTROL,
|
||||
motordir[3] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_front_rightL_joint, p.POSITION_CONTROL,
|
||||
motordir[4] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_front_rightR_joint, p.POSITION_CONTROL,
|
||||
motordir[5] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_back_rightL_joint, p.POSITION_CONTROL,
|
||||
motordir[6] * halfpi * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, motor_back_rightR_joint, p.POSITION_CONTROL,
|
||||
motordir[7] * halfpi * float(aa) / steps)
|
||||
|
||||
p.setJointMotorControl2(quadruped, knee_front_leftL_joint, p.POSITION_CONTROL,
|
||||
motordir[0] * (kneeangle + twopi) * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_front_leftR_joint, p.POSITION_CONTROL,
|
||||
motordir[1] * kneeangle * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_back_leftL_joint, p.POSITION_CONTROL,
|
||||
motordir[2] * kneeangle * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_back_leftR_joint, p.POSITION_CONTROL,
|
||||
motordir[3] * (kneeangle + twopi) * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_front_rightL_joint, p.POSITION_CONTROL,
|
||||
motordir[4] * (kneeangle) * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_front_rightR_joint, p.POSITION_CONTROL,
|
||||
motordir[5] * (kneeangle + twopi) * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_back_rightL_joint, p.POSITION_CONTROL,
|
||||
motordir[6] * (kneeangle + twopi) * float(aa) / steps)
|
||||
p.setJointMotorControl2(quadruped, knee_back_rightR_joint, p.POSITION_CONTROL,
|
||||
motordir[7] * kneeangle * float(aa) / steps)
|
||||
|
||||
p.stepSimulation()
|
||||
#time.sleep(fixedTimeStep)
|
||||
else:
|
||||
|
||||
p.resetJointState(quadruped, motor_front_leftL_joint, motordir[0] * halfpi)
|
||||
p.resetJointState(quadruped, knee_front_leftL_joint, motordir[0] * kneeangle)
|
||||
p.resetJointState(quadruped, motor_front_leftR_joint, motordir[1] * halfpi)
|
||||
p.resetJointState(quadruped, knee_front_leftR_joint, motordir[1] * kneeangle)
|
||||
|
||||
p.resetJointState(quadruped, motor_back_leftL_joint, motordir[2] * halfpi)
|
||||
p.resetJointState(quadruped, knee_back_leftL_joint, motordir[2] * kneeangle)
|
||||
p.resetJointState(quadruped, motor_back_leftR_joint, motordir[3] * halfpi)
|
||||
p.resetJointState(quadruped, knee_back_leftR_joint, motordir[3] * kneeangle)
|
||||
|
||||
p.resetJointState(quadruped, motor_front_rightL_joint, motordir[4] * halfpi)
|
||||
p.resetJointState(quadruped, knee_front_rightL_joint, motordir[4] * kneeangle)
|
||||
p.resetJointState(quadruped, motor_front_rightR_joint, motordir[5] * halfpi)
|
||||
p.resetJointState(quadruped, knee_front_rightR_joint, motordir[5] * kneeangle)
|
||||
|
||||
p.resetJointState(quadruped, motor_back_rightL_joint, motordir[6] * halfpi)
|
||||
p.resetJointState(quadruped, knee_back_rightL_joint, motordir[6] * kneeangle)
|
||||
p.resetJointState(quadruped, motor_back_rightR_joint, motordir[7] * halfpi)
|
||||
p.resetJointState(quadruped, knee_back_rightR_joint, motordir[7] * kneeangle)
|
||||
|
||||
#p.getNumJoints(1)
|
||||
|
||||
if (toeConstraint):
|
||||
cid = p.createConstraint(quadruped, knee_front_leftR_joint, quadruped, knee_front_leftL_joint,
|
||||
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
|
||||
p.changeConstraint(cid, maxForce=maxKneeForce)
|
||||
cid = p.createConstraint(quadruped, knee_front_rightR_joint, quadruped, knee_front_rightL_joint,
|
||||
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
|
||||
p.changeConstraint(cid, maxForce=maxKneeForce)
|
||||
cid = p.createConstraint(quadruped, knee_back_leftR_joint, quadruped, knee_back_leftL_joint,
|
||||
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
|
||||
p.changeConstraint(cid, maxForce=maxKneeForce)
|
||||
cid = p.createConstraint(quadruped, knee_back_rightR_joint, quadruped, knee_back_rightL_joint,
|
||||
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1])
|
||||
p.changeConstraint(cid, maxForce=maxKneeForce)
|
||||
|
||||
if (1):
|
||||
p.setJointMotorControl(quadruped, knee_front_leftL_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_front_leftR_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_front_rightL_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_front_rightR_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_leftL_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_leftR_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_leftL_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_leftR_joint, p.VELOCITY_CONTROL, 0, kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_rightL_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
p.setJointMotorControl(quadruped, knee_back_rightR_joint, p.VELOCITY_CONTROL, 0,
|
||||
kneeFrictionForce)
|
||||
|
||||
p.setGravity(0, 0, -10)
|
||||
|
||||
legnumbering = [
|
||||
motor_front_leftL_joint, motor_front_leftR_joint, motor_back_leftL_joint,
|
||||
motor_back_leftR_joint, motor_front_rightL_joint, motor_front_rightR_joint,
|
||||
motor_back_rightL_joint, motor_back_rightR_joint
|
||||
]
|
||||
|
||||
for i in range(8):
|
||||
print(legnumbering[i])
|
||||
#use the Minitaur leg numbering
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[0],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[0] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[1],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[1] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[2],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[2] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[3],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[3] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[4],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[4] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[5],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[5] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[6],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[6] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[7],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[7] * 1.57,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
#stand still
|
||||
p.setRealTimeSimulation(useRealTime)
|
||||
|
||||
t = 0.0
|
||||
t_end = t + 5
|
||||
ref_time = time.time()
|
||||
while (t < t_end):
|
||||
p.setGravity(0, 0, -10)
|
||||
if (useRealTime):
|
||||
t = time.time() - ref_time
|
||||
else:
|
||||
t = t + fixedTimeStep
|
||||
if (useRealTime == 0):
|
||||
p.stepSimulation()
|
||||
time.sleep(fixedTimeStep)
|
||||
|
||||
print("quadruped Id = ")
|
||||
print(quadruped)
|
||||
p.saveWorld("quadru.py")
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR, "quadrupedLog.bin", [quadruped])
|
||||
|
||||
#jump
|
||||
t = 0.0
|
||||
t_end = t + 100
|
||||
i = 0
|
||||
ref_time = time.time()
|
||||
|
||||
while (1):
|
||||
if (useRealTime):
|
||||
t = time.time() - ref_time
|
||||
else:
|
||||
t = t + fixedTimeStep
|
||||
if (True):
|
||||
|
||||
target = math.sin(t * speed) * jump_amp + 1.57
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[0],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[0] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[1],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[1] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[2],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[2] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[3],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[3] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[4],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[4] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[5],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[5] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[6],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[6] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
p.setJointMotorControl2(bodyIndex=quadruped,
|
||||
jointIndex=legnumbering[7],
|
||||
controlMode=p.POSITION_CONTROL,
|
||||
targetPosition=motordir[7] * target,
|
||||
positionGain=kp,
|
||||
velocityGain=kd,
|
||||
force=maxForce)
|
||||
|
||||
if (useRealTime == 0):
|
||||
p.stepSimulation()
|
||||
time.sleep(fixedTimeStep)
|
||||
@@ -0,0 +1,23 @@
|
||||
import pybullet as p
|
||||
import pybullet_data as pd
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.setGravity(0,0,-9.8)
|
||||
p.setAdditionalSearchPath(pd.getDataPath())
|
||||
floor = p.loadURDF("plane.urdf")
|
||||
startPos = [0,0,0.5]
|
||||
robot = p.loadURDF("mini_cheetah/mini_cheetah.urdf",startPos)
|
||||
numJoints = p.getNumJoints(robot)
|
||||
p.changeVisualShape(robot,-1,rgbaColor=[1,1,1,1])
|
||||
for j in range (numJoints):
|
||||
p.changeVisualShape(robot,j,rgbaColor=[1,1,1,1])
|
||||
force=200
|
||||
pos=0
|
||||
p.setJointMotorControl2(robot,j,p.POSITION_CONTROL,pos,force=force)
|
||||
dt = 1./240.
|
||||
p.setTimeStep(dt)
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
time.sleep(dt)
|
||||
|
||||
@@ -80,6 +80,7 @@ static DBVT_INLINE void deletenode(btDbvt* pdbvt,
|
||||
static void recursedeletenode(btDbvt* pdbvt,
|
||||
btDbvtNode* node)
|
||||
{
|
||||
if (node == 0) return;
|
||||
if (!node->isleaf())
|
||||
{
|
||||
recursedeletenode(pdbvt, node->childs[0]);
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
/*
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
|
||||
|
||||
@@ -311,9 +311,9 @@ void btGeneric6DofSpring2Constraint::calculateAngleInfo()
|
||||
case RO_XYZ:
|
||||
{
|
||||
//Is this the "line of nodes" calculation choosing planes YZ (B coordinate system) and xy (A coordinate system)? (http://en.wikipedia.org/wiki/Euler_angles)
|
||||
//The two planes are non-homologous, so this is a Tait<EFBFBD>Bryan angle formalism and not a proper Euler
|
||||
//The two planes are non-homologous, so this is a Tait Bryan angle formalism and not a proper Euler
|
||||
//Extrinsic rotations are equal to the reversed order intrinsic rotations so the above xyz extrinsic rotations (axes are fixed) are the same as the zy'x" intrinsic rotations (axes are refreshed after each rotation)
|
||||
//that is why xy and YZ planes are chosen (this will describe a zy'x" intrinsic rotation) (see the figure on the left at http://en.wikipedia.org/wiki/Euler_angles under Tait<EFBFBD>Bryan angles)
|
||||
//that is why xy and YZ planes are chosen (this will describe a zy'x" intrinsic rotation) (see the figure on the left at http://en.wikipedia.org/wiki/Euler_angles under Tait Bryan angles)
|
||||
// x' = Nperp = N.cross(axis2)
|
||||
// y' = N = axis2.cross(axis0)
|
||||
// z' = z
|
||||
@@ -866,7 +866,7 @@ int btGeneric6DofSpring2Constraint::get_limit_motor_info2(
|
||||
// vel + f / m * (rotational ? -1 : 1)
|
||||
// so in theory this should be set here for m_constraintError
|
||||
// (with m_constraintError we set a desired velocity for the affected body(es))
|
||||
// however in practice any value is fine as long as it is greater then the "proper" velocity,
|
||||
// however in practice any value is fine as long as it is greater than the "proper" velocity,
|
||||
// because the m_lowerLimit and the m_upperLimit will determinate the strength of the final pulling force
|
||||
// so it is much simpler (and more robust) just to simply use inf (with the proper sign)
|
||||
// (Even with our best intent the "new" velocity is only an estimation. If we underestimate
|
||||
|
||||
@@ -294,7 +294,7 @@ protected:
|
||||
bool m_hasStaticBody;
|
||||
int m_flags;
|
||||
|
||||
btGeneric6DofSpring2Constraint& operator=(btGeneric6DofSpring2Constraint&)
|
||||
btGeneric6DofSpring2Constraint& operator=(const btGeneric6DofSpring2Constraint&)
|
||||
{
|
||||
btAssert(0);
|
||||
return *this;
|
||||
|
||||
@@ -352,9 +352,9 @@ void btMultiBody::finalizeMultiDof()
|
||||
updateLinksDofOffsets();
|
||||
}
|
||||
|
||||
int btMultiBody::getParent(int i) const
|
||||
int btMultiBody::getParent(int link_num) const
|
||||
{
|
||||
return m_links[i].m_parent;
|
||||
return m_links[link_num].m_parent;
|
||||
}
|
||||
|
||||
btScalar btMultiBody::getLinkMass(int i) const
|
||||
|
||||
@@ -65,7 +65,7 @@ public:
|
||||
virtual ~btMultiBody();
|
||||
|
||||
//note: fixed link collision with parent is always disabled
|
||||
void setupFixed(int linkIndex,
|
||||
void setupFixed(int i, //linkIndex
|
||||
btScalar mass,
|
||||
const btVector3 &inertia,
|
||||
int parent,
|
||||
@@ -83,7 +83,7 @@ public:
|
||||
const btVector3 &thisPivotToThisComOffset,
|
||||
bool disableParentCollision);
|
||||
|
||||
void setupRevolute(int linkIndex, // 0 to num_links-1
|
||||
void setupRevolute(int i, // 0 to num_links-1
|
||||
btScalar mass,
|
||||
const btVector3 &inertia,
|
||||
int parentIndex,
|
||||
@@ -93,7 +93,7 @@ public:
|
||||
const btVector3 &thisPivotToThisComOffset, // vector from joint axis to my COM, in MY frame
|
||||
bool disableParentCollision = false);
|
||||
|
||||
void setupSpherical(int linkIndex, // 0 to num_links-1
|
||||
void setupSpherical(int i, // linkIndex, 0 to num_links-1
|
||||
btScalar mass,
|
||||
const btVector3 &inertia,
|
||||
int parent,
|
||||
@@ -277,15 +277,15 @@ public:
|
||||
//
|
||||
// transform vectors in local frame of link i to world frame (or vice versa)
|
||||
//
|
||||
btVector3 localPosToWorld(int i, const btVector3 &vec) const;
|
||||
btVector3 localDirToWorld(int i, const btVector3 &vec) const;
|
||||
btVector3 worldPosToLocal(int i, const btVector3 &vec) const;
|
||||
btVector3 worldDirToLocal(int i, const btVector3 &vec) const;
|
||||
btVector3 localPosToWorld(int i, const btVector3 &local_pos) const;
|
||||
btVector3 localDirToWorld(int i, const btVector3 &local_dir) const;
|
||||
btVector3 worldPosToLocal(int i, const btVector3 &world_pos) const;
|
||||
btVector3 worldDirToLocal(int i, const btVector3 &world_dir) const;
|
||||
|
||||
//
|
||||
// transform a frame in local coordinate to a frame in world coordinate
|
||||
//
|
||||
btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &mat) const;
|
||||
btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &local_frame) const;
|
||||
|
||||
//
|
||||
// calculate kinetic energy and angular momentum
|
||||
@@ -576,11 +576,11 @@ public:
|
||||
{
|
||||
return m_internalNeedsJointFeedback;
|
||||
}
|
||||
void forwardKinematics(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
|
||||
void forwardKinematics(btAlignedObjectArray<btQuaternion>& world_to_local, btAlignedObjectArray<btVector3> & local_origin);
|
||||
|
||||
void compTreeLinkVelocities(btVector3 * omega, btVector3 * vel) const;
|
||||
|
||||
void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
|
||||
void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & world_to_local, btAlignedObjectArray<btVector3> & local_origin);
|
||||
|
||||
virtual int calculateSerializeBufferSize() const;
|
||||
|
||||
|
||||
@@ -20,7 +20,7 @@ subject to the following restrictions:
|
||||
#include "btMLCPSolverInterface.h"
|
||||
#include "btLemkeAlgorithm.h"
|
||||
|
||||
///The btLemkeSolver is based on "Fast Implementation of Lemke<EFBFBD>s Algorithm for Rigid Body Contact Simulation (John E. Lloyd) "
|
||||
///The btLemkeSolver is based on "Fast Implementation of Lemke’s Algorithm for Rigid Body Contact Simulation (John E. Lloyd) "
|
||||
///It is a slower but more accurate solver. Increase the m_maxLoops for better convergence, at the cost of more CPU time.
|
||||
///The original implementation of the btLemkeAlgorithm was done by Kilian Grundl from the MBSim team
|
||||
class btLemkeSolver : public btMLCPSolverInterface
|
||||
@@ -67,7 +67,7 @@ public:
|
||||
btMatrixXu A1;
|
||||
btMatrixXu B(n, n);
|
||||
{
|
||||
BT_PROFILE("inverse(slow)");
|
||||
//BT_PROFILE("inverse(slow)");
|
||||
A1.resize(A.rows(), A.cols());
|
||||
for (int row = 0; row < A.rows(); row++)
|
||||
{
|
||||
@@ -174,7 +174,7 @@ public:
|
||||
y1.resize(n, 1);
|
||||
btLemkeAlgorithm lemke(M, qq, m_debugLevel);
|
||||
{
|
||||
BT_PROFILE("lemke.solve");
|
||||
//BT_PROFILE("lemke.solve");
|
||||
lemke.setSystem(M, qq);
|
||||
z1 = lemke.solve(m_maxLoops);
|
||||
}
|
||||
|
||||
@@ -45,14 +45,14 @@ subject to the following restrictions:
|
||||
|
||||
int btGetNumHardwareThreads()
|
||||
{
|
||||
return btMin<int>(BT_MAX_THREAD_COUNT, std::thread::hardware_concurrency());
|
||||
return btMax(1u, btMin(BT_MAX_THREAD_COUNT, std::thread::hardware_concurrency()));
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
int btGetNumHardwareThreads()
|
||||
{
|
||||
return btMin<int>(BT_MAX_THREAD_COUNT, sysconf(_SC_NPROCESSORS_ONLN));
|
||||
return btMax(1, btMin<int>(BT_MAX_THREAD_COUNT, sysconf(_SC_NPROCESSORS_ONLN)));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@@ -284,7 +284,7 @@ struct btMatrixX
|
||||
}
|
||||
}
|
||||
|
||||
void printMatrix(const char* msg)
|
||||
void printMatrix(const char* msg) const
|
||||
{
|
||||
printf("%s ---------------------\n", msg);
|
||||
for (int i = 0; i < rows(); i++)
|
||||
|
||||
Reference in New Issue
Block a user