#include "ImportURDFSetup.h" ImportUrdfDemo::ImportUrdfDemo() { } ImportUrdfDemo::~ImportUrdfDemo() { } #include "urdf/urdfdom/urdf_parser/include/urdf_parser/urdf_parser.h" #include #include using namespace urdf; void printTree(my_shared_ptr link,int level = 0) { level+=2; int count = 0; for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) { if (*child) { for(int j=0;jname << std::endl; // first grandchild printTree(*child,level); } else { for(int j=0;jname << " has a null child!" << *child << std::endl; } } } #define MSTRINGIFY(A) #A const char* urdf_char2 = MSTRINGIFY( ); const char* urdf_char1 = MSTRINGIFY( ); const char* urdf_char3 = MSTRINGIFY( ); const char* urdf_char4 = MSTRINGIFY( ); const char* urdf_char_r2d2 = MSTRINGIFY( ); const char* urdf_char = MSTRINGIFY( ); #include "BulletCollision/CollisionShapes/btCylinderShape.h" void URDFvisual2BulletCollisionShape(my_shared_ptr link, GraphicsPhysicsBridge& gfxBridge, const btTransform& parentTransformInWorldSpace, btDiscreteDynamicsWorld* world) { btCollisionShape* shape = 0; btTransform linkTransformInWorldSpace; linkTransformInWorldSpace.setIdentity(); btScalar mass = 0; btTransform inertialFrame; inertialFrame.setIdentity(); if ((*link).inertial) { mass = (*link).inertial->mass; inertialFrame.setOrigin(btVector3((*link).inertial->origin.position.x,(*link).inertial->origin.position.y,(*link).inertial->origin.position.z)); inertialFrame.setRotation(btQuaternion((*link).inertial->origin.rotation.x,(*link).inertial->origin.rotation.y,(*link).inertial->origin.rotation.z,(*link).inertial->origin.rotation.w)); } if ((*link).parent_joint) { btTransform p2j; const urdf::Vector3 pos = (*link).parent_joint->parent_to_joint_origin_transform.position; const urdf::Rotation orn = (*link).parent_joint->parent_to_joint_origin_transform.rotation; btTransform parent2joint; parent2joint.setOrigin(btVector3(pos.x,pos.y,pos.z)); parent2joint.setRotation(btQuaternion(orn.x,orn.y,orn.z,orn.w)); linkTransformInWorldSpace =parentTransformInWorldSpace*parent2joint; } else { linkTransformInWorldSpace = parentTransformInWorldSpace; } //btTransform linkCenterOfMass =inertialFrame*linkTransformInWorldSpace; { printf("converting link %s",link->name.c_str()); for (int v=0;vvisual_array.size();v++) { const Visual* visual = link->visual_array[v].get(); switch (visual->geometry->type) { case Geometry::CYLINDER: { printf("processing a cylinder\n"); urdf::Cylinder* cyl = (urdf::Cylinder*)visual->geometry.get(); btVector3 halfExtents(cyl->radius,cyl->radius,cyl->length/2.); btCylinderShapeZ* cylZShape = new btCylinderShapeZ(halfExtents); shape = cylZShape; break; } case Geometry::BOX: { printf("processing a box\n"); urdf::Box* box = (urdf::Box*)visual->geometry.get(); btVector3 extents(box->dim.x,box->dim.y,box->dim.z); btBoxShape* boxShape = new btBoxShape(extents*0.5f); shape = boxShape; break; } case Geometry::SPHERE: { printf("processing a sphere\n"); urdf::Sphere* sphere = (urdf::Sphere*)visual->geometry.get(); btScalar radius = sphere->radius; btSphereShape* sphereShape = new btSphereShape(radius); shape = sphereShape; break; break; } case Geometry::MESH: { break; } default: { printf("Error: unknown visual geometry type\n"); } } if (shape) { gfxBridge.createCollisionShapeGraphicsObject(shape); btVector3 color(0,0,1); if (visual->material.get()) { color.setValue(visual->material->color.r,visual->material->color.g,visual->material->color.b);//,visual->material->color.a); } btVector3 localInertia(0,0,0); if (mass) { shape->calculateLocalInertia(mass,localInertia); } btRigidBody::btRigidBodyConstructionInfo rbci(mass,0,shape,localInertia); btVector3 visual_pos(visual->origin.position.x,visual->origin.position.y,visual->origin.position.z); btQuaternion visual_orn(visual->origin.rotation.x,visual->origin.rotation.y,visual->origin.rotation.z,visual->origin.rotation.w); btTransform visual_frame; visual_frame.setOrigin(visual_pos); visual_frame.setRotation(visual_orn); btTransform visualFrameInWorldSpace =linkTransformInWorldSpace*visual_frame; rbci.m_startWorldTransform = visualFrameInWorldSpace;//linkCenterOfMass; btRigidBody* body = new btRigidBody(rbci); world->addRigidBody(body); gfxBridge.createRigidBodyGraphicsObject(body,color); } } } for (std::vector >::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) { if (*child) { URDFvisual2BulletCollisionShape(*child,gfxBridge, linkTransformInWorldSpace, world); } else { std::cout << "root link: " << link->name << " has a null child!" << *child << std::endl; } } } void ImportUrdfDemo::initPhysics(GraphicsPhysicsBridge& gfxBridge) { int upAxis = 2; gfxBridge.setUpAxis(upAxis); this->createEmptyDynamicsWorld(); /* btVector3 groundHalfExtents(50,50,50); groundHalfExtents[upAxis]=1.f; btBoxShape* box = new btBoxShape(groundHalfExtents); gfxBridge.createCollisionShapeGraphicsObject(box); btTransform start; start.setIdentity(); btVector3 groundOrigin(0,0,0); groundOrigin[upAxis]=-5; start.setOrigin(groundOrigin); btRigidBody* body = createRigidBody(0,start,box); btVector3 color(0,1,0); gfxBridge.createRigidBodyGraphicsObject(body,color); */ btVector3 gravity(0,0,0); gravity[upAxis]=-9.8; m_dynamicsWorld->setGravity(gravity); int argc=0; char* filename="somefile.urdf"; std::string xml_string; if (argc < 2){ std::cerr << "No URDF file name provided, using a dummy test URDF" << std::endl; xml_string = std::string(urdf_char); } else { std::fstream xml_file(filename, 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 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 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 printTree(root_link); btTransform worldTrans; worldTrans.setIdentity(); { URDFvisual2BulletCollisionShape(root_link, gfxBridge, worldTrans,m_dynamicsWorld); } }