24 #include "hrpCorba/ViewSimulator.hh"
28 #include <boost/typeof/typeof.hpp>
29 #define FOREACH(it, v) for(BOOST_TYPEOF((v).begin()) it = (v).begin(); it != (v).end(); (it)++)
35 typedef map<string, string> SensorTypeMap;
36 SensorTypeMap sensorTypeMap;
39 void operator<<(std::ostream& os,
const OpenHRP::DblArray12& ttemp) {
40 OpenHRP::DblArray4 quat;
42 os << ttemp[3] <<
" " << ttemp[7] <<
" " << ttemp[11] <<
" / ";
43 os << quat[0] <<
" " << quat[1] <<
" " << quat[2] <<
" " << quat[3];
46 #define printArrayWARN(name, ary) \
47 COLLADALOG_WARN(str(boost::format(name": %f\t%f\t%f\t%f")%ary[0]%ary[1]%ary[2]%ary[3])); \
48 COLLADALOG_WARN(str(boost::format(name": %f\t%f\t%f\t%f")%ary[4]%ary[5]%ary[6]%ary[7])); \
49 COLLADALOG_WARN(str(boost::format(name": %f\t%f\t%f\t%f")%ary[8]%ary[9]%ary[10]%ary[11]));
50 #define printArrayDEBUG(name, ary) \
51 COLLADALOG_DEBUG(str(boost::format(name": %f\t%f\t%f\t%f")%ary[0]%ary[1]%ary[2]%ary[3])); \
52 COLLADALOG_DEBUG(str(boost::format(name": %f\t%f\t%f\t%f")%ary[4]%ary[5]%ary[6]%ary[7])); \
53 COLLADALOG_DEBUG(str(boost::format(name": %f\t%f\t%f\t%f")%ary[8]%ary[9]%ary[10]%ary[11]));
54 #define printArray printArrayDEBUG
63 JointAxisBinding(daeElementRef pvisualtrans, domAxis_constraintRef pkinematicaxis, domCommon_float_or_paramRef jointvalue, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info) : pvisualtrans(pvisualtrans), pkinematicaxis(pkinematicaxis), jointvalue(jointvalue), kinematics_axis_info(kinematics_axis_info), motion_axis_info(motion_axis_info) {
65 daeElement* pae = pvisualtrans->getParentElement();
67 visualnode = daeSafeCast<domNode> (pae);
71 pae = pae->getParentElement();
75 COLLADALOG_WARN(str(boost::format(
"couldn't find parent node of element id %s, sid %s")%pkinematicaxis->getID()%pkinematicaxis->getSid()));
114 bool AddAxisInfo(
const domInstance_kinematics_model_Array& arr, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info)
116 if( !kinematics_axis_info ) {
119 for(
size_t ik = 0; ik < arr.getCount(); ++ik) {
120 daeElement* pelt = daeSidRef(kinematics_axis_info->getAxis(), arr[ik]->getUrl().getElement()).resolve().elt;
124 for(std::list<JointAxisBinding>::iterator itbinding = listAxisBindings.begin(); itbinding != listAxisBindings.end(); ++itbinding) {
125 if( itbinding->pkinematicaxis.cast() == pelt ) {
126 itbinding->kinematics_axis_info = kinematics_axis_info;
127 if( !!motion_axis_info ) {
128 itbinding->motion_axis_info = motion_axis_info;
135 COLLADALOG_WARN(str(boost::format(
"could not find binding for axis: %s, %s")%kinematics_axis_info->getAxis()%pelt->getAttribute(
"sid")));
141 COLLADALOG_WARN(str(boost::format(
"could not find kinematics axis target: %s")%kinematics_axis_info->getAxis()));
147 ColladaReader() : _dom(NULL), _nGlobalSensorId(0), _nGlobalActuatorId(0), _nGlobalManipulatorId(0), _nGlobalIndex(0) {
148 daeErrorHandler::setErrorHandler(
this);
149 _bOpeningZAE =
false;
163 for(
size_t i = 0;
i < url2.size(); ++
i) {
164 if( url2[
i] ==
'\\' ) {
170 COLLADALOG_VERBOSE(str(boost::format(
"init COLLADA reader version: %s, namespace: %s, filename: %s")%COLLADA_VERSION%COLLADA_NAMESPACE%
filename));
174 _dom = daeSafeCast<domCOLLADA>(_dae->open(
filename));
175 _bOpeningZAE =
false;
185 COLLADALOG_DEBUG(str(boost::format(
"init COLLADA reader version: %s, namespace: %s")%COLLADA_VERSION%COLLADA_NAMESPACE));
187 _dom = daeSafeCast<domCOLLADA>(_dae->openFromMemory(
".",pdata.c_str()));
197 if( !!_dom->getAsset() ) {
198 if( !!_dom->getAsset()->getUnit() ) {
199 _fGlobalScale = _dom->getAsset()->getUnit()->getMeter();
207 _mapJointUnits.clear();
208 _mapJointIds.clear();
209 _mapLinkNames.clear();
211 _veclinknames.clear();
217 std::list< pair<domInstance_kinematics_modelRef, boost::shared_ptr<KinematicsSceneBindings> > > listPossibleBodies;
218 domCOLLADA::domSceneRef allscene = _dom->getScene();
232 for (
size_t iscene = 0; iscene < allscene->getInstance_kinematics_scene_array().getCount(); iscene++) {
233 domInstance_kinematics_sceneRef kiscene = allscene->getInstance_kinematics_scene_array()[iscene];
234 domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene> (kiscene->getUrl().getElement().cast());
239 _ExtractKinematicsVisualBindings(allscene->getInstance_visual_scene(),kiscene,*bindings);
240 _ExtractPhysicsBindings(allscene,*bindings);
241 for(
size_t ias = 0; ias < kscene->getInstance_articulated_system_array().getCount(); ++ias) {
242 if( ExtractArticulatedSystem(probot, kscene->getInstance_articulated_system_array()[ias], *bindings) && !!probot ) {
247 for(
size_t ikmodel = 0; ikmodel < kscene->getInstance_kinematics_model_array().getCount(); ++ikmodel) {
248 listPossibleBodies.push_back(make_pair(kscene->getInstance_kinematics_model_array()[ikmodel], bindings));
252 for(std::list< pair<domInstance_kinematics_modelRef, boost::shared_ptr<KinematicsSceneBindings> > >::iterator it = listPossibleBodies.begin(); it != listPossibleBodies.end(); ++it) {
253 if( ExtractKinematicsModel(probot, it->first, *it->second) ) {
261 if (!!allscene->getInstance_visual_scene()) {
262 domVisual_sceneRef viscene = daeSafeCast<domVisual_scene>(allscene->getInstance_visual_scene()->getUrl().getElement().cast());
263 for (
size_t node = 0; node < viscene->getNode_array().getCount(); node++) {
265 if ( ExtractKinematicsModel(probot, viscene->getNode_array()[node],*bindings,std::vector<std::string>()) ) {
277 probot->
links_.length(_veclinks.size());
279 for(
size_t i = 0;
i < _veclinks.size(); ++
i) {
286 probot->
links_[
i].segments.length(numSegment);
287 for (
int s = 0; s < numSegment; ++s ) {
288 SegmentInfo_var segmentInfo(
new SegmentInfo());
293 for(
int col=0; col < 4; ++col){
294 segmentInfo->transformMatrix[p++] = T(
row, col);
297 segmentInfo->name = _veclinknames[
i].c_str();
298 segmentInfo->shapeIndices.length(probot->
links_[
i].shapeIndices.length());
299 for(
unsigned int j = 0; j < probot->
links_[
i].shapeIndices.length(); j++ ) {
300 segmentInfo->shapeIndices[j] = j;
302 segmentInfo->mass = probot->
links_[
i].mass;
303 segmentInfo->centerOfMass[0] = probot->
links_[
i].centerOfMass[0];
304 segmentInfo->centerOfMass[1] = probot->
links_[
i].centerOfMass[1];
305 segmentInfo->centerOfMass[2] = probot->
links_[
i].centerOfMass[2];
306 for(
int j = 0; j < 9 ; j++ ) {
307 segmentInfo->inertia[j] = probot->
links_[
i].inertia[j];
309 probot->
links_[
i].segments[s] = segmentInfo;
316 for(
size_t linkIndex = 0; linkIndex < _veclinks.size(); ++linkIndex) {
318 coldetModel->setName(std::string(probot->
links_[linkIndex].name));
320 int triangleIndex = 0;
323 const TransformedShapeIndexSequence& shapeIndices = probot->
linkShapeIndices_[linkIndex];
324 probot->
setColdetModel(coldetModel, shapeIndices, E, vertexIndex, triangleIndex);
327 const SensorInfoSequence& sensors = probot->
links_[linkIndex].sensors;
328 for (
unsigned int i=0;
i<sensors.length();
i++){
329 const SensorInfo& sensor = sensors[
i];
331 sensor.rotation[2]), sensor.rotation[3]);
332 T(0,3) = sensor.translation[0];
333 T(1,3) = sensor.translation[1];
334 T(2,3) = sensor.translation[2];
335 const TransformedShapeIndexSequence& sensorShapeIndices = sensor.shapeIndices;
336 probot->
setColdetModel(coldetModel, sensorShapeIndices, T, vertexIndex, triangleIndex);
338 if(triangleIndex>0) {
339 coldetModel->build();
342 probot->
links_[linkIndex].AABBmaxDepth = coldetModel->getAABBTreeDepth();
343 probot->
links_[linkIndex].AABBmaxNum = coldetModel->getAABBmaxNum();
355 domArticulated_systemRef articulated_system = daeSafeCast<domArticulated_system> (ias->getUrl().getElement().cast());
356 if( !articulated_system ) {
360 boost::shared_ptr<std::string> pinterface_type = _ExtractInterfaceType(ias->getExtra_array());
361 if( !pinterface_type ) {
362 pinterface_type = _ExtractInterfaceType(articulated_system->getExtra_array());
364 if( !!pinterface_type ) {
365 COLLADALOG_WARN(str(boost::format(
"need to create a robot with type %s")%*(pinterface_type)));
370 if( probot->
url_.size() == 0 ) {
371 probot->
url_ = _filename;
373 if( probot->
name_.size() == 0 && !!ias->getName() ) {
374 probot->
name_ = CORBA::string_dup(ias->getName());
376 if( probot->
name_.size() == 0 && !!ias->getSid()) {
377 probot->
name_ = CORBA::string_dup(ias->getSid());
379 if( probot->
name_.size() == 0 && !!articulated_system->getName() ) {
380 probot->
name_ = CORBA::string_dup(articulated_system->getName());
382 if( probot->
name_.size() == 0 && !!articulated_system->getId()) {
383 probot->
name_ = CORBA::string_dup(articulated_system->getId());
386 if( !!articulated_system->getMotion() ) {
387 domInstance_articulated_systemRef ias_new = articulated_system->getMotion()->getInstance_articulated_system();
388 if( !!articulated_system->getMotion()->getTechnique_common() ) {
389 for(
size_t i = 0;
i < articulated_system->getMotion()->getTechnique_common()->getAxis_info_array().getCount(); ++
i) {
390 domMotion_axis_infoRef motion_axis_info = articulated_system->getMotion()->getTechnique_common()->getAxis_info_array()[
i];
392 domKinematics_axis_infoRef kinematics_axis_info = daeSafeCast<domKinematics_axis_info>(daeSidRef(motion_axis_info->getAxis(), ias_new->getUrl().getElement()).resolve().elt);
393 if( !!kinematics_axis_info ) {
395 daeElement* pparent = kinematics_axis_info->getParent();
396 while(!!pparent && pparent->typeID() != domKinematics::ID()) {
397 pparent = pparent->getParent();
400 bindings.
AddAxisInfo(daeSafeCast<domKinematics>(pparent)->getInstance_kinematics_model_array(), kinematics_axis_info, motion_axis_info);
403 COLLADALOG_WARN(str(boost::format(
"failed to find kinematics axis %s")%motion_axis_info->getAxis()));
407 if( !ExtractArticulatedSystem(probot,ias_new,bindings) ) {
412 if( !articulated_system->getKinematics() ) {
413 COLLADALOG_WARN(str(boost::format(
"collada <kinematics> tag empty? instance_articulated_system=%s")%ias->getID()));
417 if( !!articulated_system->getKinematics()->getTechnique_common() ) {
418 for(
size_t i = 0;
i < articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array().getCount(); ++
i) {
419 bindings.
AddAxisInfo(articulated_system->getKinematics()->getInstance_kinematics_model_array(), articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array()[
i], NULL);
429 for(
size_t ik = 0; ik < articulated_system->getKinematics()->getInstance_kinematics_model_array().getCount(); ++ik) {
430 ExtractKinematicsModel(probot,articulated_system->getKinematics()->getInstance_kinematics_model_array()[ik],bindings);
434 ExtractRobotManipulators(probot, articulated_system);
435 ExtractRobotAttachedSensors(probot, articulated_system);
436 ExtractRobotAttachedActuators(probot, articulated_system);
445 COLLADALOG_DEBUG(str(boost::format(
"instance kinematics model sid %s")%ikm->getSid()));
446 domKinematics_modelRef kmodel = daeSafeCast<domKinematics_model> (ikm->getUrl().getElement().cast());
448 COLLADALOG_WARN(str(boost::format(
"%s does not reference valid kinematics")%ikm->getSid()));
451 domPhysics_modelRef pmodel;
453 boost::shared_ptr<std::string> pinterface_type = _ExtractInterfaceType(ikm->getExtra_array());
454 if( !pinterface_type ) {
455 pinterface_type = _ExtractInterfaceType(kmodel->getExtra_array());
457 if( !!pinterface_type ) {
458 COLLADALOG_WARN(str(boost::format(
"need to create a robot with type %s")%*pinterface_type));
463 if( pkinbody->
url_.size() == 0 ) {
464 pkinbody->
url_ = _filename;
468 domNodeRef pvisualnode;
470 if( it->second == ikm ) {
471 pvisualnode = it->first;
476 COLLADALOG_WARN(str(boost::format(
"failed to find visual node for instance kinematics model %s")%ikm->getSid()));
480 if( pkinbody->
name_.size() == 0 && !!ikm->getName() ) {
481 pkinbody->
name_ = CORBA::string_dup(ikm->getName());
483 if( pkinbody->
name_.size() == 0 && !!ikm->getID() ) {
484 pkinbody->
name_ = CORBA::string_dup(ikm->getID());
487 if (!ExtractKinematicsModel(pkinbody, kmodel, pvisualnode, pmodel, bindings)) {
488 COLLADALOG_WARN(str(boost::format(
"failed to load kinbody from kinematics model %s")%kmodel->getID()));
497 if( !!pdomnode->getID() && find(vprocessednodes.begin(),vprocessednodes.end(),pdomnode->getID()) != vprocessednodes.end() ) {
498 COLLADALOG_WARN(str(boost::format(
"could not create kinematics type pnode getid %s")%pdomnode->getID()));
502 string name = !pdomnode->getName() ?
"" : _ConvertToValidName(pdomnode->getName());
503 if(
name.size() == 0 ) {
504 name = _ConvertToValidName(pdomnode->getID());
506 boost::shared_ptr<LinkInfo> plink(
new LinkInfo());
507 _veclinks.push_back(plink);
509 plink->jointType = CORBA::string_dup(
"fixed");
510 plink->parentIndex = -1;
511 plink->name = CORBA::string_dup(
name.c_str());
515 bool bhasgeometry = ExtractGeometry(pkinbody,plink,tlink,pdomnode,bindings.
listAxisBindings,vprocessednodes);
516 if( !bhasgeometry ) {
529 vector<domJointRef> vdomjoints;
533 if( pkinbody->
name_.size() == 0 && !!kmodel->getName() ) {
534 pkinbody->
name_ = CORBA::string_dup(kmodel->getName());
536 if( pkinbody->
name_.size() == 0 && !!kmodel->getID() ) {
537 pkinbody->
name_ = CORBA::string_dup(kmodel->getID());
543 if( !kmodel->getID() ) {
548 domKinematics_model_techniqueRef ktec = kmodel->getTechnique_common();
551 for (
size_t ijoint = 0; ijoint < ktec->getJoint_array().getCount(); ++ijoint) {
552 vdomjoints.push_back(ktec->getJoint_array()[ijoint]);
556 for (
size_t ijoint = 0; ijoint < ktec->getInstance_joint_array().getCount(); ++ijoint) {
557 domJointRef pelt = daeSafeCast<domJoint> (ktec->getInstance_joint_array()[ijoint]->getUrl().getElement());
562 vdomjoints.push_back(pelt);
566 COLLADALOG_VERBOSE(str(boost::format(
"Number of root links in the kmodel %d")%ktec->getLink_array().getCount()));
569 for (
size_t ilink = 0; ilink < ktec->getLink_array().getCount(); ++ilink) {
570 domLinkRef pdomlink = ktec->getLink_array()[ilink];
572 _ExtractFullTransform(rootOrigin, pdomlink);
574 domNodeRef pvisualnode;
576 if(strcmp(it->first->getName() ,pdomlink->getName()) == 0) {
577 pvisualnode = it->first;
582 getNodeParentTransform(visualRootOrigin, pvisualnode);
583 printArray(
"visualRootOrigin", visualRootOrigin);
588 int linkindex = ExtractLink(pkinbody, pdomlink, ilink == 0 ? pnode : domNodeRef(),
589 identity, identity, vdomjoints, bindings);
591 boost::shared_ptr<LinkInfo> plink = _veclinks.at(linkindex);
595 for (
size_t iform = 0; iform < ktec->getFormula_array().getCount(); ++iform) {
596 domFormulaRef pf = ktec->getFormula_array()[iform];
597 if (!pf->getTarget()) {
603 boost::shared_ptr<LinkInfo> pjoint = _getJointFromRef(pf->getTarget()->getParam()->getValue(),pf,pkinbody).first;
609 dReal ftargetunit = 1;
610 if(_mapJointUnits.find(pjoint) != _mapJointUnits.end() ) {
611 ftargetunit = _mapJointUnits[pjoint].at(iaxis);
614 daeTArray<daeElementRef> children;
615 pf->getTechnique_common()->getChildren(children);
617 domTechniqueRef popenravetec = _ExtractOpenRAVEProfile(pf->getTechnique_array());
618 if( !!popenravetec ) {
619 for(
size_t ic = 0; ic < popenravetec->getContents().getCount(); ++ic) {
620 daeElementRef pequation = popenravetec->getContents()[ic];
621 if( pequation->getElementName() ==
string(
"equation") ) {
622 if( !pequation->hasAttribute(
"type") ) {
626 if( children.getCount() != 1 ) {
630 std::string equationtype = pequation->getAttribute(
"type");
631 boost::shared_ptr<LinkInfo> pjointtarget;
632 if( pequation->hasAttribute(
"target") ) {
633 pjointtarget = _getJointFromRef(pequation->getAttribute(
"target").c_str(),pf,pkinbody).first;
636 std::string eq = _ExtractMathML(pf,pkinbody,children[0]);
637 if( ftargetunit != 1 ) {
638 eq = str(boost::format(
"%f*(%s)")%ftargetunit%eq);
640 if( equationtype ==
"position" ) {
641 COLLADALOG_WARN(str(boost::format(
"cannot set joint %s position equation: %s!")%pjoint->name%eq));
643 else if( equationtype ==
"first_partial" ) {
644 if( !pjointtarget ) {
645 COLLADALOG_WARN(str(boost::format(
"first_partial equation '%s' needs a target attribute! ignoring...")%eq));
648 COLLADALOG_WARN(str(boost::format(
"cannot set joint %s first partial equation: d %s=%s!")%pjoint->name%pjointtarget->name%eq));
650 else if( equationtype ==
"second_partial" ) {
651 if( !pjointtarget ) {
652 COLLADALOG_WARN(str(boost::format(
"second_partial equation '%s' needs a target attribute! ignoring...")%eq));
655 COLLADALOG_WARN(str(boost::format(
"cannot set joint %s second partial equation: d^2 %s = %s!")%pjoint->name%pjointtarget->name%eq));
658 COLLADALOG_WARN(str(boost::format(
"unknown equation type %s")%equationtype));
661 catch(
const ModelLoader::ModelLoaderException& ex) {
662 COLLADALOG_WARN(str(boost::format(
"failed to parse formula %s for target %s")%equationtype%pjoint->name));
667 else if (!!pf->getTechnique_common()) {
669 for(
size_t ic = 0; ic < children.getCount(); ++ic) {
670 string eq = _ExtractMathML(pf,pkinbody,children[ic]);
671 if( ftargetunit != 1 ) {
672 eq = str(boost::format(
"%f*(%s)")%ftargetunit%eq);
674 if( eq.size() > 0 ) {
675 COLLADALOG_WARN(str(boost::format(
"cannot set joint %s position equation: %s!")%pjoint->name%eq));
680 catch(
const ModelLoader::ModelLoaderException& ex) {
681 COLLADALOG_WARN(str(boost::format(
"failed to parse formula for target %s: %s")%pjoint->name%ex.description));
687 for(
size_t ie = 0; ie < kmodel->getExtra_array().getCount(); ++ie) {
688 domExtraRef pextra = kmodel->getExtra_array()[ie];
689 if( strcmp(pextra->getType(),
"collision") == 0 ) {
690 domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array());
692 for(
size_t ic = 0; ic < tec->getContents().getCount(); ++ic) {
693 daeElementRef pelt = tec->getContents()[ic];
694 if( pelt->getElementName() ==
string(
"ignore_link_pair") ) {
695 domLinkRef pdomlink0 = daeSafeCast<domLink>(daeSidRef(pelt->getAttribute(
"link0"), kmodel).resolve().elt);
696 domLinkRef pdomlink1 = daeSafeCast<domLink>(daeSidRef(pelt->getAttribute(
"link1"), kmodel).resolve().elt);
697 if( !pdomlink0 || !pdomlink1 ) {
698 COLLADALOG_WARN(str(boost::format(
"failed to reference <ignore_link_pair> links: %s %s")%pelt->getAttribute(
"link0")%pelt->getAttribute(
"link1")));
701 COLLADALOG_INFO(str(boost::format(
"need to specifying ignore link pair %s:%s")%_ExtractLinkName(pdomlink0)%_ExtractLinkName(pdomlink1)));
703 else if( pelt->getElementName() ==
string(
"bind_instance_geometry") ) {
715 for(std::map<std::string,boost::shared_ptr<LinkInfo> >::iterator it = _mapJointIds.begin(); it != _mapJointIds.end(); ++it) {
716 string linkname(CORBA::String_var(it->second->name));
717 if( linkname ==
name ) {
721 return boost::shared_ptr<LinkInfo>();
726 const std::list<JointAxisBinding>& listAxisBindings = bindings.
listAxisBindings;
729 std::string linkname;
731 linkname = _ExtractLinkName(pdomlink);
732 if( linkname.size() == 0 ) {
736 if( linkname.size() == 0 ) {
738 if (!!pdomnode->getName()) {
739 linkname = _ConvertToValidName(pdomnode->getName());
741 if( linkname.size() == 0 && !!pdomnode->getID()) {
742 linkname = _ConvertToValidName(pdomnode->getID());
747 boost::shared_ptr<LinkInfo> plink(
new LinkInfo());
748 plink->parentIndex = -1;
751 plink->centerOfMass[0] = plink->centerOfMass[1] = plink->centerOfMass[2] = 0;
752 plink->inertia[0] = plink->inertia[4] = plink->inertia[8] = 1;
753 plink->jointValue = 0;
754 _mapLinkNames[linkname] = plink;
755 plink->name = CORBA::string_dup(linkname.c_str());
756 plink->jointType = CORBA::string_dup(
"free");
757 int ilinkindex = (
int)_veclinks.size();
758 _veclinks.push_back(plink);
759 _veclinknames.push_back(linkname);
762 COLLADALOG_VERBOSE(str(boost::format(
"Node Id %s and Name %s")%pdomnode->getId()%pdomnode->getName()));
766 domInstance_rigid_bodyRef irigidbody;
767 domRigid_bodyRef rigidbody;
768 domInstance_rigid_constraintRef irigidconstraint;
770 if( !!pdomnode->getID() && !!itlinkbinding->node->getID() && strcmp(pdomnode->getID(),itlinkbinding->node->getID()) == 0 ) {
771 irigidbody = itlinkbinding->irigidbody;
772 rigidbody = itlinkbinding->rigidbody;
776 if( !!pdomnode->getID() && !!itconstraintbinding->rigidconstraint->getName() && strcmp(linkname.c_str(),itconstraintbinding->rigidconstraint->getName()) == 0 ) {
777 plink->jointType = CORBA::string_dup(
"fixed");
782 ExtractGeometry(pkinbody,plink,tParentLink,pdomnode,listAxisBindings,std::vector<std::string>());
785 COLLADALOG_DEBUG(str(boost::format(
"Attachment link elements: %d")%pdomlink->getAttachment_full_array().getCount()));
788 _ExtractFullTransform(tlink, pdomlink);
790 DblArray12 tgeomlink;
791 PoseMult(tgeomlink, tParentWorldLink, tlink);
794 ExtractGeometry(pkinbody,plink,tgeomlink,pdomnode,listAxisBindings,std::vector<std::string>());
796 COLLADALOG_DEBUG(str(boost::format(
"After ExtractGeometry Attachment link elements: %d")%pdomlink->getAttachment_full_array().getCount()));
798 if( !!rigidbody && !!rigidbody->getTechnique_common() ) {
799 domRigid_body::domTechnique_commonRef rigiddata = rigidbody->getTechnique_common();
800 if( !!rigiddata->getMass() ) {
801 plink->mass = rigiddata->getMass()->getValue();
803 if( !!rigiddata->getInertia() ) {
804 plink->inertia[0] = rigiddata->getInertia()->getValue()[0];
805 plink->inertia[4] = rigiddata->getInertia()->getValue()[1];
806 plink->inertia[8] = rigiddata->getInertia()->getValue()[2];
808 if( !!rigiddata->getMass_frame() ) {
809 DblArray12 atemp1,atemp2,atemp3,tlocalmass;
812 PoseMult(atemp1, tParentWorldLink, tlink);
816 _ExtractFullTransform(atemp2, rigiddata->getMass_frame());
817 PoseMult(tlocalmass, atemp1, atemp2);
820 plink->centerOfMass[0] = tlocalmass[3];
821 plink->centerOfMass[1] = tlocalmass[7];
822 plink->centerOfMass[2] = tlocalmass[11];
823 if( !!rigiddata->getInertia() ) {
824 DblArray12 temp_i, temp_a, m_inertia, m_result;
825 for (
int i = 0;
i < 12;
i++) { m_inertia[
i] = 0.0; }
826 m_inertia[4*0 + 0] = plink->inertia[0];
827 m_inertia[4*1 + 1] = plink->inertia[4];
828 m_inertia[4*2 + 2] = plink->inertia[8];
829 tlocalmass[3] = 0; tlocalmass[7] = 0; tlocalmass[11] = 0;
831 PoseMult(temp_a, tlocalmass, m_inertia);
834 for(
int i = 0;
i < 3;
i++) {
835 for(
int j = 0; j < 3; j++) {
836 plink->inertia[3*
i + j] = m_result[4*
i + j];
844 for (
size_t iatt = 0; iatt < pdomlink->getAttachment_full_array().getCount(); ++iatt) {
845 domLink::domAttachment_fullRef pattfull = pdomlink->getAttachment_full_array()[iatt];
849 _ExtractFullTransform(tatt,pattfull);
859 daeElement* peltjoint = daeSidRef(pattfull->getJoint(), pattfull).resolve().elt;
861 COLLADALOG_WARN(str(boost::format(
"could not find attached joint %s!")%pattfull->getJoint()));
865 if(
string(pattfull->getJoint()).find(
"./") == 0 ) {
866 jointid = str(boost::format(
"%s/%s")%_ExtractParentId(pattfull)%&pattfull->getJoint()[1]);
869 jointid = pattfull->getJoint();
872 domJointRef pdomjoint = daeSafeCast<domJoint> (peltjoint);
874 domInstance_jointRef pdomijoint = daeSafeCast<domInstance_joint> (peltjoint);
876 pdomjoint = daeSafeCast<domJoint> (pdomijoint->getUrl().getElement().cast());
879 COLLADALOG_WARN(str(boost::format(
"could not cast element <%s> to <joint>!")%peltjoint->getElementName()));
885 if (!pattfull->getLink()) {
886 COLLADALOG_WARN(str(boost::format(
"joint %s needs to be attached to a valid link")%jointid));
891 daeTArray<domAxis_constraintRef> vdomaxes = pdomjoint->getChildrenByType<domAxis_constraint>();
892 domNodeRef pchildnode;
895 for(std::list<JointAxisBinding>::const_iterator itaxisbinding = listAxisBindings.begin(); itaxisbinding != listAxisBindings.end(); ++itaxisbinding) {
896 for (
size_t ic = 0; ic < vdomaxes.getCount(); ++ic) {
898 if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
899 pchildnode = itaxisbinding->visualnode;
908 COLLADALOG_DEBUG(str(boost::format(
"joint %s has no visual binding")%jointid));
912 DblArray12 tnewparent;
915 PoseMult(ttemp, tParentWorldLink, tlink);
918 int ijointindex = ExtractLink(pkinbody, pattfull->getLink(), pchildnode,
920 tatt, vdomjoints, bindings);
921 boost::shared_ptr<LinkInfo> pjoint = _veclinks.at(ijointindex);
922 int cindex = plink->childIndices.length();
923 plink->childIndices.length(cindex+1);
924 plink->childIndices[cindex] = ijointindex;
925 pjoint->parentIndex = ilinkindex;
927 if ( ilinkindex == 0 ){
928 memcpy(tnewparent, tatt,
sizeof(tatt));
931 _ExtractFullTransform(ttemp, pattfull->getLink());
938 if( vdomaxes.getCount() > 1 ) {
939 COLLADALOG_WARN(str(boost::format(
"joint %s has %d degrees of freedom, only 1 DOF is supported")%pjoint->name%vdomaxes.getCount()));
941 else if( vdomaxes.getCount() == 0 ) {
946 std::vector<dReal> vaxisunits(1,
dReal(1));
947 for(std::list<JointAxisBinding>::const_iterator itaxisbinding = listAxisBindings.begin(); itaxisbinding != listAxisBindings.end(); ++itaxisbinding) {
948 if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
949 if( !!itaxisbinding->kinematics_axis_info ) {
950 if( !!itaxisbinding->kinematics_axis_info->getActive() ) {
952 bActive = resolveBool(itaxisbinding->kinematics_axis_info->getActive(),itaxisbinding->kinematics_axis_info);
958 domAxis_constraintRef pdomaxis = vdomaxes[ic];
959 bool bIsRevolute =
false;
960 if( strcmp(pdomaxis->getElementName(),
"revolute") == 0 ) {
961 pjoint->jointType = CORBA::string_dup(
"rotate");
964 else if( strcmp(pdomaxis->getElementName(),
"prismatic") == 0 ) {
965 pjoint->jointType = CORBA::string_dup(
"slide");
966 vaxisunits[ic] = _GetUnitScale(pdomaxis,_fGlobalScale);
969 COLLADALOG_WARN(str(boost::format(
"unsupported joint type: %s")%pdomaxis->getElementName()));
972 _mapJointUnits[pjoint] = vaxisunits;
974 if( !!pdomjoint->getName() ) {
975 jointname = _ConvertToValidName(pdomjoint->getName());
978 jointname = str(boost::format(
"dummy%d")%pjoint->jointId);
980 pjoint->name = CORBA::string_dup(jointname.c_str());
982 if( _mapJointIds.find(jointid) != _mapJointIds.end() ) {
983 COLLADALOG_WARN(str(boost::format(
"jointid '%s' is duplicated!")%jointid));
987 if ( sscanf(jointid.c_str(),
"kmodel1/jointsid%d", &jointsid) ) {
988 pjoint->jointId = jointsid;
990 pjoint->jointId = ijointindex - 1;
992 _mapJointIds[jointid] = pjoint;
993 COLLADALOG_DEBUG(str(boost::format(
"joint %s (%d)")%pjoint->name%pjoint->jointId));
995 domKinematics_axis_infoRef kinematics_axis_info;
996 domMotion_axis_infoRef motion_axis_info;
997 for(std::list<JointAxisBinding>::const_iterator itaxisbinding = listAxisBindings.begin(); itaxisbinding != listAxisBindings.end(); ++itaxisbinding) {
998 if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
999 kinematics_axis_info = itaxisbinding->kinematics_axis_info;
1000 motion_axis_info = itaxisbinding->motion_axis_info;
1007 for(
int i = 0;
i < 3; ++
i) {
1008 len2 += pdomaxis->getAxis()->getValue()[
i] * pdomaxis->getAxis()->getValue()[
i];
1012 DblArray12 trans_joint_to_child;
1013 _ExtractFullTransform(trans_joint_to_child, pattfull->getLink());
1017 double ax = pdomaxis->getAxis()->getValue()[0]*len2;
1018 double ay = pdomaxis->getAxis()->getValue()[1]*len2;
1019 double az = pdomaxis->getAxis()->getValue()[2]*len2;
1020 pjoint->jointAxis[0] = patt[0] * ax + patt[1] * ay + patt[2] * az;
1021 pjoint->jointAxis[1] = patt[4] * ax + patt[5] * ay + patt[6] * az;
1022 pjoint->jointAxis[2] = patt[8] * ax + patt[9] * ay + patt[10] * az;
1023 COLLADALOG_DEBUG(str(boost::format(
"axis: %f %f %f -> %f %f %f")%ax%ay%az%pjoint->jointAxis[0]%pjoint->jointAxis[1]%pjoint->jointAxis[2]));
1026 pjoint->jointAxis[0] = 0;
1027 pjoint->jointAxis[1] = 0;
1028 pjoint->jointAxis[2] = 1;
1032 COLLADALOG_WARN(str(boost::format(
"joint %s has axis: %f %f %f")%jointname%pjoint->jointAxis[0]%pjoint->jointAxis[1]%pjoint->jointAxis[2]));
1034 if( !motion_axis_info ) {
1035 COLLADALOG_WARN(str(boost::format(
"No motion axis info for joint %s")%pjoint->name));
1039 if (!!motion_axis_info) {
1040 if (!!motion_axis_info->getSpeed()) {
1041 pjoint->lvlimit.length(1);
1042 pjoint->uvlimit.length(1);
1043 pjoint->uvlimit[0] = resolveFloat(motion_axis_info->getSpeed(),motion_axis_info);
1044 pjoint->lvlimit[0] = -pjoint->uvlimit[0];
1046 if (!!motion_axis_info->getAcceleration()) {
1051 bool joint_locked =
false;
1052 bool kinematics_limits =
false;
1054 if (!!kinematics_axis_info) {
1055 if (!!kinematics_axis_info->getLocked()) {
1056 joint_locked = resolveBool(kinematics_axis_info->getLocked(),kinematics_axis_info);
1061 pjoint->llimit.length(1);
1062 pjoint->ulimit.length(1);
1063 pjoint->llimit[ic] = 0;
1064 pjoint->ulimit[ic] = 0;
1066 else if (kinematics_axis_info->getLimits()) {
1067 kinematics_limits =
true;
1068 pjoint->llimit.length(1);
1069 pjoint->ulimit.length(1);
1070 dReal fscale = bIsRevolute?(
M_PI/180.0f):_GetUnitScale(kinematics_axis_info,_fGlobalScale);
1071 pjoint->llimit[ic] = fscale*(
dReal)(resolveFloat(kinematics_axis_info->getLimits()->getMin(),kinematics_axis_info));
1072 pjoint->ulimit[ic] = fscale*(
dReal)(resolveFloat(kinematics_axis_info->getLimits()->getMax(),kinematics_axis_info));
1077 if (!kinematics_axis_info || (!joint_locked && !kinematics_limits)) {
1079 if( !!pdomaxis->getLimits() ) {
1080 dReal fscale = bIsRevolute?(
M_PI/180.0f):_GetUnitScale(pdomaxis,_fGlobalScale);
1081 pjoint->llimit.length(1);
1082 pjoint->ulimit.length(1);
1083 pjoint->llimit[ic] = (
dReal)pdomaxis->getLimits()->getMin()->getValue()*fscale;
1084 pjoint->ulimit[ic] = (
dReal)pdomaxis->getLimits()->getMax()->getValue()*fscale;
1087 COLLADALOG_VERBOSE(str(boost::format(
"There are NO LIMITS in joint %s:%d ...")%pjoint->name%kinematics_limits));
1091 if( pdomlink->getAttachment_start_array().getCount() > 0 ) {
1092 COLLADALOG_WARN(
"openrave collada reader does not support attachment_start");
1094 if( pdomlink->getAttachment_end_array().getCount() > 0 ) {
1095 COLLADALOG_WARN(
"openrave collada reader does not support attachment_end");
1104 bool ExtractGeometry(
BodyInfoCollada_impl* pkinbody, boost::shared_ptr<LinkInfo> plink,
const DblArray12& tlink,
const domNodeRef pdomnode,
const std::list<JointAxisBinding>& listAxisBindings,
const std::vector<std::string>& vprocessednodes)
1107 COLLADALOG_WARN(str(boost::format(
"fail to ExtractGeometry(LinkInfo,plink,tlink,pdomnode) of %s")%plink->name));
1110 if( !!pdomnode->getID() && find(vprocessednodes.begin(),vprocessednodes.end(),pdomnode->getID()) != vprocessednodes.end() ) {
1111 COLLADALOG_WARN(str(boost::format(
"could not create geometry type pnode getid %s")%pdomnode->getID()));
1115 COLLADALOG_VERBOSE(str(boost::format(
"ExtractGeometry(node,link) of %s")%pdomnode->getName()));
1117 bool bhasgeometry =
false;
1119 for (
size_t i = 0;
i < pdomnode->getNode_array().getCount();
i++) {
1121 bool contains=
false;
1122 for(std::list<JointAxisBinding>::const_iterator it = listAxisBindings.begin(); it != listAxisBindings.end(); ++it) {
1124 if ( (pdomnode->getNode_array()[
i]) == (it->visualnode)){
1133 bhasgeometry |= ExtractGeometry(pkinbody, plink, tlink, pdomnode->getNode_array()[
i],listAxisBindings,vprocessednodes);
1140 unsigned int nGeomBefore = plink->shapeIndices.length();
1143 for (
size_t igeom = 0; igeom < pdomnode->getInstance_geometry_array().getCount(); ++igeom) {
1144 domInstance_geometryRef domigeom = pdomnode->getInstance_geometry_array()[igeom];
1145 domGeometryRef domgeom = daeSafeCast<domGeometry> (domigeom->getUrl().getElement());
1147 COLLADALOG_WARN(str(boost::format(
"link %s does not have valid geometry")%plink->name));
1152 map<string, int> mapmaterials;
1153 map<string, int> maptextures;
1154 if (!!domigeom->getBind_material() && !!domigeom->getBind_material()->getTechnique_common()) {
1155 const domInstance_material_Array& matarray = domigeom->getBind_material()->getTechnique_common()->getInstance_material_array();
1156 for (
size_t imat = 0; imat < matarray.getCount(); ++imat) {
1157 domMaterialRef pdommat = daeSafeCast<domMaterial>(matarray[imat]->getTarget().getElement());
1161 _FillMaterial(pkinbody->
materials_[mindex],pdommat);
1162 mapmaterials[matarray[imat]->getSymbol()] = mindex;
1164 if( !!pdommat && !!pdommat->getInstance_effect() ) {
1165 domEffectRef peffect = daeSafeCast<domEffect>(pdommat->getInstance_effect()->getUrl().getElement().cast());
1167 domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast<domProfile_common::domTechnique::domPhong>(peffect->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domPhong::ID())));
1168 if( !!pphong && !!pphong->getDiffuse() && !!pphong->getDiffuse()->getTexture() ) {
1170 daeElementRefArray psamplers = daeSidRef(pphong->getDiffuse()->getTexture()->getTexture(), peffect).resolve().elt->getChildren();
1171 daeElementRef psampler;
1172 for (
size_t i = 0;
i < psamplers.getCount(); ++
i ) {
1173 if ( strcmp(psamplers[
i]->getElementName(),
"sampler2D") == 0 ) {
1174 psampler = psamplers[
i];
1178 domInstance_imageRef pinstanceimage;
1179 for (
size_t i = 0;
i < psampler->getChildren().getCount(); ++
i ) {
1180 if ( strcmp(psampler->getChildren()[
i]->getElementName(),
"instance_image") == 0 ) {
1181 pinstanceimage = daeSafeCast<domInstance_image>(psampler->getChildren()[
i]);
1184 domImageRef
image = daeSafeCast<domImage>(pinstanceimage->getUrl().getElement());
1185 if (
image &&
image->getInit_from() &&
image->getInit_from()->getRef() ) {
1186 int tindex = pkinbody->
textures_.length();
1188 TextureInfo_var texture(
new TextureInfo());
1189 texture->repeatS = 1;
1190 texture->repeatT = 1;
1191 texture->url = string(
image->getInit_from()->getRef()->getValue().path()).c_str();
1193 maptextures[matarray[imat]->getSymbol()] = tindex;
1204 bhasgeometry |= ExtractGeometry(pkinbody, plink, domgeom, mapmaterials, maptextures);
1207 if( !bhasgeometry ) {
1211 DblArray12 tmnodegeom, ttemp1, ttemp2, ttemp3;
1213 getNodeParentTransform(ttemp2, pdomnode);
1215 _ExtractFullTransform(ttemp1, pdomnode);
1218 PoseMult(tmnodegeom, ttemp1, ttemp2);
1223 double x=tmnodegeom[3],y=tmnodegeom[7],z=tmnodegeom[11];
1226 tmnodegeom[3] = x; tmnodegeom[7] = y; tmnodegeom[11] = z;
1229 for(
unsigned int i = nGeomBefore;
i < plink->shapeIndices.length(); ++
i) {
1230 memcpy(plink->shapeIndices[
i].transformMatrix,tmnodegeom,
sizeof(tmnodegeom));
1231 plink->shapeIndices[
i].inlinedShapeTransformMatrixIndex = -1;
1242 bool _ExtractGeometry(
BodyInfoCollada_impl* pkinbody, boost::shared_ptr<LinkInfo> plink,
const domTrianglesRef triRef,
const domVerticesRef vertsRef,
const map<string,int>& mapmaterials,
const map<string,int>& maptextures)
1245 COLLADALOG_WARN(str(boost::format(
"fail to _ExtractGeometry(LinkInfo,Triangles,Vertices) of %s")%plink->name));
1248 int shapeIndex = pkinbody->
shapes_.length();
1249 pkinbody->
shapes_.length(shapeIndex+1);
1250 ShapeInfo& shape = pkinbody->
shapes_[shapeIndex];
1251 shape.primitiveType = SP_MESH;
1253 int lsindex = plink->shapeIndices.length();
1254 plink->shapeIndices.length(lsindex+1);
1255 plink->shapeIndices[lsindex].shapeIndex = shapeIndex;
1259 AppearanceInfo& ainfo = pkinbody->
appearances_[aindex];
1260 ainfo.materialIndex = -1;
1261 ainfo.normalPerVertex = 0;
1263 ainfo.creaseAngle = 0;
1264 ainfo.colorPerVertex = 0;
1265 ainfo.textureIndex = -1;
1266 if( !!triRef->getMaterial() ) {
1267 map<string,int>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
1268 if( itmat != mapmaterials.end() ) {
1269 ainfo.materialIndex = itmat->second;
1272 shape.appearanceIndex = aindex;
1274 size_t triangleIndexStride = 0;
1275 int vertexoffset = -1, normaloffset = -1, texcoordoffset = -1;
1276 domInput_local_offsetRef indexOffsetRef, normalOffsetRef, texcoordOffsetRef;
1278 for (
unsigned int w=0;w<triRef->getInput_array().getCount();w++) {
1279 size_t offset = triRef->getInput_array()[w]->getOffset();
1280 daeString str = triRef->getInput_array()[w]->getSemantic();
1281 if (!strcmp(str,
"VERTEX")) {
1282 indexOffsetRef = triRef->getInput_array()[w];
1283 vertexoffset = offset;
1285 if (!strcmp(str,
"NORMAL")) {
1286 normalOffsetRef = triRef->getInput_array()[w];
1287 normaloffset = offset;
1289 if (!strcmp(str,
"TEXCOORD")) {
1290 texcoordOffsetRef = triRef->getInput_array()[w];
1291 texcoordoffset = offset;
1293 if (offset> triangleIndexStride) {
1294 triangleIndexStride = offset;
1297 triangleIndexStride++;
1299 const domList_of_uints& indexArray =triRef->getP()->getValue();
1300 shape.triangles.length(triRef->getCount()*3);
1301 shape.vertices.length(triRef->getCount()*9);
1304 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();++
i) {
1305 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1306 daeString str = localRef->getSemantic();
1307 if ( strcmp(str,
"POSITION") == 0 ) {
1308 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1312 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1313 const domFloat_arrayRef flArray = node->getFloat_array();
1315 const domList_of_floats& listFloats = flArray->getValue();
1317 int vertexStride = 3;
1319 for(
size_t itri = 0; itri < triRef->getCount(); ++itri) {
1320 if(k+2*triangleIndexStride < indexArray.getCount() ) {
1321 for (
int j=0;j<3;j++) {
1322 int index0 = indexArray.get(k)*vertexStride;
1323 domFloat fl0 = listFloats.get(index0);
1324 domFloat fl1 = listFloats.get(index0+1);
1325 domFloat fl2 = listFloats.get(index0+2);
1326 k+=triangleIndexStride;
1327 shape.triangles[itriangle++] = ivertex/3;
1328 shape.vertices[ivertex++] = fl0*fUnitScale;
1329 shape.vertices[ivertex++] = fl1*fUnitScale;
1330 shape.vertices[ivertex++] = fl2*fUnitScale;
1339 if ( normaloffset >= 0 ) {
1340 const domSourceRef normalNode = daeSafeCast<domSource>(normalOffsetRef->getSource().getElement());
1341 const domFloat_arrayRef normalArray = normalNode->getFloat_array();
1342 const domList_of_floats& normalFloats = normalArray->getValue();
1343 AppearanceInfo& ainfo = pkinbody->
appearances_[shape.appearanceIndex];
1344 ainfo.normalPerVertex = 1;
1345 ainfo.normals.length(triRef->getCount()*9);
1346 int k = normaloffset;
1347 int vertexStride = 3;
1349 for(
size_t itri = 0; itri < triRef->getCount(); ++itri) {
1350 if(k+2*triangleIndexStride < indexArray.getCount() ) {
1351 for (
int j=0;j<3;j++) {
1352 int index0 = indexArray.get(k)*vertexStride;
1353 domFloat fl0 = normalFloats.get(index0);
1354 domFloat fl1 = normalFloats.get(index0+1);
1355 domFloat fl2 = normalFloats.get(index0+2);
1356 k+=triangleIndexStride;
1357 ainfo.normals[ivertex++] = fl0;
1358 ainfo.normals[ivertex++] = fl1;
1359 ainfo.normals[ivertex++] = fl2;
1365 if ( texcoordoffset >= 0 ) {
1366 const domSourceRef texcoordNode = daeSafeCast<domSource>(texcoordOffsetRef->getSource().getElement());
1367 const domFloat_arrayRef texcoordArray = texcoordNode->getFloat_array();
1368 const domList_of_floats& texcoordFloats = texcoordArray->getValue();
1369 AppearanceInfo& ainfo = pkinbody->
appearances_[shape.appearanceIndex];
1370 map<string,int>::const_iterator itmat = maptextures.find(triRef->getMaterial());
1371 if( itmat != maptextures.end() ) {
1372 ainfo.textureIndex = itmat->second;
1374 ainfo.textureCoordinate.length(texcoordArray->getCount());
1375 ainfo.textureCoordIndices.length(triRef->getCount()*3);
1376 int k = texcoordoffset;
1378 for(
size_t itex = 0; itex < texcoordArray->getCount() ; ++itex) {
1379 ainfo.textureCoordinate[itex] = texcoordFloats.get(itex);
1381 for(
size_t itri = 0; itri < triRef->getCount(); ++itri) {
1382 if(k+2*triangleIndexStride < indexArray.getCount() ) {
1383 for (
int j=0;j<3;j++) {
1384 int index0 = indexArray.get(k);
1385 k+=triangleIndexStride;
1386 ainfo.textureCoordIndices[itriangle++] = index0;
1390 for(
int i=0,k=0;
i<3;
i++) {
1391 for(
int j=0; j<3; j++) {
1393 ainfo.textransformMatrix[k++] = 1;
1395 ainfo.textransformMatrix[k++] = 0;
1400 }
else if ( strcmp(str,
"NORMAL") == 0 ) {
1402 const domSourceRef normalNode = daeSafeCast<domSource>(localRef->getSource().getElement());
1406 const domFloat_arrayRef normalArray = normalNode->getFloat_array();
1407 if (!!normalArray) {
1408 const domList_of_floats& normalFloats = normalArray->getValue();
1410 int vertexStride = 3;
1412 AppearanceInfo& ainfo = pkinbody->
appearances_[shape.appearanceIndex];
1413 ainfo.normalPerVertex = 1;
1414 ainfo.normals.length(triRef->getCount()*9);
1415 for(
size_t itri = 0; itri < triRef->getCount(); ++itri) {
1416 if(2*triangleIndexStride < indexArray.getCount() ) {
1417 for (
int j=0;j<3;j++) {
1418 int index0 = indexArray.get(k)*vertexStride;
1419 domFloat fl0 = normalFloats.get(index0);
1420 domFloat fl1 = normalFloats.get(index0+1);
1421 domFloat fl2 = normalFloats.get(index0+2);
1422 k+=triangleIndexStride;
1423 ainfo.normals[ivertex++] = fl0;
1424 ainfo.normals[ivertex++] = fl1;
1425 ainfo.normals[ivertex++] = fl2;
1436 if ( ainfo.normals.length() == 0 ) {
1439 std::vector<Vector3> faceNormals(itriangle/3);
1440 std::vector<std::vector<int> > vertexFaceMapping(itriangle);
1441 for(
int i=0;
i < itriangle/3; ++
i) {
1442 int vIndex1 = shape.triangles[
i*3+0];
1443 int vIndex2 = shape.triangles[
i*3+1];
1444 int vIndex3 = shape.triangles[
i*3+2];
1445 Vector3 a(shape.vertices[vIndex1*3+0]-
1446 shape.vertices[vIndex3*3+0],
1447 shape.vertices[vIndex1*3+1]-
1448 shape.vertices[vIndex3*3+1],
1449 shape.vertices[vIndex1*3+2]-
1450 shape.vertices[vIndex3*3+2]);
1451 Vector3 b(shape.vertices[vIndex1*3+0]-
1452 shape.vertices[vIndex2*3+0],
1453 shape.vertices[vIndex1*3+1]-
1454 shape.vertices[vIndex2*3+1],
1455 shape.vertices[vIndex1*3+2]-
1456 shape.vertices[vIndex2*3+2]);
1460 faceNormals[
i] =
c.normalized();
1461 vertexFaceMapping[vIndex1].push_back(
i);
1462 vertexFaceMapping[vIndex2].push_back(
i);
1463 vertexFaceMapping[vIndex3].push_back(
i);
1466 ainfo.normalPerVertex = 1;
1467 ainfo.normals.length(itriangle*3);
1468 double creaseAngle =
M_PI/4;
1469 for (
int i=0;
i<itriangle/3;
i++){
1470 const Vector3 ¤tFaceNormal = faceNormals[
i];
1471 for (
int vertex=0; vertex<3; vertex++){
1472 bool normalIsFaceNormal =
true;
1473 int vIndex = shape.triangles[
i*3+vertex];
1474 Vector3 normal = currentFaceNormal;
1475 const std::vector<int>& faces = vertexFaceMapping[vIndex];
1476 for (
size_t k=0; k<faces.size(); k++){
1477 const Vector3& adjoingFaceNormal = faceNormals[k];
1478 double angle = acos(currentFaceNormal.dot(adjoingFaceNormal) /
1479 (currentFaceNormal.norm() * adjoingFaceNormal.norm()));
1480 if(angle > 1.0e-6 && angle < creaseAngle){
1481 normal += adjoingFaceNormal;
1482 normalIsFaceNormal =
false;
1485 if (!normalIsFaceNormal){
1488 ainfo.normals[vIndex*3 ] = normal[0];
1489 ainfo.normals[vIndex*3+1] = normal[1];
1490 ainfo.normals[vIndex*3+2] = normal[2];
1495 if( itriangle != 3*(
int)triRef->getCount() ) {
1506 bool _ExtractGeometry(
BodyInfoCollada_impl* pkinbody, boost::shared_ptr<LinkInfo> plink,
const domTrifansRef triRef,
const domVerticesRef vertsRef,
const map<string,int>& mapmaterials,
const map<string,int>& maptextures)
1509 COLLADALOG_WARN(str(boost::format(
"fail to _ExtractGeometry(LinkInfo,Trifans,Vertices) of %s")%plink->name));
1512 int shapeIndex = pkinbody->
shapes_.length();
1513 pkinbody->
shapes_.length(shapeIndex+1);
1514 ShapeInfo& shape = pkinbody->
shapes_[shapeIndex];
1515 shape.primitiveType = SP_MESH;
1516 int lsindex = plink->shapeIndices.length();
1517 plink->shapeIndices.length(lsindex+1);
1518 plink->shapeIndices[lsindex].shapeIndex = shapeIndex;
1521 shape.appearanceIndex = -1;
1522 if( !!triRef->getMaterial() ) {
1523 map<string,int>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
1524 if( itmat != mapmaterials.end() ) {
1525 shape.appearanceIndex = itmat->second;
1529 size_t triangleIndexStride = 0, vertexoffset = -1;
1530 domInput_local_offsetRef indexOffsetRef;
1532 for (
unsigned int w=0;w<triRef->getInput_array().getCount();w++) {
1533 size_t offset = triRef->getInput_array()[w]->getOffset();
1534 daeString str = triRef->getInput_array()[w]->getSemantic();
1535 if (!strcmp(str,
"VERTEX")) {
1536 indexOffsetRef = triRef->getInput_array()[w];
1537 vertexoffset = offset;
1539 if (offset> triangleIndexStride) {
1540 triangleIndexStride = offset;
1543 triangleIndexStride++;
1544 size_t primitivecount = triRef->getCount();
1545 if( primitivecount > triRef->getP_array().getCount() ) {
1547 primitivecount = triRef->getP_array().getCount();
1549 int itriangle = 0, ivertex = 0;
1550 for(
size_t ip = 0; ip < primitivecount; ++ip) {
1551 domList_of_uints indexArray =triRef->getP_array()[ip]->getValue();
1552 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();++
i) {
1553 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1554 daeString str = localRef->getSemantic();
1555 if ( strcmp(str,
"POSITION") == 0 ) {
1556 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1560 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1561 const domFloat_arrayRef flArray = node->getFloat_array();
1563 const domList_of_floats& listFloats = flArray->getValue();
1565 int vertexStride = 3;
1566 size_t usedindices = 3*(indexArray.getCount()-2);
1567 shape.triangles.length(shape.triangles.length()+usedindices);
1568 shape.vertices.length(shape.vertices.length()+3*indexArray.getCount());
1569 size_t startoffset = ivertex/3;
1570 while(k < (
int)indexArray.getCount() ) {
1571 int index0 = indexArray.get(k)*vertexStride;
1572 domFloat fl0 = listFloats.get(index0);
1573 domFloat fl1 = listFloats.get(index0+1);
1574 domFloat fl2 = listFloats.get(index0+2);
1575 k+=triangleIndexStride;
1576 shape.vertices[ivertex++] = fl0*fUnitScale;
1577 shape.vertices[ivertex++] = fl1*fUnitScale;
1578 shape.vertices[ivertex++] = fl2*fUnitScale;
1580 for(
size_t ivert = 2; ivert < indexArray.getCount(); ++ivert) {
1581 shape.triangles[itriangle++] = startoffset;
1582 shape.triangles[itriangle++] = startoffset+ivert-1;
1583 shape.triangles[itriangle++] = startoffset+ivert;
1601 bool _ExtractGeometry(
BodyInfoCollada_impl* pkinbody, boost::shared_ptr<LinkInfo> plink,
const domTristripsRef triRef,
const domVerticesRef vertsRef,
const map<string,int>& mapmaterials,
const map<string,int>& maptextures)
1604 COLLADALOG_WARN(str(boost::format(
"fail to _ExtractGeometry(LinkInfo,Tristrips,Vertices) of %s")%plink->name));
1607 int shapeIndex = pkinbody->
shapes_.length();
1608 pkinbody->
shapes_.length(shapeIndex+1);
1609 ShapeInfo& shape = pkinbody->
shapes_[shapeIndex];
1610 shape.primitiveType = SP_MESH;
1611 int lsindex = plink->shapeIndices.length();
1612 plink->shapeIndices.length(lsindex+1);
1613 plink->shapeIndices[lsindex].shapeIndex = shapeIndex;
1616 shape.appearanceIndex = -1;
1617 if( !!triRef->getMaterial() ) {
1618 map<string,int>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
1619 if( itmat != mapmaterials.end() ) {
1620 shape.appearanceIndex = itmat->second;
1624 size_t triangleIndexStride = 0, vertexoffset = -1;
1625 domInput_local_offsetRef indexOffsetRef;
1627 for (
unsigned int w=0;w<triRef->getInput_array().getCount();w++) {
1628 size_t offset = triRef->getInput_array()[w]->getOffset();
1629 daeString str = triRef->getInput_array()[w]->getSemantic();
1630 if (!strcmp(str,
"VERTEX")) {
1631 indexOffsetRef = triRef->getInput_array()[w];
1632 vertexoffset = offset;
1634 if (offset> triangleIndexStride) {
1635 triangleIndexStride = offset;
1638 triangleIndexStride++;
1639 size_t primitivecount = triRef->getCount();
1640 if( primitivecount > triRef->getP_array().getCount() ) {
1642 primitivecount = triRef->getP_array().getCount();
1644 int itriangle = 0, ivertex = 0;
1645 for(
size_t ip = 0; ip < primitivecount; ++ip) {
1646 domList_of_uints indexArray = triRef->getP_array()[ip]->getValue();
1647 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();++
i) {
1648 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1649 daeString str = localRef->getSemantic();
1650 if ( strcmp(str,
"POSITION") == 0 ) {
1651 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1655 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1656 const domFloat_arrayRef flArray = node->getFloat_array();
1658 const domList_of_floats& listFloats = flArray->getValue();
1660 int vertexStride = 3;
1661 size_t usedindices = 3*(indexArray.getCount()-2);
1662 shape.triangles.length(shape.triangles.length()+usedindices);
1663 shape.vertices.length(shape.vertices.length()+3*indexArray.getCount());
1664 size_t startoffset = ivertex/3;
1665 while(k < (
int)indexArray.getCount() ) {
1666 int index0 = indexArray.get(k)*vertexStride;
1667 domFloat fl0 = listFloats.get(index0);
1668 domFloat fl1 = listFloats.get(index0+1);
1669 domFloat fl2 = listFloats.get(index0+2);
1670 k+=triangleIndexStride;
1671 shape.vertices[ivertex++] = fl0*fUnitScale;
1672 shape.vertices[ivertex++] = fl1*fUnitScale;
1673 shape.vertices[ivertex++] = fl2*fUnitScale;
1677 for(
size_t ivert = 2; ivert < indexArray.getCount(); ++ivert) {
1678 shape.triangles[itriangle++] = startoffset-2;
1679 shape.triangles[itriangle++] = bFlip ? startoffset+ivert : startoffset+ivert-1;
1680 shape.triangles[itriangle++] = bFlip ? startoffset+ivert-1 : startoffset+ivert;
1699 bool _ExtractGeometry(
BodyInfoCollada_impl* pkinbody, boost::shared_ptr<LinkInfo> plink,
const domPolylistRef triRef,
const domVerticesRef vertsRef,
const map<string,int>& mapmaterials,
const map<string,int>& maptextures)
1702 COLLADALOG_WARN(str(boost::format(
"fail to _ExtractGeometry(LinkInfo,Polylist,VErtices) of %s")%plink->name));
1705 int shapeIndex = pkinbody->
shapes_.length();
1706 pkinbody->
shapes_.length(shapeIndex+1);
1707 ShapeInfo& shape = pkinbody->
shapes_[shapeIndex];
1708 shape.primitiveType = SP_MESH;
1709 int lsindex = plink->shapeIndices.length();
1710 plink->shapeIndices.length(lsindex+1);
1711 plink->shapeIndices[lsindex].shapeIndex = shapeIndex;
1714 shape.appearanceIndex = -1;
1715 if( !!triRef->getMaterial() ) {
1716 map<string,int>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
1717 if( itmat != mapmaterials.end() ) {
1718 shape.appearanceIndex = itmat->second;
1722 size_t triangleIndexStride = 0,vertexoffset = -1;
1723 domInput_local_offsetRef indexOffsetRef;
1724 for (
unsigned int w=0;w<triRef->getInput_array().getCount();w++) {
1725 size_t offset = triRef->getInput_array()[w]->getOffset();
1726 daeString str = triRef->getInput_array()[w]->getSemantic();
1727 if (!strcmp(str,
"VERTEX")) {
1728 indexOffsetRef = triRef->getInput_array()[w];
1729 vertexoffset = offset;
1731 if (offset> triangleIndexStride) {
1732 triangleIndexStride = offset;
1735 triangleIndexStride++;
1736 const domList_of_uints& indexArray =triRef->getP()->getValue();
1737 int ivertex = 0, itriangle=0;
1738 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();++
i) {
1739 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1740 daeString str = localRef->getSemantic();
1741 if ( strcmp(str,
"POSITION") == 0 ) {
1742 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1746 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1747 const domFloat_arrayRef flArray = node->getFloat_array();
1749 const domList_of_floats& listFloats = flArray->getValue();
1750 size_t k=vertexoffset;
1751 int vertexStride = 3;
1752 for(
size_t ipoly = 0; ipoly < triRef->getVcount()->getValue().getCount(); ++ipoly) {
1753 size_t numverts = triRef->getVcount()->getValue()[ipoly];
1754 if(numverts > 0 && k+(numverts-1)*triangleIndexStride < indexArray.getCount() ) {
1755 size_t startoffset = ivertex/3;
1756 shape.vertices.length(shape.vertices.length()+3*numverts);
1757 shape.triangles.length(shape.triangles.length()+3*(numverts-2));
1758 for (
size_t j=0;j<numverts;j++) {
1759 int index0 = indexArray.get(k)*vertexStride;
1760 domFloat fl0 = listFloats.get(index0);
1761 domFloat fl1 = listFloats.get(index0+1);
1762 domFloat fl2 = listFloats.get(index0+2);
1763 k+=triangleIndexStride;
1764 shape.vertices[ivertex++] = fl0*fUnitScale;
1765 shape.vertices[ivertex++] = fl1*fUnitScale;
1766 shape.vertices[ivertex++] = fl2*fUnitScale;
1768 for(
size_t ivert = 2; ivert < numverts; ++ivert) {
1769 shape.triangles[itriangle++] = startoffset;
1770 shape.triangles[itriangle++] = startoffset+ivert-1;
1771 shape.triangles[itriangle++] = startoffset+ivert;
1792 COLLADALOG_WARN(str(boost::format(
"fail to ExtractGeometry(plink,geom) of %s")%plink->name));
1795 std::vector<Vector3> vconvexhull;
1796 if (geom->getMesh()) {
1797 const domMeshRef meshRef = geom->getMesh();
1798 for (
size_t tg = 0;tg<meshRef->getTriangles_array().getCount();tg++) {
1799 _ExtractGeometry(pkinbody, plink, meshRef->getTriangles_array()[tg], meshRef->getVertices(), mapmaterials, maptextures);
1801 for (
size_t tg = 0;tg<meshRef->getTrifans_array().getCount();tg++) {
1802 _ExtractGeometry(pkinbody, plink, meshRef->getTrifans_array()[tg], meshRef->getVertices(), mapmaterials, maptextures);
1804 for (
size_t tg = 0;tg<meshRef->getTristrips_array().getCount();tg++) {
1805 _ExtractGeometry(pkinbody, plink, meshRef->getTristrips_array()[tg], meshRef->getVertices(), mapmaterials, maptextures);
1807 for (
size_t tg = 0;tg<meshRef->getPolylist_array().getCount();tg++) {
1808 _ExtractGeometry(pkinbody, plink, meshRef->getPolylist_array()[tg], meshRef->getVertices(), mapmaterials, maptextures);
1810 if( meshRef->getPolygons_array().getCount()> 0 ) {
1845 else if (geom->getConvex_mesh()) {
1847 const domConvex_meshRef convexRef = geom->getConvex_mesh();
1848 daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement();
1849 if ( !!otherElemRef ) {
1850 domGeometryRef linkedGeom = *(domGeometryRef*)&otherElemRef;
1854 COLLADALOG_WARN(str(boost::format(
"convexMesh polyCount = %d")%(
int)convexRef->getPolygons_array().getCount()));
1855 COLLADALOG_WARN(str(boost::format(
"convexMesh triCount = %d")%(
int)convexRef->getTriangles_array().getCount()));
1859 const domConvex_meshRef convexRef = geom->getConvex_mesh();
1861 daeString urlref2 = convexRef->getConvex_hull_of().getOriginalURI();
1863 daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement();
1866 for (
size_t i = 0;
i < _dom->getLibrary_geometries_array().getCount();
i++) {
1867 domLibrary_geometriesRef libgeom = _dom->getLibrary_geometries_array()[
i];
1868 for (
size_t i = 0;
i < libgeom->getGeometry_array().getCount();
i++) {
1869 domGeometryRef lib = libgeom->getGeometry_array()[
i];
1870 if (!strcmp(lib->getId(),urlref2+1)) {
1872 domMesh *meshElement = lib->getMesh();
1874 const domVerticesRef vertsRef = meshElement->getVertices();
1875 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();
i++) {
1876 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1877 daeString str = localRef->getSemantic();
1878 if ( strcmp(str,
"POSITION") == 0) {
1879 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1883 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1884 const domFloat_arrayRef flArray = node->getFloat_array();
1886 vconvexhull.reserve(vconvexhull.size()+flArray->getCount());
1887 const domList_of_floats& listFloats = flArray->getValue();
1888 for (
size_t k=0;k+2<flArray->getCount();k+=3) {
1889 domFloat fl0 = listFloats.get(k);
1890 domFloat fl1 = listFloats.get(k+1);
1891 domFloat fl2 = listFloats.get(k+2);
1892 vconvexhull.push_back(
Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
1904 const domVerticesRef vertsRef = convexRef->getVertices();
1905 for (
size_t i=0;
i<vertsRef->getInput_array().getCount();
i++) {
1906 domInput_localRef localRef = vertsRef->getInput_array()[
i];
1907 daeString str = localRef->getSemantic();
1908 if ( strcmp(str,
"POSITION") == 0 ) {
1909 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
1913 dReal fUnitScale = _GetUnitScale(node,_fGlobalScale);
1914 const domFloat_arrayRef flArray = node->getFloat_array();
1916 const domList_of_floats& listFloats = flArray->getValue();
1917 vconvexhull.reserve(vconvexhull.size()+flArray->getCount());
1918 for (
size_t k=0;k+2<flArray->getCount();k+=3) {
1919 domFloat fl0 = listFloats.get(k);
1920 domFloat fl1 = listFloats.get(k+1);
1921 domFloat fl2 = listFloats.get(k+2);
1922 vconvexhull.push_back(
Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
1929 if( vconvexhull.size()> 0 ) {
1948 mat.ambientIntensity = 0.1;
1949 mat.diffuseColor[0] = 0.8; mat.diffuseColor[1] = 0.8; mat.diffuseColor[2] = 0.8;
1950 mat.emissiveColor[0] = 0; mat.emissiveColor[1] = 0; mat.emissiveColor[2] = 0;
1952 mat.specularColor[0] = 0; mat.specularColor[1] = 0; mat.specularColor[2] = 0;
1953 mat.transparency = 0;
1954 if( !!pdommat && !!pdommat->getInstance_effect() ) {
1955 domEffectRef peffect = daeSafeCast<domEffect>(pdommat->getInstance_effect()->getUrl().getElement().cast());
1957 domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast<domProfile_common::domTechnique::domPhong>(peffect->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domPhong::ID())));
1959 if( !!pphong->getAmbient() && !!pphong->getAmbient()->getColor() ) {
1960 domFx_color
c = pphong->getAmbient()->getColor()->getValue();
1961 mat.ambientIntensity = (fabs(
c[0])+fabs(
c[1])+fabs(
c[2]))/3;
1963 if( !!pphong->getDiffuse() && !!pphong->getDiffuse()->getColor() ) {
1964 domFx_color
c = pphong->getDiffuse()->getColor()->getValue();
1965 mat.diffuseColor[0] =
c[0];
1966 mat.diffuseColor[1] =
c[1];
1967 mat.diffuseColor[2] =
c[2];
1970 domProfile_common::domTechnique::domLambertRef plambert = daeSafeCast<domProfile_common::domTechnique::domLambert>(peffect->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domLambert::ID())));
1972 if( !!plambert->getAmbient() && !!plambert->getAmbient()->getColor() ) {
1973 domFx_color
c = plambert->getAmbient()->getColor()->getValue();
1974 mat.ambientIntensity = (fabs(
c[0])+fabs(
c[1])+fabs(
c[2]))/3;
1976 if( !!plambert->getDiffuse() && !!plambert->getDiffuse()->getColor() ) {
1977 domFx_color
c = plambert->getDiffuse()->getColor()->getValue();
1978 mat.diffuseColor[0] =
c[0];
1979 mat.diffuseColor[1] =
c[1];
1980 mat.diffuseColor[2] =
c[2];
1990 for(
size_t ie = 0; ie < as->getExtra_array().getCount(); ++ie) {
1991 domExtraRef pextra = as->getExtra_array()[ie];
1992 if( strcmp(pextra->getType(),
"manipulator") == 0 ) {
1993 string name = pextra->getAttribute(
"name");
1994 if(
name.size() == 0 ) {
1995 name = str(boost::format(
"manipulator%d")%_nGlobalManipulatorId++);
1997 domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array());
2011 for (
size_t ie = 0; ie < as->getExtra_array().getCount(); ie++) {
2012 domExtraRef pextra = as->getExtra_array()[ie];
2013 if( strcmp(pextra->getType(),
"attach_sensor") == 0 ) {
2014 string name = pextra->getAttribute(
"name");
2015 if(
name.size() == 0 ) {
2016 name = str(boost::format(
"sensor%d")%_nGlobalSensorId++);
2018 domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array());
2020 daeElement* pframe_origin = tec->getChild(
"frame_origin");
2021 if( !!pframe_origin ) {
2022 domLinkRef pdomlink = daeSafeCast<domLink>(daeSidRef(pframe_origin->getAttribute(
"link"), as).resolve().elt);
2023 SensorInfo_var psensor(
new SensorInfo());
2024 psensor->name = CORBA::string_dup(
name.c_str() );
2025 boost::shared_ptr<LinkInfo> plink;
2026 if( _mapLinkNames.find(_ExtractLinkName(pdomlink)) != _mapLinkNames.end() ) {
2027 plink = _mapLinkNames[_ExtractLinkName(pdomlink)];
2029 COLLADALOG_WARN(str(boost::format(
"unknown joint %s")%_ExtractLinkName(pdomlink)));
2032 if( plink && _ExtractSensor(psensor,tec->getChild(
"instance_sensor")) ) {
2035 _ExtractFullTransformFromChildren(ttemp, pframe_origin);
2037 if (
string(psensor->type) ==
"Vision" ) {
2039 DblArray12 rotation, ttemp2;
2048 int numSensors = plink->sensors.length();
2049 plink->sensors.length(numSensors + 1);
2050 plink->sensors[numSensors] = psensor;
2066 for (
size_t ie = 0; ie < as->getExtra_array().getCount(); ie++) {
2067 domExtraRef pextra = as->getExtra_array()[ie];
2068 if( strcmp(pextra->getType(),
"attach_actuator") == 0 ) {
2069 string name = pextra->getAttribute(
"name");
2070 if(
name.size() == 0 ) {
2071 name = str(boost::format(
"actuator%d")%_nGlobalActuatorId++);
2073 domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array());
2075 if ( GetLink(
name) && _ExtractActuator(GetLink(
name), tec->getChild(
"instance_actuator")) ) {
2090 if( !instance_sensor ) {
2094 if( !instance_sensor->hasAttribute(
"url") ) {
2099 std::string instance_id = instance_sensor->getAttribute(
"id");
2100 std::string instance_url = instance_sensor->getAttribute(
"url");
2101 daeElementRef domsensor = _getElementFromUrl(daeURI(*instance_sensor,instance_url));
2103 COLLADALOG_WARN(str(boost::format(
"failed to find senor id %s url=%s")%instance_id%instance_url));
2106 if( !domsensor->hasAttribute(
"type") ) {
2110 if ( domsensor->hasAttribute(
"sid")) {
2111 psensor.id = boost::lexical_cast<int>(domsensor->getAttribute(
"sid"));
2115 std::string sensortype = domsensor->getAttribute(
"type");
2116 if ( sensortype ==
"base_imu" ) {
2117 psensor.specValues.length( CORBA::ULong(3) );
2118 daeElement *max_angular_velocity = domsensor->getChild(
"max_angular_velocity");
2119 daeElement *max_acceleration = domsensor->getChild(
"max_acceleration");
2120 if ( !! max_angular_velocity ) {
2121 istringstream ins(max_angular_velocity->getCharData());
2122 ins >> psensor.specValues[0] >> psensor.specValues[1] >> psensor.specValues[2];
2123 psensor.type = CORBA::string_dup(
"RateGyro" );
2124 }
else if ( !! max_acceleration ) {
2125 istringstream ins(max_acceleration->getCharData());
2126 ins >> psensor.specValues[0] >> psensor.specValues[1] >> psensor.specValues[2];
2127 psensor.type = CORBA::string_dup(
"Acceleration" );
2129 COLLADALOG_WARN(str(boost::format(
"couldn't find max_angular_velocity nor max_acceleration%s")%sensortype));
2133 if ( sensortype ==
"base_pinhole_camera" ) {
2134 psensor.type = CORBA::string_dup(
"Vision" );
2135 psensor.specValues.length( CORBA::ULong(7) );
2138 psensor.specValues[1] = 10;
2144 daeElement *measurement_time = domsensor->getChild(
"measurement_time");
2145 if ( !! measurement_time ) {
2146 psensor.specValues[6] = 1.0/(boost::lexical_cast<double>(measurement_time->getCharData()));
2148 COLLADALOG_WARN(str(boost::format(
"couldn't find measurement_time %s")%sensortype));
2150 daeElement *focal_length = domsensor->getChild(
"focal_length");
2151 if ( !! focal_length ) {
2152 psensor.specValues[0] = boost::lexical_cast<double>(focal_length->getCharData());
2154 COLLADALOG_WARN(str(boost::format(
"couldn't find focal_length %s")%sensortype));
2155 psensor.specValues[0] = 0.1;
2157 daeElement *image_format = domsensor->getChild(
"format");
2158 std::string string_format =
"uint8";
2159 if ( !! image_format ) {
2160 string_format = image_format->getCharData();
2162 daeElement *intrinsic = domsensor->getChild(
"intrinsic");
2163 if ( !! intrinsic ) {
2164 istringstream ins(intrinsic->getCharData());
2165 float f0,f1,f2,f3,f4,f5;
2166 ins >> f0 >> f1 >> f2 >> f3 >> f4 >> f5;
2167 psensor.specValues[2] = atan( f2 / f0) * 2.0;
2169 COLLADALOG_WARN(str(boost::format(
"couldn't find intrinsic %s")%sensortype));
2170 psensor.specValues[2] = 0.785398;
2172 daeElement *image_dimensions = domsensor->getChild(
"image_dimensions");
2173 if ( !! image_dimensions ) {
2174 istringstream ins(image_dimensions->getCharData());
2176 ins >> psensor.specValues[4] >> psensor.specValues[5] >> ichannel;
2179 if ( string_format ==
"uint8") {
2180 psensor.specValues[3] = OpenHRP::Camera::MONO;
2181 }
else if ( string_format ==
"float32") {
2182 psensor.specValues[3] = OpenHRP::Camera::DEPTH;
2184 COLLADALOG_WARN(str(boost::format(
"unknown image format %s %d")%string_format%ichannel));
2188 if ( string_format ==
"float32") {
2189 psensor.specValues[3] = OpenHRP::Camera::MONO_DEPTH;
2191 COLLADALOG_WARN(str(boost::format(
"unknown image format %s %d")%string_format%ichannel));
2195 if ( string_format ==
"uint8") {
2196 psensor.specValues[3] = OpenHRP::Camera::COLOR;
2198 COLLADALOG_WARN(str(boost::format(
"unknown image format %s %d")%string_format%ichannel));
2202 if ( string_format ==
"float32") {
2203 psensor.specValues[3] = OpenHRP::Camera::COLOR_DEPTH;
2205 COLLADALOG_WARN(str(boost::format(
"unknown image format %s %d")%string_format%ichannel));
2209 COLLADALOG_WARN(str(boost::format(
"unknown image format %s %d")%string_format%ichannel));
2213 COLLADALOG_WARN(str(boost::format(
"couldn't find image_dimensions %s")%sensortype));
2214 psensor.specValues[4] = 320;
2215 psensor.specValues[5] = 240;
2219 if ( sensortype ==
"base_force6d" ) {
2220 psensor.type = CORBA::string_dup(
"Force" );
2221 psensor.specValues.length( CORBA::ULong(6) );
2222 daeElement *max_force = domsensor->getChild(
"load_range_force");
2223 if ( !! max_force ) {
2224 istringstream ins(max_force->getCharData());
2225 ins >> psensor.specValues[0] >> psensor.specValues[1] >> psensor.specValues[2];
2227 COLLADALOG_WARN(str(boost::format(
"couldn't find load_range_force %s")%sensortype));
2229 daeElement *max_torque = domsensor->getChild(
"load_range_torque");
2230 if ( !! max_torque ) {
2231 istringstream ins(max_torque->getCharData());
2232 ins >> psensor.specValues[3] >> psensor.specValues[4] >> psensor.specValues[5];
2234 COLLADALOG_WARN(str(boost::format(
"couldn't findload_range_torque %s")%sensortype));
2238 if ( sensortype ==
"base_laser1d" ) {
2239 psensor.type = CORBA::string_dup(
"Range" );
2240 psensor.specValues.length( CORBA::ULong(4) );
2241 daeElement *scan_angle = domsensor->getChild(
"angle_range");
2242 if ( !! scan_angle ) {
2243 psensor.specValues[0] = boost::lexical_cast<double>(scan_angle->getCharData());
2245 COLLADALOG_WARN(str(boost::format(
"couldn't find angle_range %s")%sensortype));
2247 daeElement *scan_step = domsensor->getChild(
"angle_increment");
2248 if ( !! scan_step ) {
2249 psensor.specValues[1] = boost::lexical_cast<double>(scan_step->getCharData());
2251 COLLADALOG_WARN(str(boost::format(
"couldn't find angle_incremnet %s")%sensortype));
2253 daeElement *scan_rate = domsensor->getChild(
"measurement_time");
2254 if ( !! scan_rate ) {
2255 psensor.specValues[2] = 1.0/boost::lexical_cast<double>(scan_rate->getCharData());
2257 COLLADALOG_WARN(str(boost::format(
"couldn't find measurement_time %s")%sensortype));
2259 daeElement *max_distance = domsensor->getChild(
"distance_range");
2260 if ( !! max_distance ) {
2261 psensor.specValues[3] = boost::lexical_cast<double>(max_distance->getCharData());
2263 COLLADALOG_WARN(str(boost::format(
"couldn't find distance_range %s")%sensortype));
2267 COLLADALOG_WARN(str(boost::format(
"need to create sensor type: %s")%sensortype));
2274 if( !instance_actuator ) {
2277 if( !instance_actuator->hasAttribute(
"url") ) {
2282 std::string instance_id = instance_actuator->getAttribute(
"id");
2283 std::string instance_url = instance_actuator->getAttribute(
"url");
2284 daeElementRef domactuator = _getElementFromUrl(daeURI(*instance_actuator,instance_url));
2285 if( !domactuator ) {
2286 COLLADALOG_WARN(str(boost::format(
"failed to find actuator id %s url=%s")%instance_id%instance_url));
2289 if( !domactuator->hasAttribute(
"type") ) {
2293 std::string actuatortype = domactuator->getAttribute(
"type");
2294 daeElement *rotor_inertia = domactuator->getChild(
"rotor_inertia");
2295 if ( !! rotor_inertia ) {
2296 plink->rotorInertia = boost::lexical_cast<double>(rotor_inertia->getCharData());
2298 daeElement *rotor_resistor = domactuator->getChild(
"rotor_resistor");
2299 if ( !! rotor_resistor ) {
2300 plink->rotorResistor = boost::lexical_cast<double>(rotor_resistor->getCharData());
2302 daeElement *gear_ratio = domactuator->getChild(
"gear_ratio");
2303 if ( !! gear_ratio ) {
2304 plink->gearRatio = boost::lexical_cast<double>(gear_ratio->getCharData());
2306 daeElement *torque_const = domactuator->getChild(
"torque_constant");
2307 if ( !! torque_const ) {
2308 plink->torqueConst = boost::lexical_cast<double>(torque_const->getCharData());
2310 daeElement *encoder_pulse = domactuator->getChild(
"encoder_pulse");
2311 if ( !! encoder_pulse ) {
2312 plink->encoderPulse = boost::lexical_cast<double>(encoder_pulse->getCharData());
2314 daeElement *nom_torque = domactuator->getChild(
"nominal_torque");
2315 if ( !! nom_torque ) {
2316 if(plink->climit.length() < 1) plink->climit.length(1);
2317 plink->climit[0] = boost::lexical_cast<double>(nom_torque->getCharData()) / ( plink->gearRatio * plink->torqueConst );
2324 return daeStandardURIResolver(*_dae).resolveElement(uri);
2327 static daeElement*
searchBinding(domCommon_sidref_or_paramRef paddr, daeElementRef parent)
2329 if( !!paddr->getSIDREF() ) {
2330 return daeSidRef(paddr->getSIDREF()->getValue(),parent).resolve().elt;
2332 if (!!paddr->getParam()) {
2333 return searchBinding(paddr->getParam()->getValue(),parent);
2346 daeElement* pelt = NULL;
2347 domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene>(parent.cast());
2349 pelt = searchBindingArray(ref,kscene->getInstance_articulated_system_array());
2353 return searchBindingArray(ref,kscene->getInstance_kinematics_model_array());
2355 domArticulated_systemRef articulated_system = daeSafeCast<domArticulated_system>(parent.cast());
2356 if( !!articulated_system ) {
2357 if( !!articulated_system->getKinematics() ) {
2358 pelt = searchBindingArray(ref,articulated_system->getKinematics()->getInstance_kinematics_model_array());
2363 if( !!articulated_system->getMotion() ) {
2364 return searchBinding(ref,articulated_system->getMotion()->getInstance_articulated_system());
2369 daeElementRef pbindelt;
2370 const domKinematics_bind_Array* pbindarray = NULL;
2371 const domKinematics_newparam_Array* pnewparamarray = NULL;
2372 domInstance_articulated_systemRef ias = daeSafeCast<domInstance_articulated_system>(parent.cast());
2374 pbindarray = &ias->getBind_array();
2375 pbindelt = ias->getUrl().getElement();
2376 pnewparamarray = &ias->getNewparam_array();
2378 if( !pbindarray || !pbindelt ) {
2379 domInstance_kinematics_modelRef ikm = daeSafeCast<domInstance_kinematics_model>(parent.cast());
2381 pbindarray = &ikm->getBind_array();
2382 pbindelt = ikm->getUrl().getElement();
2383 pnewparamarray = &ikm->getNewparam_array();
2386 if( !!pbindarray && !!pbindelt ) {
2387 for (
size_t ibind = 0; ibind < pbindarray->getCount(); ++ibind) {
2388 domKinematics_bindRef pbind = (*pbindarray)[ibind];
2389 if( !!pbind->getSymbol() && strcmp(pbind->getSymbol(), ref) == 0 ) {
2391 if( !!pbind->getParam() ) {
2393 return daeSidRef(pbind->getParam()->getRef(), pbindelt).resolve().elt;
2395 else if( !!pbind->getSIDREF() ) {
2396 return daeSidRef(pbind->getSIDREF()->getValue(), pbindelt).resolve().elt;
2400 for(
size_t inewparam = 0; inewparam < pnewparamarray->getCount(); ++inewparam) {
2401 domKinematics_newparamRef newparam = (*pnewparamarray)[inewparam];
2402 if( !!newparam->getSid() && strcmp(newparam->getSid(), ref) == 0 ) {
2403 if( !!newparam->getSIDREF() ) {
2404 return daeSidRef(newparam->getSIDREF()->getValue(),pbindelt).resolve().elt;
2406 COLLADALOG_WARN(str(boost::format(
"newparam sid=%s does not have SIDREF")%newparam->getSid()));
2410 COLLADALOG_WARN(str(boost::format(
"failed to get binding '%s' for element: %s")%ref%parent->getElementName()));
2414 static daeElement*
searchBindingArray(daeString ref,
const domInstance_articulated_system_Array& paramArray)
2416 for(
size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) {
2417 daeElement* pelt = searchBinding(ref,paramArray[iikm].cast());
2425 static daeElement*
searchBindingArray(daeString ref,
const domInstance_kinematics_model_Array& paramArray)
2427 for(
size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) {
2428 daeElement* pelt = searchBinding(ref,paramArray[iikm].cast());
2436 template <
typename U>
static xsBoolean
resolveBool(domCommon_bool_or_paramRef paddr,
const U& parent) {
2437 if( !!paddr->getBool() ) {
2438 return paddr->getBool()->getValue();
2440 if( !paddr->getParam() ) {
2444 for(
size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) {
2445 domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam];
2446 if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) {
2447 if( !!pnewparam->getBool() ) {
2448 return pnewparam->getBool()->getValue();
2450 else if( !!pnewparam->getSIDREF() ) {
2451 domKinematics_newparam::domBoolRef ptarget = daeSafeCast<domKinematics_newparam::domBool>(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt);
2453 COLLADALOG_WARN(str(boost::format(
"failed to resolve %s from %s")%pnewparam->getSIDREF()->getValue()%paddr->getID()));
2456 return ptarget->getValue();
2460 COLLADALOG_WARN(str(boost::format(
"failed to resolve %s")%paddr->getParam()->getValue()));
2463 template <
typename U>
static domFloat
resolveFloat(domCommon_float_or_paramRef paddr,
const U& parent) {
2464 if( !!paddr->getFloat() ) {
2465 return paddr->getFloat()->getValue();
2467 if( !paddr->getParam() ) {
2471 for(
size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) {
2472 domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam];
2473 if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) {
2474 if( !!pnewparam->getFloat() ) {
2475 return pnewparam->getFloat()->getValue();
2477 else if( !!pnewparam->getSIDREF() ) {
2478 domKinematics_newparam::domFloatRef ptarget = daeSafeCast<domKinematics_newparam::domFloat>(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt);
2480 COLLADALOG_WARN(str(boost::format(
"failed to resolve %s from %s")%pnewparam->getSIDREF()->getValue()%paddr->getID()));
2483 return ptarget->getValue();
2487 COLLADALOG_WARN(str(boost::format(
"failed to resolve %s")%paddr->getParam()->getValue()));
2493 daeElement* pfloat = pcommon->getChild(
"float");
2495 stringstream sfloat(pfloat->getCharData());
2499 daeElement* pparam = pcommon->getChild(
"param");
2501 if( pparam->hasAttribute(
"ref") ) {
2505 daeElement* pelt = daeSidRef(pparam->getCharData(),parent).resolve().elt;
2507 COLLADALOG_WARN(str(boost::format(
"found param ref: %s from %s")%pelt->getCharData()%pparam->getCharData()));
2517 domRotateRef protate = daeSafeCast<domRotate>(pelt);
2525 dReal fscale = _GetUnitScale(pelt,_fGlobalScale);
2526 domTranslateRef ptrans = daeSafeCast<domTranslate>(pelt);
2529 tres[3] = ptrans->getValue()[0]*fscale;
2530 tres[7] = ptrans->getValue()[1]*fscale;
2531 tres[11] = ptrans->getValue()[2]*fscale;
2535 domMatrixRef pmat = daeSafeCast<domMatrix>(pelt);
2537 for(
int i = 0;
i < 12; ++
i) {
2538 tres[
i] = pmat->getValue()[
i];
2547 domScaleRef pscale = daeSafeCast<domScale>(pelt);
2549 tres[0] = pscale->getValue()[0];
2550 tres[5] = pscale->getValue()[1];
2551 tres[10] = pscale->getValue()[2];
2555 domLookatRef pcamera = daeSafeCast<domLookat>(pelt);
2556 if( pelt->typeID() == domLookat::ID() ) {
2561 domSkewRef pskew = daeSafeCast<domSkew>(pelt);
2572 domNodeRef pnode = daeSafeCast<domNode>(pelt->getParent());
2574 DblArray12 ttemp, ttemp2;
2575 _ExtractFullTransform(ttemp, pnode);
2576 getNodeParentTransform(tres, pnode);
2578 memcpy(&tres[0],&ttemp2[0],
sizeof(DblArray12));
2585 DblArray12 ttemp, ttemp2;
2586 for(
size_t i = 0;
i < pelt->getContents().getCount(); ++
i) {
2587 getTransform(ttemp, pelt->getContents()[
i]);
2589 memcpy(&tres[0],&ttemp2[0],
sizeof(DblArray12));
2596 DblArray12 ttemp, ttemp2;
2597 daeTArray<daeElementRef> children;
2598 pelt->getChildren(children);
2599 for(
size_t i = 0;
i < children.getCount(); ++
i) {
2600 getTransform(ttemp, children[
i]);
2602 memcpy(&tres[0],&ttemp2[0],
sizeof(DblArray12));
2622 if( _bOpeningZAE && (msg ==
string(
"Document is empty\n") || msg ==
string(
"Error parsing XML in daeLIBXMLPlugin::read\n")) ) {
2641 domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene> (kiscene->getUrl().getElement().cast());
2645 for (
size_t imodel = 0; imodel < kiscene->getBind_kinematics_model_array().getCount(); imodel++) {
2646 domArticulated_systemRef articulated_system;
2647 domBind_kinematics_modelRef kbindmodel = kiscene->getBind_kinematics_model_array()[imodel];
2648 if (!kbindmodel->getNode()) {
2649 COLLADALOG_WARN(
"do not support kinematics models without references to nodes");
2654 domNodeRef node = daeSafeCast<domNode>(daeSidRef(kbindmodel->getNode(), viscene->getUrl().getElement()).resolve().elt);
2656 COLLADALOG_WARN(str(boost::format(
"bind_kinematics_model does not reference valid node %sn")%kbindmodel->getNode()));
2661 daeElement* pelt = searchBinding(kbindmodel,kscene);
2662 domInstance_kinematics_modelRef kimodel = daeSafeCast<domInstance_kinematics_model>(pelt);
2668 COLLADALOG_WARN(str(boost::format(
"bind_kinematics_model cannot find reference to %s:%s:n")%kbindmodel->getNode()%pelt->getElementName()));
2675 for (
size_t ijoint = 0; ijoint < kiscene->getBind_joint_axis_array().getCount(); ++ijoint) {
2676 domBind_joint_axisRef bindjoint = kiscene->getBind_joint_axis_array()[ijoint];
2677 daeElementRef pjtarget = daeSidRef(bindjoint->getTarget(), viscene->getUrl().getElement()).resolve().elt;
2679 COLLADALOG_WARN(str(boost::format(
"Target Node '%s' not found")%bindjoint->getTarget()));
2682 daeElement* pelt = searchBinding(bindjoint->getAxis(),kscene);
2683 domAxis_constraintRef pjointaxis = daeSafeCast<domAxis_constraint>(pelt);
2685 COLLADALOG_WARN(str(boost::format(
"joint axis for target %s")%bindjoint->getTarget()));
2694 for(
size_t iphysics = 0; iphysics < allscene->getInstance_physics_scene_array().getCount(); ++iphysics) {
2695 domPhysics_sceneRef pscene = daeSafeCast<domPhysics_scene>(allscene->getInstance_physics_scene_array()[iphysics]->getUrl().getElement().cast());
2696 for(
size_t imodel = 0; imodel < pscene->getInstance_physics_model_array().getCount(); ++imodel) {
2697 domInstance_physics_modelRef ipmodel = pscene->getInstance_physics_model_array()[imodel];
2698 domPhysics_modelRef pmodel = daeSafeCast<domPhysics_model> (ipmodel->getUrl().getElement().cast());
2699 domNodeRef nodephysicsoffset = daeSafeCast<domNode>(ipmodel->getParent().getElement().cast());
2700 for(
size_t ibody = 0; ibody < ipmodel->getInstance_rigid_body_array().getCount(); ++ibody) {
2702 lb.
irigidbody = ipmodel->getInstance_rigid_body_array()[ibody];
2703 lb.
node = daeSafeCast<domNode>(lb.
irigidbody->getTarget().getElement().cast());
2704 lb.
rigidbody = daeSafeCast<domRigid_body>(daeSidRef(lb.
irigidbody->getBody(),pmodel).resolve().elt);
2710 for(
size_t iconst = 0; iconst < ipmodel->getInstance_rigid_constraint_array().getCount(); ++iconst) {
2712 cb.
irigidconstraint = ipmodel->getInstance_rigid_constraint_array()[iconst];
2714 cb.
node = daeSafeCast<domNode>(cb.
rigidconstraint->getAttachment()->getRigid_body().getElement());
2725 for(
size_t i = 0;
i < arr.getCount(); ++
i) {
2726 if( strcmp(arr[
i]->getProfile(),
"OpenRAVE") == 0 ) {
2730 return domTechniqueRef();
2735 daeTArray<daeElementRef> children;
2736 pelt->getChildren(children);
2737 for(
size_t i = 0;
i < children.getCount(); ++
i) {
2738 if( children[
i]->getElementName() ==
string(
"technique") && children[
i]->hasAttribute(
"profile") && children[
i]->getAttribute(
"profile") ==
string(
"OpenRAVE") ) {
2742 return daeElementRef();
2747 daeTArray<daeElementRef> children;
2748 pelt->getChildren(children);
2749 for(
size_t i = 0;
i < children.getCount(); ++
i) {
2750 if( children[
i]->getElementName() ==
string(
"interface_type") ) {
2751 daeElementRef ptec = _ExtractOpenRAVEProfile(children[
i]);
2753 daeElement* ptype = ptec->getChild(
"interface");
2755 return boost::shared_ptr<std::string>(
new std::string(ptype->getCharData()));
2760 return boost::shared_ptr<std::string>();
2765 for(
size_t i = 0;
i < arr.getCount(); ++
i) {
2766 if( strcmp(arr[
i]->getType(),
"interface_type") == 0 ) {
2767 domTechniqueRef tec = _ExtractOpenRAVEProfile(arr[
i]->getTechnique_array());
2769 daeElement* ptype = tec->getChild(
"interface");
2771 return boost::shared_ptr<std::string>(
new std::string(ptype->getCharData()));
2776 return boost::shared_ptr<std::string>();
2780 std::string linkname;
2782 if( !!pdomlink->getName() ) {
2783 linkname = pdomlink->getName();
2785 if( linkname.size() == 0 && !!pdomlink->getID() ) {
2786 linkname = pdomlink->getID();
2789 return _ConvertToValidName(linkname);
2794 if( pelt->getElementName()==
type ) {
2798 string name = pelt->getElementName();
2799 size_t pos =
name.find_last_of(
':');
2800 if( pos == string::npos ) {
2807 daeElement* peltjoint = daeSidRef(targetref, peltref).resolve().elt;
2808 domJointRef pdomjoint = daeSafeCast<domJoint> (peltjoint);
2810 domInstance_jointRef pdomijoint = daeSafeCast<domInstance_joint> (peltjoint);
2812 pdomjoint = daeSafeCast<domJoint> (pdomijoint->getUrl().getElement().cast());
2817 COLLADALOG_WARN(str(boost::format(
"could not find collada joint '%s'!")%targetref));
2818 return std::make_pair(boost::shared_ptr<LinkInfo>(),domJointRef());
2821 if(
string(targetref).find(
"./") != 0 ) {
2822 std::map<std::string,boost::shared_ptr<LinkInfo> >::iterator itjoint = _mapJointIds.find(targetref);
2823 if( itjoint != _mapJointIds.end() ) {
2824 return std::make_pair(itjoint->second,pdomjoint);
2826 COLLADALOG_WARN(str(boost::format(
"failed to find joint target '%s' in _mapJointIds")%targetref));
2829 boost::shared_ptr<LinkInfo> pjoint = GetLink(pdomjoint->getName());
2831 COLLADALOG_WARN(str(boost::format(
"could not find openrave joint '%s'!")%pdomjoint->getName()));
2833 return std::make_pair(pjoint,pdomjoint);
2838 std::string
name = pelt->getElementName();
2839 std::size_t pos =
name.find_last_of(
':');
2840 if( pos != string::npos ) {
2841 return name.substr(pos+1);
2848 if( p->hasAttribute(
"id") ) {
2849 return p->getAttribute(
"id");
2859 std::string
name = _getElementName(pelt);
2861 daeTArray<daeElementRef> children;
2862 pelt->getChildren(children);
2863 if(
name ==
"math" ) {
2864 for(std::size_t ic = 0; ic < children.getCount(); ++ic) {
2865 std::string childname = _getElementName(children[ic]);
2866 if( childname ==
"apply" || childname ==
"csymbol" || childname ==
"cn" || childname ==
"ci" ) {
2867 eq = _ExtractMathML(proot, pkinbody, children[ic]);
2870 throw ModelLoader::ModelLoaderException(str(boost::format(
"_ExtractMathML: do not support element %s in mathml")%childname).c_str());
2874 else if(
name ==
"apply" ) {
2875 if( children.getCount() == 0 ) {
2878 string childname = _getElementName(children[0]);
2879 if( childname ==
"plus" ) {
2881 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
2882 eq += _ExtractMathML(proot, pkinbody, children[ic]);
2883 if( ic+1 < children.getCount() ) {
2889 else if( childname ==
"quotient" ) {
2891 eq += str(boost::format(
"floor(%s/%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
2893 else if( childname ==
"divide" ) {
2895 eq += str(boost::format(
"(%s/%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
2897 else if( childname ==
"minus" ) {
2899 if( children.getCount() == 2 ) {
2900 eq += str(boost::format(
"(-%s)")%_ExtractMathML(proot,pkinbody,children[1]));
2903 eq += str(boost::format(
"(%s-%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
2906 else if( childname ==
"power" ) {
2908 std::string sbase = _ExtractMathML(proot,pkinbody,children[1]);
2909 std::string sexp = _ExtractMathML(proot,pkinbody,children[2]);
2923 eq += str(boost::format(
"pow(%s,%s)")%sbase%sexp);
2926 else if( childname ==
"rem" ) {
2928 eq += str(boost::format(
"(%s%%%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
2930 else if( childname ==
"times" ) {
2932 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
2933 eq += _ExtractMathML(proot, pkinbody, children[ic]);
2934 if( ic+1 < children.getCount() ) {
2940 else if( childname ==
"root" ) {
2942 string sdegree, snum;
2943 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
2944 if( _getElementName(children[ic]) ==
string(
"degree") ) {
2945 sdegree = _ExtractMathML(proot,pkinbody,children[ic]->getChildren()[0]);
2948 snum = _ExtractMathML(proot,pkinbody,children[ic]);
2952 int degree = boost::lexical_cast<int>(sdegree);
2954 eq += str(boost::format(
"(%s)")%snum);
2956 else if( degree == 2 ) {
2957 eq += str(boost::format(
"sqrt(%s)")%snum);
2959 else if( degree == 3 ) {
2960 eq += str(boost::format(
"cbrt(%s)")%snum);
2963 eq += str(boost::format(
"pow(%s,1.0/%s)")%snum%sdegree);
2966 catch(
const boost::bad_lexical_cast&) {
2967 eq += str(boost::format(
"pow(%s,1.0/%s)")%snum%sdegree);
2970 else if( childname ==
"and" ) {
2972 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
2973 eq += _ExtractMathML(proot, pkinbody, children[ic]);
2974 if( ic+1 < children.getCount() ) {
2980 else if( childname ==
"or" ) {
2982 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
2983 eq += _ExtractMathML(proot, pkinbody, children[ic]);
2984 if( ic+1 < children.getCount() ) {
2990 else if( childname ==
"not" ) {
2992 eq += str(boost::format(
"(!%s)")%_ExtractMathML(proot,pkinbody,children[1]));
2994 else if( childname ==
"floor" ) {
2996 eq += str(boost::format(
"floor(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
2998 else if( childname ==
"ceiling" ) {
3000 eq += str(boost::format(
"ceil(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3002 else if( childname ==
"eq" ) {
3004 eq += str(boost::format(
"(%s=%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3006 else if( childname ==
"neq" ) {
3008 eq += str(boost::format(
"(%s!=%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3010 else if( childname ==
"gt" ) {
3012 eq += str(boost::format(
"(%s>%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3014 else if( childname ==
"lt" ) {
3016 eq += str(boost::format(
"(%s<%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3018 else if( childname ==
"geq" ) {
3020 eq += str(boost::format(
"(%s>=%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3022 else if( childname ==
"leq" ) {
3024 eq += str(boost::format(
"(%s<=%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3026 else if( childname ==
"ln" ) {
3028 eq += str(boost::format(
"log(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3030 else if( childname ==
"log" ) {
3031 COLLADA_ASSERT(children.getCount()==2 || children.getCount()==3);
3032 string sbase=
"10", snum;
3033 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
3034 if( _getElementName(children[ic]) ==
string(
"logbase") ) {
3035 sbase = _ExtractMathML(proot,pkinbody,children[ic]->getChildren()[0]);
3038 snum = _ExtractMathML(proot,pkinbody,children[ic]);
3042 int base = boost::lexical_cast<int>(sbase);
3044 eq += str(boost::format(
"log10(%s)")%snum);
3046 else if( base == 2 ) {
3047 eq += str(boost::format(
"log2(%s)")%snum);
3050 eq += str(boost::format(
"(log(%s)/log(%s))")%snum%sbase);
3053 catch(
const boost::bad_lexical_cast&) {
3054 eq += str(boost::format(
"(log(%s)/log(%s))")%snum%sbase);
3057 else if( childname ==
"arcsin" ) {
3059 eq += str(boost::format(
"asin(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3061 else if( childname ==
"arccos" ) {
3063 eq += str(boost::format(
"acos(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3065 else if( childname ==
"arctan" ) {
3067 eq += str(boost::format(
"atan(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3069 else if( childname ==
"arccosh" ) {
3071 eq += str(boost::format(
"acosh(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3073 else if( childname ==
"arccot" ) {
3075 eq += str(boost::format(
"acot(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3077 else if( childname ==
"arccoth" ) {
3079 eq += str(boost::format(
"acoth(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3081 else if( childname ==
"arccsc" ) {
3083 eq += str(boost::format(
"acsc(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3085 else if( childname ==
"arccsch" ) {
3087 eq += str(boost::format(
"acsch(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3089 else if( childname ==
"arcsec" ) {
3091 eq += str(boost::format(
"asec(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3093 else if( childname ==
"arcsech" ) {
3095 eq += str(boost::format(
"asech(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3097 else if( childname ==
"arcsinh" ) {
3099 eq += str(boost::format(
"asinh(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3101 else if( childname ==
"arctanh" ) {
3103 eq += str(boost::format(
"atanh(%s)")%_ExtractMathML(proot,pkinbody,children[1]));
3105 else if( childname ==
"implies" || childname ==
"forall" || childname ==
"exists" || childname ==
"conjugate" || childname ==
"arg" || childname ==
"real" || childname ==
"imaginary" || childname ==
"lcm" || childname ==
"factorial" || childname ==
"xor") {
3106 throw ModelLoader::ModelLoaderException(str(boost::format(
"_ExtractMathML: %s function in <apply> tag not supported")%childname).c_str());
3108 else if( childname ==
"csymbol" ) {
3109 if( children[0]->getAttribute(
"encoding")==
string(
"text/xml") ) {
3110 domFormulaRef pformula;
3111 string functionname;
3112 if( children[0]->hasAttribute(
"definitionURL") ) {
3114 string formulaurl = children[0]->getAttribute(
"definitionURL");
3115 if( formulaurl.size() > 0 ) {
3116 daeElementRef pelt = _getElementFromUrl(daeURI(*children[0],formulaurl));
3117 pformula = daeSafeCast<domFormula>(pelt);
3119 COLLADALOG_WARN(str(boost::format(
"could not find csymbol %s formula")%children[0]->getAttribute(
"definitionURL")));
3122 COLLADALOG_DEBUG(str(boost::format(
"csymbol formula %s found")%pformula->getId()));
3127 if( children[0]->hasAttribute(
"type") ) {
3128 if( children[0]->getAttribute(
"type") ==
"function" ) {
3129 functionname = children[0]->getCharData();
3134 if( !!pformula->getName() ) {
3135 functionname = pformula->getName();
3138 functionname = children[0]->getCharData();
3142 if( functionname ==
"INRANGE" ) {
3144 string a = _ExtractMathML(proot,pkinbody,children[1]),
b = _ExtractMathML(proot,pkinbody,children[2]),
c = _ExtractMathML(proot,pkinbody,children[3]);
3145 eq += str(boost::format(
"((%s>=%s)&(%s<=%s))")%
a%
b%
a%
c);
3147 else if( functionname ==
"SSSA" || functionname ==
"SASA" || functionname ==
"SASS" ) {
3149 eq += str(boost::format(
"%s(%s,%s,%s)")%functionname%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2])%_ExtractMathML(proot,pkinbody,children[3]));
3151 else if( functionname ==
"atan2") {
3153 eq += str(boost::format(
"atan2(%s,%s)")%_ExtractMathML(proot,pkinbody,children[1])%_ExtractMathML(proot,pkinbody,children[2]));
3156 COLLADALOG_WARN(str(boost::format(
"csymbol %s not implemented")%functionname));
3160 else if( children[0]->getAttribute(
"encoding")!=
string(
"COLLADA") ) {
3161 COLLADALOG_WARN(str(boost::format(
"_ExtractMathML: csymbol '%s' has unknown encoding '%s'")%children[0]->getCharData()%children[0]->getAttribute(
"encoding")));
3164 eq += _ExtractMathML(proot,pkinbody,children[0]);
3171 for(
size_t ic = 1; ic < children.getCount(); ++ic) {
3172 eq += _ExtractMathML(proot, pkinbody, children[ic]);
3173 if( ic+1 < children.getCount() ) {
3180 else if(
name ==
"csymbol" ) {
3181 if( !pelt->hasAttribute(
"encoding") ) {
3182 COLLADALOG_WARN(str(boost::format(
"_ExtractMathML: csymbol '%s' does not have any encoding")%pelt->getCharData()));
3184 else if( pelt->getAttribute(
"encoding")!=
string(
"COLLADA") ) {
3185 COLLADALOG_WARN(str(boost::format(
"_ExtractMathML: csymbol '%s' has unknown encoding '%s'")%pelt->getCharData()%pelt->getAttribute(
"encoding")));
3187 boost::shared_ptr<LinkInfo> pjoint = _getJointFromRef(pelt->getCharData().c_str(),proot,pkinbody).first;
3189 COLLADALOG_WARN(str(boost::format(
"_ExtractMathML: failed to find csymbol: %s")%pelt->getCharData()));
3190 eq = pelt->getCharData();
3192 string jointname(CORBA::String_var(pjoint->name));
3195 if( _mapJointUnits.find(pjoint) != _mapJointUnits.end() && _mapJointUnits[pjoint].at(0) != 1 ) {
3196 eq = str(boost::format(
"(%f*%s)")%(1/_mapJointUnits[pjoint].at(0))%jointname);
3202 else if(
name ==
"cn" ) {
3203 eq = pelt->getCharData();
3205 else if(
name ==
"ci" ) {
3206 eq = pelt->getCharData();
3208 else if(
name ==
"pi" ) {
3209 eq =
"3.14159265358979323846";
3219 if( s.size() == 0 ) {
3222 return std::count_if(s.begin(), s.end(), _IsValidCharInName) == (
int)s.size();
3226 if(
name.size() == 0 ) {
3227 return str(boost::format(
"__dummy%d")%_nGlobalIndex++);
3229 if( _IsValidName(
name) ) {
3232 std::string newname =
name;
3233 for(
size_t i = 0;
i < newname.size(); ++
i) {
3234 if( !_IsValidCharInName(newname[
i]) ) {
3238 COLLADALOG_WARN(str(boost::format(
"name '%s' is not a valid name, converting to '%s'")%
name%newname));
3245 domExtraRef pextra = daeSafeCast<domExtra> (pelt->getChild(
"extra"));
3246 if( !!pextra && !!pextra->getAsset() && !!pextra->getAsset()->getUnit() ) {
3247 return pextra->getAsset()->getUnit()->getMeter();
3249 if( !!pelt->getParent() ) {
3250 return _GetUnitScale(pelt->getParent(),startscale);
3289 return CORBA::string_dup(
name_.c_str());
3295 return CORBA::string_dup(
url_.c_str());
3301 return new StringSequence(
info_);
3307 return new LinkInfoSequence(
links_);
3324 boost::mutex::scoped_lock lock(
lock_);
3327 throw ModelLoader::ModelLoaderException(
"The model file cannot be found.");
3330 throw ModelLoader::ModelLoaderException(
"The model file cannot be loaded.");
3336 if(param ==
"readImage") {
3343 if(param ==
"readImage") {
3351 if(param ==
"AABBType") {
3357 for(
unsigned int i=0;
i < shapeIndices.length();
i++){
3363 (
ColdetModelPtr& coldetModel,
const TransformedShapeIndex& tsi,
const Matrix44& Tparent,
int& vertexIndex,
int& triangleIndex)
3365 short shapeIndex = tsi.shapeIndex;
3366 const DblArray12& M = tsi.transformMatrix;;
3368 Tlocal << M[0], M[1], M[2], M[3],
3369 M[4], M[5], M[6], M[7],
3370 M[8], M[9], M[10], M[11],
3372 T = Tparent * Tlocal;
3374 const ShapeInfo& shapeInfo = shapes_[shapeIndex];
3376 const FloatSequence& vertices = shapeInfo.vertices;
3377 const LongSequence& triangles = shapeInfo.triangles;
3378 const int numTriangles = triangles.length() / 3;
3380 coldetModel->setNumTriangles(coldetModel->getNumTriangles()+numTriangles);
3381 int numVertices = numTriangles * 3;
3382 coldetModel->setNumVertices(coldetModel->getNumVertices()+numVertices);
3383 for(
int j=0; j < numTriangles; ++j){
3384 int vertexIndexTop = vertexIndex;
3385 for(
int k=0; k < 3; ++k){
3386 long orgVertexIndex = shapeInfo.triangles[j * 3 + k];
3387 int p = orgVertexIndex * 3;
3388 Vector4 v(T *
Vector4(vertices[p+0], vertices[p+1], vertices[p+2], 1.0));
3389 coldetModel->setVertex(vertexIndex++, (
float)v[0], (
float)v[1], (
float)v[2]);
3391 coldetModel->setTriangle(triangleIndex++, vertexIndexTop, vertexIndexTop + 1, vertexIndexTop + 2);
3397 const double EPS = 1.0e-6;
3399 std::vector<Vector3> boxSizeMap;
3400 std::vector<Vector3> boundingBoxData;
3402 for(
unsigned int i=0;
i<
links_.length();
i++){
3407 _depth = inputData[
i];
3408 if( _depth >=
links_[
i].AABBmaxDepth)
3409 _depth =
links_[
i].AABBmaxDepth-1;
3412 std::vector<TransformedShapeIndex> tsiMap;
3413 links_[
i].shapeIndices.length(0);
3414 SensorInfoSequence& sensors =
links_[
i].sensors;
3415 for (
unsigned int j=0; j<sensors.length(); j++){
3416 SensorInfo& sensor = sensors[j];
3417 sensor.shapeIndices.length(0);
3420 for(
unsigned int j=0; j<boundingBoxData.size()/2; j++){
3424 for( ; k<boxSizeMap.size(); k++)
3425 if((boxSizeMap[k] - boundingBoxData[j*2+1]).
norm() <
EPS)
3427 if( k<boxSizeMap.size() )
3430 boxSizeMap.push_back(boundingBoxData[j*2+1]);
3436 for( ; l<tsiMap.size(); l++){
3437 Vector3 p(tsiMap[l].transformMatrix[3],tsiMap[l].transformMatrix[7],tsiMap[l].transformMatrix[11]);
3438 if((p - boundingBoxData[j*2]).
norm() <
EPS && tsiMap[l].shapeIndex == (
int)k)
3441 if( l==tsiMap.size() )
3448 TransformedShapeIndex& tsi =
links_[
i].shapeIndices[
num];
3449 tsi.inlinedShapeTransformMatrixIndex = -1;
3453 for(
int col=0; col < 4; ++col)
3457 tsi.transformMatrix[p++] = boundingBoxData[j*2][0];
3460 tsi.transformMatrix[p++] = boundingBoxData[j*2][1];
3463 tsi.transformMatrix[p++] = boundingBoxData[j*2][2];
3469 tsi.transformMatrix[p++] = T(
row, col);
3471 tsiMap.push_back(tsi);
3483 struct stat statbuff;
3485 if( stat( it->first.c_str(), &statbuff ) == 0 ){
3486 mtime = statbuff.st_mtime;
3488 if(it->second!=mtime){