added LICENSE.txt and AUTHORS.txt file
add MultiBody Custom Creation example, to show how to import data from a URDF file and fill up your own data structures. add btMultiBody::setBaseWorldTransform method todo: fix cmake build, this patch is premake only
This commit is contained in:
39
AUTHORS.txt
Normal file
39
AUTHORS.txt
Normal file
@@ -0,0 +1,39 @@
|
|||||||
|
Bullet Physics is created by Erwin Coumans with contributions from the following authors / copyright holders:
|
||||||
|
|
||||||
|
AMD
|
||||||
|
Apple
|
||||||
|
Steve Baker
|
||||||
|
Gino van den Bergen
|
||||||
|
Nicola Candussi
|
||||||
|
Erin Catto
|
||||||
|
Lawrence Chai
|
||||||
|
Erwin Coumans
|
||||||
|
Christer Ericson
|
||||||
|
Disney Animation
|
||||||
|
Google
|
||||||
|
Dirk Gregorius
|
||||||
|
Marcus Hennix
|
||||||
|
MBSim Development Team
|
||||||
|
Takahiro Harada
|
||||||
|
Simon Hobbs
|
||||||
|
John Hsu
|
||||||
|
Ole Kniemeyer
|
||||||
|
Jay Lee
|
||||||
|
Francisco Leon
|
||||||
|
Vsevolod Klementjev
|
||||||
|
Phil Knight
|
||||||
|
John McCutchan
|
||||||
|
Steven Peters
|
||||||
|
Roman Ponomarev
|
||||||
|
Nathanael Presson
|
||||||
|
Gabor PUHR
|
||||||
|
Arthur Shek
|
||||||
|
Russel Smith
|
||||||
|
Sony
|
||||||
|
Jakub Stephien
|
||||||
|
Marten Svanfeldt
|
||||||
|
Pierre Terdiman
|
||||||
|
Steven Thompson
|
||||||
|
Tamas Umenhoffer
|
||||||
|
|
||||||
|
If your name is missing, please send an email to erwin.coumans@gmail.com or file an issue at http://github.com/bulletphysics/bullet3
|
||||||
15
LICENSE.txt
Normal file
15
LICENSE.txt
Normal file
@@ -0,0 +1,15 @@
|
|||||||
|
|
||||||
|
The files in this repository are licensed under the zlib license, except for the files under examples/ThirdPartyLibs.
|
||||||
|
|
||||||
|
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.
|
||||||
@@ -121,6 +121,7 @@
|
|||||||
|
|
||||||
include "../examples/HelloWorld"
|
include "../examples/HelloWorld"
|
||||||
include "../examples/BasicDemo"
|
include "../examples/BasicDemo"
|
||||||
|
include "../examples/MultiBody"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -53,7 +53,7 @@ static ExampleEntry gDefaultExamples[]=
|
|||||||
ExampleEntry(0,"MultiBody",0),
|
ExampleEntry(0,"MultiBody",0),
|
||||||
ExampleEntry(1,"TestJointTorque",TestJointTorqueCreateFunc),
|
ExampleEntry(1,"TestJointTorque",TestJointTorqueCreateFunc),
|
||||||
ExampleEntry(1,"MultiDofCreateFunc",MultiDofCreateFunc),
|
ExampleEntry(1,"MultiDofCreateFunc",MultiDofCreateFunc),
|
||||||
ExampleEntry(1,"Custom URDF",MultiBodyCustomURDFDofCreateFunc),
|
ExampleEntry(1,"Custom URDF",MultiBodyCustomURDFDemoCreateFunc),
|
||||||
|
|
||||||
|
|
||||||
#ifndef _DEBUG
|
#ifndef _DEBUG
|
||||||
|
|||||||
@@ -27,6 +27,10 @@
|
|||||||
"../Importers/**",
|
"../Importers/**",
|
||||||
"../Planar2D/Planar2D.*",
|
"../Planar2D/Planar2D.*",
|
||||||
"../RenderingExamples/*",
|
"../RenderingExamples/*",
|
||||||
|
"../Constraints/*",
|
||||||
|
"../MultiBody/MultiBodyCustomURDFDemo.cpp",
|
||||||
|
"../MultiBody/MultiDofDemo.cpp",
|
||||||
|
"../MultiBody/TestJointTorqueSetup.cpp",
|
||||||
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.*",
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.*",
|
||||||
"../ThirdPartyLibs/tinyxml/*",
|
"../ThirdPartyLibs/tinyxml/*",
|
||||||
"../Utils/b3Clock.*",
|
"../Utils/b3Clock.*",
|
||||||
|
|||||||
@@ -11,22 +11,14 @@
|
|||||||
#include "../CommonInterfaces/CommonParameterInterface.h"
|
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||||
#include "MyURDFImporter.h"
|
#include "MyURDFImporter.h"
|
||||||
|
|
||||||
static int bodyCollisionFilterGroup=btBroadphaseProxy::CharacterFilter;
|
|
||||||
static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphaseProxy::CharacterFilter);
|
|
||||||
static bool enableConstraints = true;//false;
|
|
||||||
#include "URDF2Bullet.h"
|
#include "URDF2Bullet.h"
|
||||||
|
|
||||||
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h"
|
|
||||||
|
|
||||||
#include "urdf_samples.h"
|
//#include "urdf_samples.h"
|
||||||
|
|
||||||
|
|
||||||
//#include "BulletCollision/CollisionShapes/btCylinderShape.h"
|
|
||||||
//#define USE_BARREL_VERTICES
|
|
||||||
//#include "OpenGLWindow/ShapeData.h"
|
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#include <fstream>
|
|
||||||
using namespace urdf;
|
|
||||||
|
|
||||||
|
|
||||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||||
@@ -148,32 +140,6 @@ void ImportUrdfSetup::setFileName(const char* urdfFileName)
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void printTree1(my_shared_ptr<const Link> link,int level = 0)
|
|
||||||
{
|
|
||||||
level+=2;
|
|
||||||
int count = 0;
|
|
||||||
for (std::vector<my_shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
|
|
||||||
{
|
|
||||||
if (*child)
|
|
||||||
{
|
|
||||||
for(int j=0;j<level;j++) std::cout << " "; //indent
|
|
||||||
std::cout << "child(" << (count++)+1 << "): " << (*child)->name << std::endl;
|
|
||||||
// first grandchild
|
|
||||||
printTree1(*child,level);
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
for(int j=0;j<level;j++) std::cout << " "; //indent
|
|
||||||
std::cout << "root link: " << link->name << " has a null child!" << *child << std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void ImportUrdfSetup::initPhysics()
|
void ImportUrdfSetup::initPhysics()
|
||||||
{
|
{
|
||||||
|
|
||||||
@@ -194,70 +160,20 @@ void ImportUrdfSetup::initPhysics()
|
|||||||
gravity[upAxis]=-9.8;
|
gravity[upAxis]=-9.8;
|
||||||
|
|
||||||
m_dynamicsWorld->setGravity(gravity);
|
m_dynamicsWorld->setGravity(gravity);
|
||||||
//int argc=0;
|
|
||||||
char relativeFileName[1024];
|
|
||||||
|
|
||||||
b3FileUtils fu;
|
|
||||||
printf("m_fileName=%s\n", m_fileName);
|
|
||||||
bool fileFound = fu.findFile(m_fileName, relativeFileName, 1024);
|
|
||||||
|
|
||||||
|
|
||||||
std::string xml_string;
|
|
||||||
char pathPrefix[1024];
|
|
||||||
pathPrefix[0] = 0;
|
|
||||||
|
|
||||||
if (!fileFound){
|
|
||||||
std::cerr << "URDF file not found, using a dummy test URDF" << std::endl;
|
|
||||||
xml_string = std::string(urdf_char);
|
|
||||||
|
|
||||||
} else
|
|
||||||
{
|
|
||||||
|
|
||||||
int maxPathLen = 1024;
|
|
||||||
fu.extractPath(relativeFileName,pathPrefix,maxPathLen);
|
|
||||||
|
|
||||||
|
|
||||||
std::fstream xml_file(relativeFileName, std::fstream::in);
|
|
||||||
while ( xml_file.good() )
|
|
||||||
{
|
|
||||||
std::string line;
|
|
||||||
std::getline( xml_file, line);
|
|
||||||
xml_string += (line + "\n");
|
|
||||||
}
|
|
||||||
xml_file.close();
|
|
||||||
}
|
|
||||||
|
|
||||||
my_shared_ptr<ModelInterface> robot = parseURDF(xml_string);
|
|
||||||
if (!robot){
|
|
||||||
std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
|
|
||||||
return ;
|
|
||||||
}
|
|
||||||
std::cout << "robot name is: " << robot->getName() << std::endl;
|
|
||||||
|
|
||||||
// get info from parser
|
|
||||||
std::cout << "---------- Successfully Parsed XML ---------------" << std::endl;
|
|
||||||
// get root link
|
|
||||||
my_shared_ptr<const Link> root_link=robot->getRoot();
|
|
||||||
if (!root_link) return ;
|
|
||||||
|
|
||||||
std::cout << "root Link: " << root_link->name << " has " << root_link->child_links.size() << " child(ren)" << std::endl;
|
|
||||||
|
|
||||||
// print entire tree
|
|
||||||
printTree1(root_link);
|
|
||||||
printf("now using new interface\n");
|
|
||||||
std::cout << "root Link: " << root_link->name << " has " << root_link->child_links.size() << " child(ren)" << std::endl;
|
|
||||||
|
|
||||||
//now print the tree using the new interface
|
//now print the tree using the new interface
|
||||||
MyURDFImporter u2b(robot,m_guiHelper);
|
MyURDFImporter u2b(m_guiHelper);
|
||||||
printTree(u2b, 0);
|
bool loadOk = u2b.loadURDF(m_fileName);
|
||||||
|
|
||||||
|
if (loadOk)
|
||||||
|
{
|
||||||
|
u2b.printTree();
|
||||||
|
|
||||||
btTransform identityTrans;
|
btTransform identityTrans;
|
||||||
identityTrans.setIdentity();
|
identityTrans.setIdentity();
|
||||||
|
|
||||||
int numJoints = (*robot).m_numJoints;
|
|
||||||
|
|
||||||
|
|
||||||
bool useUrdfInterfaceClass = true;
|
|
||||||
|
|
||||||
{
|
{
|
||||||
|
|
||||||
@@ -265,21 +181,17 @@ void ImportUrdfSetup::initPhysics()
|
|||||||
btMultiBody* mb = 0;
|
btMultiBody* mb = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||||
int rootLinkIndex = u2b.getRootLinkIndex();
|
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||||
printf("urdf root link index = %d\n",rootLinkIndex);
|
printf("urdf root link index = %d\n",rootLinkIndex);
|
||||||
MyMultiBodyCreator creation(m_guiHelper);
|
MyMultiBodyCreator creation(m_guiHelper);
|
||||||
|
|
||||||
ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,m_useMultiBody,pathPrefix);
|
ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,m_useMultiBody,u2b.getPathPrefix());
|
||||||
mb = creation.getBulletMultiBody();
|
mb = creation.getBulletMultiBody();
|
||||||
|
|
||||||
if (m_useMultiBody)
|
if (m_useMultiBody)
|
||||||
{
|
{
|
||||||
mb->setHasSelfCollision(false);
|
|
||||||
mb->finalizeMultiDof();
|
|
||||||
m_dynamicsWorld->addMultiBody(mb);
|
|
||||||
|
|
||||||
|
|
||||||
//create motors for each joint
|
//create motors for each joint
|
||||||
@@ -317,7 +229,7 @@ void ImportUrdfSetup::initPhysics()
|
|||||||
//the btMultiBody support is work-in-progress :-)
|
//the btMultiBody support is work-in-progress :-)
|
||||||
|
|
||||||
|
|
||||||
printf("numJoints/DOFS = %d\n", numJoints);
|
|
||||||
|
|
||||||
bool createGround=true;
|
bool createGround=true;
|
||||||
if (createGround)
|
if (createGround)
|
||||||
@@ -341,6 +253,7 @@ void ImportUrdfSetup::initPhysics()
|
|||||||
|
|
||||||
///this extra stepSimulation call makes sure that all the btMultibody transforms are properly propagates.
|
///this extra stepSimulation call makes sure that all the btMultibody transforms are properly propagates.
|
||||||
m_dynamicsWorld->stepSimulation(1. / 240., 0);// 1., 10, 1. / 240.);
|
m_dynamicsWorld->stepSimulation(1. / 240., 0);// 1., 10, 1. / 240.);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ImportUrdfSetup::stepSimulation(float deltaTime)
|
void ImportUrdfSetup::stepSimulation(float deltaTime)
|
||||||
|
|||||||
@@ -24,6 +24,7 @@ public:
|
|||||||
virtual class btMultiBodyLinkCollider* allocateMultiBodyLinkCollider(int urdfLinkIndex, int mbLinkIndex, btMultiBody* body) = 0;
|
virtual class btMultiBodyLinkCollider* allocateMultiBodyLinkCollider(int urdfLinkIndex, int mbLinkIndex, btMultiBody* body) = 0;
|
||||||
|
|
||||||
virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex) = 0;
|
virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex) = 0;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //MULTIBODY_CREATION_INTERFACE_H
|
#endif //MULTIBODY_CREATION_INTERFACE_H
|
||||||
@@ -69,3 +69,4 @@ btMultiBody* MyMultiBodyCreator::getBulletMultiBody()
|
|||||||
{
|
{
|
||||||
return m_bulletMultiBody;
|
return m_bulletMultiBody;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -43,6 +43,7 @@ public:
|
|||||||
virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex);
|
virtual void addLinkMapping(int urdfLinkIndex, int mbLinkIndex);
|
||||||
|
|
||||||
btMultiBody* getBulletMultiBody();
|
btMultiBody* getBulletMultiBody();
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //MY_MULTIBODY_CREATOR
|
#endif //MY_MULTIBODY_CREATOR
|
||||||
|
|||||||
@@ -1,3 +1,17 @@
|
|||||||
|
/* Copyright (C) 2015 Google
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
#include "MyURDFImporter.h"
|
#include "MyURDFImporter.h"
|
||||||
|
|
||||||
|
|
||||||
@@ -9,21 +23,58 @@
|
|||||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"//to create a tesselation of a generic btConvexShape
|
#include "BulletCollision/CollisionShapes/btShapeHull.h"//to create a tesselation of a generic btConvexShape
|
||||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
#include "Bullet3Common/b3FileUtils.h"
|
#include "Bullet3Common/b3FileUtils.h"
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h"
|
||||||
|
#include <iostream>
|
||||||
|
#include <fstream>
|
||||||
using namespace urdf;
|
using namespace urdf;
|
||||||
|
|
||||||
void convertURDFToVisualShape(const Visual* visual, const char* pathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut);
|
void convertURDFToVisualShape(const Visual* visual, const char* pathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut);
|
||||||
btCollisionShape* convertURDFToCollisionShape(const Collision* visual, const char* pathPrefix);
|
btCollisionShape* convertURDFToCollisionShape(const Collision* visual, const char* pathPrefix);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
static void printTreeInternal(my_shared_ptr<const Link> link,int level = 0)
|
||||||
|
{
|
||||||
|
level+=2;
|
||||||
|
int count = 0;
|
||||||
|
for (std::vector<my_shared_ptr<Link> >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++)
|
||||||
|
{
|
||||||
|
if (*child)
|
||||||
|
{
|
||||||
|
for(int j=0;j<level;j++) std::cout << " "; //indent
|
||||||
|
std::cout << "child(" << (count++)+1 << "): " << (*child)->name << std::endl;
|
||||||
|
// first grandchild
|
||||||
|
printTreeInternal(*child,level);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
for(int j=0;j<level;j++) std::cout << " "; //indent
|
||||||
|
std::cout << "root link: " << link->name << " has a null child!" << *child << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
struct MyURDFInternalData
|
struct MyURDFInternalData
|
||||||
{
|
{
|
||||||
my_shared_ptr<ModelInterface> m_robot;
|
my_shared_ptr<ModelInterface> m_robot;
|
||||||
std::vector<my_shared_ptr<Link> > m_links;
|
std::vector<my_shared_ptr<Link> > m_links;
|
||||||
struct GUIHelperInterface* m_guiHelper;
|
struct GUIHelperInterface* m_guiHelper;
|
||||||
|
const char* m_pathPrefix;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
void MyURDFImporter::printTree()
|
||||||
|
{
|
||||||
|
printTreeInternal(m_data->m_robot->getRoot(),0);
|
||||||
|
}
|
||||||
|
|
||||||
enum MyFileType
|
enum MyFileType
|
||||||
{
|
{
|
||||||
FILE_STL=1,
|
FILE_STL=1,
|
||||||
@@ -33,11 +84,72 @@ enum MyFileType
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
MyURDFImporter::MyURDFImporter(my_shared_ptr<ModelInterface> robot,struct GUIHelperInterface* helper)
|
MyURDFImporter::MyURDFImporter(struct GUIHelperInterface* helper)
|
||||||
{
|
{
|
||||||
m_data = new MyURDFInternalData;
|
m_data = new MyURDFInternalData;
|
||||||
m_data->m_robot = robot;
|
m_data->m_robot = 0;
|
||||||
m_data->m_guiHelper = helper;
|
m_data->m_guiHelper = helper;
|
||||||
|
m_data->m_pathPrefix=0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
bool MyURDFImporter::loadURDF(const char* fileName)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
//int argc=0;
|
||||||
|
char relativeFileName[1024];
|
||||||
|
|
||||||
|
b3FileUtils fu;
|
||||||
|
|
||||||
|
bool fileFound = fu.findFile(fileName, relativeFileName, 1024);
|
||||||
|
|
||||||
|
std::string xml_string;
|
||||||
|
char pathPrefix[1024];
|
||||||
|
pathPrefix[0] = 0;
|
||||||
|
|
||||||
|
if (!fileFound){
|
||||||
|
std::cerr << "URDF file not found" << std::endl;
|
||||||
|
return false;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
|
||||||
|
int maxPathLen = 1024;
|
||||||
|
fu.extractPath(relativeFileName,pathPrefix,maxPathLen);
|
||||||
|
|
||||||
|
|
||||||
|
std::fstream xml_file(relativeFileName, std::fstream::in);
|
||||||
|
while ( xml_file.good() )
|
||||||
|
{
|
||||||
|
std::string line;
|
||||||
|
std::getline( xml_file, line);
|
||||||
|
xml_string += (line + "\n");
|
||||||
|
}
|
||||||
|
xml_file.close();
|
||||||
|
}
|
||||||
|
|
||||||
|
my_shared_ptr<ModelInterface> robot = parseURDF(xml_string);
|
||||||
|
if (!robot){
|
||||||
|
std::cerr << "ERROR: Model Parsing the xml failed" << std::endl;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
std::cout << "robot name is: " << robot->getName() << std::endl;
|
||||||
|
|
||||||
|
// get info from parser
|
||||||
|
std::cout << "Successfully Parsed URDF" << std::endl;
|
||||||
|
// get root link
|
||||||
|
my_shared_ptr<const Link> root_link=robot->getRoot();
|
||||||
|
if (!root_link)
|
||||||
|
{
|
||||||
|
std::cout << "Failed to find root link in URDF" << std::endl;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
m_data->m_robot = robot;
|
||||||
|
|
||||||
m_data->m_robot->getLinks(m_data->m_links);
|
m_data->m_robot->getLinks(m_data->m_links);
|
||||||
|
|
||||||
//initialize the 'index' of each link
|
//initialize the 'index' of each link
|
||||||
@@ -46,8 +158,15 @@ MyURDFImporter::MyURDFImporter(my_shared_ptr<ModelInterface> robot,struct GUIHel
|
|||||||
m_data->m_links[i]->m_link_index = i;
|
m_data->m_links[i]->m_link_index = i;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const char* MyURDFImporter::getPathPrefix()
|
||||||
|
{
|
||||||
|
return m_data->m_pathPrefix;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
MyURDFImporter::~MyURDFImporter()
|
MyURDFImporter::~MyURDFImporter()
|
||||||
{
|
{
|
||||||
delete m_data;
|
delete m_data;
|
||||||
|
|||||||
@@ -2,9 +2,7 @@
|
|||||||
#define MY_URDF_IMPORTER_H
|
#define MY_URDF_IMPORTER_H
|
||||||
|
|
||||||
#include "URDFImporterInterface.h"
|
#include "URDFImporterInterface.h"
|
||||||
#include <vector> //temp, replace by btAlignedObjectArray
|
|
||||||
|
|
||||||
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h"
|
|
||||||
|
|
||||||
class MyURDFImporter : public URDFImporterInterface
|
class MyURDFImporter : public URDFImporterInterface
|
||||||
{
|
{
|
||||||
@@ -14,11 +12,16 @@ class MyURDFImporter : public URDFImporterInterface
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
MyURDFImporter(struct GUIHelperInterface* guiHelper);
|
||||||
MyURDFImporter(my_shared_ptr<urdf::ModelInterface> robot,struct GUIHelperInterface* helper);
|
|
||||||
|
|
||||||
virtual ~MyURDFImporter();
|
virtual ~MyURDFImporter();
|
||||||
|
|
||||||
|
virtual bool loadURDF(const char* fileName);
|
||||||
|
|
||||||
|
const char* getPathPrefix();
|
||||||
|
|
||||||
|
void printTree(); //for debugging
|
||||||
|
|
||||||
virtual int getRootLinkIndex() const;
|
virtual int getRootLinkIndex() const;
|
||||||
|
|
||||||
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
||||||
@@ -31,7 +34,7 @@ public:
|
|||||||
|
|
||||||
virtual bool getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit) const;
|
virtual bool getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit) const;
|
||||||
|
|
||||||
virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& inertialFrame) const;
|
virtual int convertLinkVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const;
|
||||||
|
|
||||||
virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const;
|
virtual class btCompoundShape* convertLinkCollisionShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame) const;
|
||||||
|
|
||||||
|
|||||||
@@ -290,10 +290,6 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat
|
|||||||
rot*offsetInB.getRotation(), offsetInA.getOrigin(),-offsetInB.getOrigin(),disableParentCollision);
|
rot*offsetInB.getRotation(), offsetInA.getOrigin(),-offsetInB.getOrigin(),disableParentCollision);
|
||||||
creation.addLinkMapping(urdfLinkIndex,mbLinkIndex);
|
creation.addLinkMapping(urdfLinkIndex,mbLinkIndex);
|
||||||
|
|
||||||
btMatrix3x3 rm(rot);
|
|
||||||
btScalar y,p,r;
|
|
||||||
rm.getEulerZYX(y,p,r);
|
|
||||||
printf("y=%f,p=%f,r=%f\n", y,p,r);
|
|
||||||
|
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
@@ -505,6 +501,16 @@ void ConvertURDF2Bullet(const URDFImporterInterface& u2b, MultiBodyCreationInter
|
|||||||
int urdfLinkIndex = u2b.getRootLinkIndex();
|
int urdfLinkIndex = u2b.getRootLinkIndex();
|
||||||
ConvertURDF2BulletInternal(u2b, creation, cache, urdfLinkIndex,rootTransformInWorldSpace,world1,createMultiBody,pathPrefix);
|
ConvertURDF2BulletInternal(u2b, creation, cache, urdfLinkIndex,rootTransformInWorldSpace,world1,createMultiBody,pathPrefix);
|
||||||
|
|
||||||
|
if (world1 && cache.m_bulletMultiBody)
|
||||||
|
{
|
||||||
|
btMultiBody* mb = cache.m_bulletMultiBody;
|
||||||
|
mb->setHasSelfCollision(false);
|
||||||
|
mb->finalizeMultiDof();
|
||||||
|
|
||||||
|
mb->setBaseWorldTransform(rootTransformInWorldSpace);
|
||||||
|
|
||||||
|
world1->addMultiBody(mb);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -16,7 +16,6 @@ class MultiBodyCreationInterface;
|
|||||||
void printTree(const URDFImporterInterface& u2b, int linkIndex, int identationLevel=0);
|
void printTree(const URDFImporterInterface& u2b, int linkIndex, int identationLevel=0);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
||||||
MultiBodyCreationInterface& creationCallback,
|
MultiBodyCreationInterface& creationCallback,
|
||||||
const btTransform& rootTransformInWorldSpace,
|
const btTransform& rootTransformInWorldSpace,
|
||||||
@@ -24,5 +23,6 @@ void ConvertURDF2Bullet(const URDFImporterInterface& u2b,
|
|||||||
bool createMultiBody,
|
bool createMultiBody,
|
||||||
const char* pathPrefix);
|
const char* pathPrefix);
|
||||||
|
|
||||||
|
|
||||||
#endif //_URDF2BULLET_H
|
#endif //_URDF2BULLET_H
|
||||||
|
|
||||||
|
|||||||
@@ -1,3 +1,17 @@
|
|||||||
|
/* Copyright (C) 2015 Google
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
#ifndef CUSTOM_MULTIBODY_CALLBACK_H
|
#ifndef CUSTOM_MULTIBODY_CALLBACK_H
|
||||||
#define CUSTOM_MULTIBODY_CALLBACK_H
|
#define CUSTOM_MULTIBODY_CALLBACK_H
|
||||||
|
|
||||||
|
|||||||
@@ -1,3 +1,15 @@
|
|||||||
|
/* Copyright (C) 2015 Google
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "MultiBodyCustomURDFDemo.h"
|
#include "MultiBodyCustomURDFDemo.h"
|
||||||
|
|
||||||
@@ -6,6 +18,9 @@
|
|||||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||||
|
|
||||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||||
|
#include "../Importers/ImportURDFDemo/MyURDFImporter.h"
|
||||||
|
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||||
|
|
||||||
#include "CustomMultiBodyCreationCallback.h"
|
#include "CustomMultiBodyCreationCallback.h"
|
||||||
|
|
||||||
|
|
||||||
@@ -34,31 +49,100 @@ MultiBodyCustomURDFDemo::~MultiBodyCustomURDFDemo()
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static void myPrintTree(const URDFImporterInterface& u2b, int linkIndex, int indentationLevel)
|
||||||
|
{
|
||||||
|
btAlignedObjectArray<int> childIndices;
|
||||||
|
u2b.getLinkChildIndices(linkIndex,childIndices);
|
||||||
|
|
||||||
|
int numChildren = childIndices.size();
|
||||||
|
|
||||||
|
indentationLevel+=2;
|
||||||
|
int count = 0;
|
||||||
|
for (int i=0;i<numChildren;i++)
|
||||||
|
{
|
||||||
|
int childLinkIndex = childIndices[i];
|
||||||
|
std::string name = u2b.getLinkName(childLinkIndex);
|
||||||
|
for(int j=0;j<indentationLevel;j++) printf(" "); //indent
|
||||||
|
printf("child(%d).name=%s with childIndex=%d\n",(count++)+1, name.c_str(),childLinkIndex);
|
||||||
|
// first grandchild
|
||||||
|
printTree(u2b,childLinkIndex,indentationLevel);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
class TestMultiBodyCreationCallback : public CustomMultiBodyCreationCallback
|
||||||
|
{
|
||||||
|
virtual int allocateMultiBodyBase(int urdfLinkIndex, int totalNumJoints,ScalarType baseMass, const Vector3dType& localInertiaDiagonal, bool isFixedBase)
|
||||||
|
{
|
||||||
|
printf("added base\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void addLinkAndJoint(int jointType, int linkIndex, // 0 to num_links-1
|
||||||
|
int parentIndex,
|
||||||
|
double mass,
|
||||||
|
const Vector3dType& inertia,
|
||||||
|
const QuaternionType &rotParentFrameToLinkFrame, // rotate points in parent frame to this frame, when q = 0
|
||||||
|
const Vector3dType& jointAxisInLinkFrame, // in Link frame
|
||||||
|
const Vector3dType& parentComToThisJointOffset, // vector from parent COM to joint frame, in Parent frame
|
||||||
|
const Vector3dType& thisJointToThisComOffset) // vector from joint frame to my COM, in Link frame);
|
||||||
|
{
|
||||||
|
printf("added link\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
void MultiBodyCustomURDFDemo::initPhysics()
|
void MultiBodyCustomURDFDemo::initPhysics()
|
||||||
{
|
{
|
||||||
int upAxis = 2;
|
int upAxis = 2;
|
||||||
m_guiHelper->setUpAxis(upAxis);
|
m_guiHelper->setUpAxis(upAxis);
|
||||||
createEmptyDynamicsWorld();
|
createEmptyDynamicsWorld();
|
||||||
|
btVector3 grav(0,0,0);
|
||||||
|
//grav[upAxis] = -10.f;
|
||||||
|
|
||||||
|
m_dynamicsWorld->setGravity(grav);
|
||||||
|
|
||||||
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||||
m_dynamicsWorld->getDebugDrawer()->setDebugMode(
|
|
||||||
//btIDebugDraw::DBG_DrawConstraints
|
|
||||||
+btIDebugDraw::DBG_DrawWireframe
|
|
||||||
+btIDebugDraw::DBG_DrawContactPoints
|
|
||||||
+btIDebugDraw::DBG_DrawAabb
|
|
||||||
);//+btIDebugDraw::DBG_DrawConstraintLimits);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
MyURDFImporter u2b(m_guiHelper);
|
||||||
|
bool loadOk = u2b.loadURDF("r2d2.urdf");
|
||||||
|
|
||||||
|
if (loadOk)
|
||||||
|
{
|
||||||
|
u2b.printTree();
|
||||||
|
int urdfRootLinkIndex = u2b.getRootLinkIndex();
|
||||||
|
myPrintTree(u2b,urdfRootLinkIndex,0);
|
||||||
|
|
||||||
|
btTransform identityTrans;
|
||||||
|
identityTrans.setIdentity();
|
||||||
|
|
||||||
|
btMultiBody* mb = 0;
|
||||||
|
|
||||||
|
|
||||||
|
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||||
|
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||||
|
printf("urdf root link index = %d\n",rootLinkIndex);
|
||||||
|
MyMultiBodyCreator creation(m_guiHelper);
|
||||||
|
|
||||||
|
bool useMultiBody = true;
|
||||||
|
|
||||||
|
ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
|
||||||
|
mb = creation.getBulletMultiBody();
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void MultiBodyCustomURDFDemo::stepSimulation(float deltaTime)
|
void MultiBodyCustomURDFDemo::stepSimulation(float deltaTime)
|
||||||
{
|
{
|
||||||
|
|
||||||
m_dynamicsWorld->stepSimulation(deltaTime);
|
m_dynamicsWorld->stepSimulation(deltaTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
class ExampleInterface* MultiBodyCustomURDFDofCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option)
|
class ExampleInterface* MultiBodyCustomURDFDemoCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option)
|
||||||
{
|
{
|
||||||
return new MultiBodyCustomURDFDemo(helper);
|
return new MultiBodyCustomURDFDemo(helper);
|
||||||
}
|
}
|
||||||
@@ -1,6 +1,20 @@
|
|||||||
|
/* Copyright (C) 2015 Google
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
#ifndef MULTI_DOF_CUSTOM_URDF_DEMO_H
|
#ifndef MULTI_DOF_CUSTOM_URDF_DEMO_H
|
||||||
#define MULTI_DOF_CUSTOM_URDF_DEMO_H
|
#define MULTI_DOF_CUSTOM_URDF_DEMO_H
|
||||||
|
|
||||||
class ExampleInterface* MultiBodyCustomURDFDofCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option);
|
class ExampleInterface* MultiBodyCustomURDFDemoCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option);
|
||||||
|
|
||||||
#endif //MULTI_DOF_CUSTOM_URDF_DEMO_H
|
#endif //MULTI_DOF_CUSTOM_URDF_DEMO_H
|
||||||
|
|||||||
43
examples/MultiBody/main.cpp
Normal file
43
examples/MultiBody/main.cpp
Normal file
@@ -0,0 +1,43 @@
|
|||||||
|
/*
|
||||||
|
Bullet Continuous Collision Detection and Physics Library
|
||||||
|
Copyright (c) 2015 Google Inc. 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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#include "MultiBodyCustomURDFDemo.h"
|
||||||
|
|
||||||
|
#include "../CommonInterfaces/ExampleInterface.h"
|
||||||
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int main(int argc, char* argv[])
|
||||||
|
{
|
||||||
|
struct PhysicsInterface* pint = 0;
|
||||||
|
|
||||||
|
DummyGUIHelper noGfx;
|
||||||
|
|
||||||
|
int option = 0;
|
||||||
|
|
||||||
|
ExampleInterface* example = MultiBodyCustomURDFDemoCreateFunc(pint, &noGfx, option);
|
||||||
|
|
||||||
|
example->initPhysics();
|
||||||
|
example->stepSimulation(1.f/60.f);
|
||||||
|
example->exitPhysics();
|
||||||
|
|
||||||
|
delete example;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
40
examples/MultiBody/premake4.lua
Normal file
40
examples/MultiBody/premake4.lua
Normal file
@@ -0,0 +1,40 @@
|
|||||||
|
|
||||||
|
project "App_CustomMultiBodyCreation"
|
||||||
|
|
||||||
|
if _OPTIONS["ios"] then
|
||||||
|
kind "WindowedApp"
|
||||||
|
else
|
||||||
|
kind "ConsoleApp"
|
||||||
|
end
|
||||||
|
|
||||||
|
includedirs {".", "../../src", "../ThirdPartyLibs"}
|
||||||
|
|
||||||
|
links {
|
||||||
|
"Bullet3Common", "BulletDynamics","BulletCollision", "LinearMath"
|
||||||
|
}
|
||||||
|
|
||||||
|
language "C++"
|
||||||
|
|
||||||
|
files {
|
||||||
|
"MultiBodyCustomURDFDemo.cpp",
|
||||||
|
"main.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/URDF2Bullet.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyURDFImporter.cpp",
|
||||||
|
"../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
|
||||||
|
"../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||||
|
"../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||||
|
"../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||||
|
"../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
|
||||||
|
"../ThirdPartyLibs/tinyxml/tinystr.cpp",
|
||||||
|
"../ThirdPartyLibs/tinyxml/tinyxml.cpp",
|
||||||
|
"../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
|
||||||
|
"../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/boost_replacement/printf_console.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/boost_replacement/string_split.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/pose.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/model.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/link.cpp",
|
||||||
|
"../ThirdPartyLibs/urdf/urdfdom/urdf_parser/src/joint.cpp",
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
@@ -178,6 +178,13 @@ public:
|
|||||||
{
|
{
|
||||||
m_basePos = pos;
|
m_basePos = pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setBaseWorldTransform(const btTransform& tr)
|
||||||
|
{
|
||||||
|
setBasePos(tr.getOrigin());
|
||||||
|
setWorldToBaseRot(tr.getRotation().inverse());
|
||||||
|
|
||||||
|
}
|
||||||
void setBaseVel(const btVector3 &vel)
|
void setBaseVel(const btVector3 &vel)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user