2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
#include "ImportURDFSetup.h"
|
|
|
|
#include "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h"
|
2015-04-22 23:35:27 +00:00
|
|
|
|
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
|
|
|
#include "Bullet3Common/b3FileUtils.h"
|
2015-04-22 23:35:27 +00:00
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
|
|
|
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
|
|
|
#include "../CommonInterfaces/CommonParameterInterface.h"
|
2015-04-22 23:35:27 +00:00
|
|
|
#include "MyURDFImporter.h"
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
static int bodyCollisionFilterGroup=btBroadphaseProxy::CharacterFilter;
|
|
|
|
static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphaseProxy::CharacterFilter);
|
|
|
|
static bool enableConstraints = true;//false;
|
|
|
|
#include "URDF2Bullet.h"
|
|
|
|
|
|
|
|
#include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.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"
|
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
#include "MyMultiBodyCreator.h"
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
|
|
|
|
class ImportUrdfSetup : public CommonMultiBodyBase
|
|
|
|
{
|
|
|
|
char m_fileName[1024];
|
|
|
|
|
|
|
|
struct ImportUrdfInternalData* m_data;
|
|
|
|
bool m_useMultiBody;
|
|
|
|
|
|
|
|
public:
|
|
|
|
ImportUrdfSetup(struct GUIHelperInterface* helper, int option);
|
|
|
|
virtual ~ImportUrdfSetup();
|
|
|
|
|
|
|
|
virtual void initPhysics();
|
|
|
|
virtual void stepSimulation(float deltaTime);
|
|
|
|
|
|
|
|
void setFileName(const char* urdfFileName);
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
btAlignedObjectArray<std::string> gFileNameArray;
|
|
|
|
|
|
|
|
|
|
|
|
#define MAX_NUM_MOTORS 1024
|
|
|
|
|
|
|
|
struct ImportUrdfInternalData
|
|
|
|
{
|
|
|
|
ImportUrdfInternalData()
|
|
|
|
:m_numMotors(0)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
btScalar m_motorTargetVelocities[MAX_NUM_MOTORS];
|
|
|
|
btMultiBodyJointMotor* m_jointMotors [MAX_NUM_MOTORS];
|
|
|
|
int m_numMotors;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
ImportUrdfSetup::ImportUrdfSetup(struct GUIHelperInterface* helper, int option)
|
|
|
|
:CommonMultiBodyBase(helper)
|
|
|
|
{
|
|
|
|
if (option==1)
|
|
|
|
{
|
|
|
|
m_useMultiBody = true;
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
m_useMultiBody = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
static int count = 0;
|
|
|
|
gFileNameArray.clear();
|
|
|
|
gFileNameArray.push_back("r2d2.urdf");
|
|
|
|
|
|
|
|
m_data = new ImportUrdfInternalData;
|
|
|
|
|
|
|
|
//load additional urdf file names from file
|
|
|
|
|
|
|
|
FILE* f = fopen("urdf_files.txt","r");
|
|
|
|
if (f)
|
|
|
|
{
|
|
|
|
int result;
|
|
|
|
//warning: we don't avoid string buffer overflow in this basic example in fscanf
|
|
|
|
char fileName[1024];
|
|
|
|
do
|
|
|
|
{
|
|
|
|
result = fscanf(f,"%s",fileName);
|
|
|
|
if (result==1)
|
|
|
|
{
|
|
|
|
gFileNameArray.push_back(fileName);
|
|
|
|
}
|
|
|
|
} while (result==1);
|
|
|
|
|
|
|
|
fclose(f);
|
|
|
|
}
|
|
|
|
|
|
|
|
int numFileNames = gFileNameArray.size();
|
|
|
|
|
|
|
|
if (count>=numFileNames)
|
|
|
|
{
|
|
|
|
count=0;
|
|
|
|
}
|
|
|
|
sprintf(m_fileName,gFileNameArray[count++].c_str());
|
|
|
|
}
|
|
|
|
|
|
|
|
ImportUrdfSetup::~ImportUrdfSetup()
|
|
|
|
{
|
|
|
|
delete m_data;
|
|
|
|
}
|
|
|
|
|
|
|
|
static btVector4 colors[4] =
|
|
|
|
{
|
|
|
|
btVector4(1,0,0,1),
|
|
|
|
btVector4(0,1,0,1),
|
|
|
|
btVector4(0,1,1,1),
|
|
|
|
btVector4(1,1,0,1),
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
btVector3 selectColor()
|
|
|
|
{
|
|
|
|
|
|
|
|
static int curColor = 0;
|
|
|
|
btVector4 color = colors[curColor];
|
|
|
|
curColor++;
|
|
|
|
curColor&=3;
|
|
|
|
return color;
|
|
|
|
}
|
|
|
|
|
|
|
|
void ImportUrdfSetup::setFileName(const char* urdfFileName)
|
|
|
|
{
|
|
|
|
memcpy(m_fileName,urdfFileName,strlen(urdfFileName)+1);
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
void printTree1(my_shared_ptr<const Link> link,int level = 0)
|
2015-04-16 16:55:32 +00:00
|
|
|
{
|
|
|
|
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
|
2015-04-22 23:35:27 +00:00
|
|
|
printTree1(*child,level);
|
2015-04-16 16:55:32 +00:00
|
|
|
}
|
|
|
|
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()
|
|
|
|
{
|
|
|
|
|
|
|
|
int upAxis = 2;
|
|
|
|
m_guiHelper->setUpAxis(2);
|
|
|
|
|
|
|
|
this->createEmptyDynamicsWorld();
|
|
|
|
//m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
|
|
|
|
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
|
|
|
m_dynamicsWorld->getDebugDrawer()->setDebugMode(
|
|
|
|
btIDebugDraw::DBG_DrawConstraints
|
|
|
|
+btIDebugDraw::DBG_DrawContactPoints
|
|
|
|
+btIDebugDraw::DBG_DrawAabb
|
|
|
|
);//+btIDebugDraw::DBG_DrawConstraintLimits);
|
|
|
|
|
|
|
|
|
|
|
|
btVector3 gravity(0,0,0);
|
|
|
|
gravity[upAxis]=-9.8;
|
|
|
|
|
|
|
|
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
|
2015-04-22 23:35:27 +00:00
|
|
|
printTree1(root_link);
|
2015-04-16 16:55:32 +00:00
|
|
|
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
|
2015-04-22 23:35:27 +00:00
|
|
|
MyURDFImporter u2b(robot,m_guiHelper);
|
|
|
|
printTree(u2b, 0);
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
btTransform identityTrans;
|
|
|
|
identityTrans.setIdentity();
|
|
|
|
|
|
|
|
int numJoints = (*robot).m_numJoints;
|
|
|
|
|
|
|
|
|
|
|
|
bool useUrdfInterfaceClass = true;
|
|
|
|
|
|
|
|
{
|
2015-04-23 01:09:00 +00:00
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
btMultiBody* mb = 0;
|
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
//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);
|
2015-04-16 16:55:32 +00:00
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,m_useMultiBody,pathPrefix);
|
|
|
|
mb = creation.getBulletMultiBody();
|
|
|
|
|
|
|
|
if (m_useMultiBody)
|
|
|
|
{
|
|
|
|
mb->setHasSelfCollision(false);
|
|
|
|
mb->finalizeMultiDof();
|
|
|
|
m_dynamicsWorld->addMultiBody(mb);
|
2015-04-16 16:55:32 +00:00
|
|
|
|
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
//create motors for each joint
|
2015-04-16 16:55:32 +00:00
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
for (int i=0;i<mb->getNumLinks();i++)
|
|
|
|
{
|
|
|
|
int mbLinkIndex = i;
|
|
|
|
if (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute)
|
2015-04-16 16:55:32 +00:00
|
|
|
{
|
2015-04-22 23:35:27 +00:00
|
|
|
if (m_data->m_numMotors<MAX_NUM_MOTORS)
|
2015-04-16 16:55:32 +00:00
|
|
|
{
|
2015-04-22 23:35:27 +00:00
|
|
|
int urdfLinkIndex = creation.m_mb2urdfLink[mbLinkIndex];
|
2015-04-16 16:55:32 +00:00
|
|
|
|
2015-04-22 23:35:27 +00:00
|
|
|
std::string jointName = u2b.getJointName(urdfLinkIndex);
|
|
|
|
char motorName[1024];
|
|
|
|
sprintf(motorName,"%s q'", jointName.c_str());
|
|
|
|
btScalar* motorVel = &m_data->m_motorTargetVelocities[m_data->m_numMotors];
|
|
|
|
*motorVel = 0.f;
|
|
|
|
SliderParams slider(motorName,motorVel);
|
|
|
|
slider.m_minVal=-4;
|
|
|
|
slider.m_maxVal=4;
|
|
|
|
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
|
|
|
float maxMotorImpulse = 0.1f;
|
|
|
|
btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,0,0,maxMotorImpulse);
|
|
|
|
m_data->m_jointMotors[m_data->m_numMotors]=motor;
|
|
|
|
m_dynamicsWorld->addMultiBodyConstraint(motor);
|
|
|
|
m_data->m_numMotors++;
|
2015-04-16 16:55:32 +00:00
|
|
|
}
|
|
|
|
}
|
2015-04-22 23:35:27 +00:00
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2015-04-22 23:35:27 +00:00
|
|
|
|
2015-04-16 16:55:32 +00:00
|
|
|
//the btMultiBody support is work-in-progress :-)
|
|
|
|
|
|
|
|
|
|
|
|
printf("numJoints/DOFS = %d\n", numJoints);
|
|
|
|
|
|
|
|
bool createGround=true;
|
|
|
|
if (createGround)
|
|
|
|
{
|
|
|
|
btVector3 groundHalfExtents(20,20,20);
|
|
|
|
groundHalfExtents[upAxis]=1.f;
|
|
|
|
btBoxShape* box = new btBoxShape(groundHalfExtents);
|
|
|
|
box->initializePolyhedralFeatures();
|
|
|
|
|
|
|
|
m_guiHelper->createCollisionShapeGraphicsObject(box);
|
|
|
|
btTransform start; start.setIdentity();
|
|
|
|
btVector3 groundOrigin(0,0,0);
|
|
|
|
groundOrigin[upAxis]=-2;//.5;
|
|
|
|
start.setOrigin(groundOrigin);
|
|
|
|
btRigidBody* body = createRigidBody(0,start,box);
|
|
|
|
//m_dynamicsWorld->removeRigidBody(body);
|
|
|
|
// m_dynamicsWorld->addRigidBody(body,2,1);
|
|
|
|
btVector3 color(0.5,0.5,0.5);
|
|
|
|
m_guiHelper->createRigidBodyGraphicsObject(body,color);
|
|
|
|
}
|
|
|
|
|
|
|
|
///this extra stepSimulation call makes sure that all the btMultibody transforms are properly propagates.
|
|
|
|
m_dynamicsWorld->stepSimulation(1. / 240., 0);// 1., 10, 1. / 240.);
|
|
|
|
}
|
|
|
|
|
|
|
|
void ImportUrdfSetup::stepSimulation(float deltaTime)
|
|
|
|
{
|
|
|
|
if (m_dynamicsWorld)
|
|
|
|
{
|
|
|
|
for (int i=0;i<m_data->m_numMotors;i++)
|
|
|
|
{
|
|
|
|
m_data->m_jointMotors[i]->setVelocityTarget(m_data->m_motorTargetVelocities[i]);
|
|
|
|
}
|
|
|
|
|
|
|
|
//the maximal coordinates/iterative MLCP solver requires a smallish timestep to converge
|
|
|
|
m_dynamicsWorld->stepSimulation(deltaTime,10,1./240.);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
class ExampleInterface* ImportURDFCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option)
|
|
|
|
{
|
|
|
|
|
|
|
|
return new ImportUrdfSetup(helper, option);
|
|
|
|
}
|