22 #ifndef OPENHRP_COLLADA_WRITER_H 23 #define OPENHRP_COLLADA_WRITER_H 31 #include <hrpCorba/ViewSimulator.hh> 43 rotation[0] = rotation[1] = rotation[2] = rotation[3] = 0;
44 translation[0] = translation[1] = translation[2] = 0;
57 static bool ComparePair(
const std::pair<int,int>& p0,
const std::pair<int,int>& p1)
59 return p0.second < p1.second;
107 axis_sids(
const string& axissid,
const string& valuesid,
const string& jointnodesid) : axissid(axissid), valuesid(valuesid), jointnodesid(jointnodesid) {
114 domInstance_kinematics_modelRef
ikm;
116 boost::shared_ptr<kinematics_model_output>
kmout;
122 domInstance_articulated_systemRef
ias;
131 domInstance_physics_modelRef
ipm;
132 boost::shared_ptr<physics_model_output>
pmout;
138 boost::shared_ptr<kinematics_model_output>
kmout;
139 boost::shared_ptr<physics_model_output>
pmout;
142 ColladaWriter(
const std::list<ManipulatorInfo>& listmanipulators,
const char* comment_str) : _dom(NULL) {
143 _listmanipulators = listmanipulators;
144 daeErrorHandler::setErrorHandler(
this);
145 COLLADALOG_INFO(str(boost::format(
"init COLLADA writer version: %s, namespace: %s")%COLLADA_VERSION%COLLADA_NAMESPACE));
146 _collada.reset(
new DAE);
147 _collada->setIOPlugin( NULL );
148 _collada->setDatabase( NULL );
150 const char* documentName =
"openrave_snapshot";
151 daeInt
error = _collada->getDatabase()->insertDocument(documentName, &_doc );
152 BOOST_ASSERT( error == DAE_OK && !!_doc );
153 _dom = daeSafeCast<domCOLLADA>(_doc->getDomRoot());
156 domAssetRef asset = daeSafeCast<domAsset>( _dom->add( COLLADA_ELEMENT_ASSET ) );
159 boost::posix_time::time_facet* facet =
new boost::posix_time::time_facet(
"%Y-%m-%dT%H:%M:%s");
160 std::stringstream ss;
161 ss.imbue(std::locale(ss.getloc(), facet));
162 ss << boost::posix_time::second_clock::local_time();
164 domAsset::domCreatedRef created = daeSafeCast<domAsset::domCreated>( asset->add( COLLADA_ELEMENT_CREATED ) );
165 created->setValue(ss.str().c_str());
166 domAsset::domModifiedRef modified = daeSafeCast<domAsset::domModified>( asset->add( COLLADA_ELEMENT_MODIFIED ) );
167 modified->setValue(ss.str().c_str());
169 domAsset::domContributorRef contrib = daeSafeCast<domAsset::domContributor>( asset->add( COLLADA_TYPE_CONTRIBUTOR ) );
170 domAsset::domContributor::domAuthoring_toolRef authoringtool = daeSafeCast<domAsset::domContributor::domAuthoring_tool>( contrib->add( COLLADA_ELEMENT_AUTHORING_TOOL ) );
171 authoringtool->setValue(
"OpenHRP3 Collada Writer");
172 domAsset::domContributor::domCommentsRef comments = daeSafeCast<domAsset::domContributor::domComments>( contrib->add( COLLADA_ELEMENT_COMMENTS ) );
173 comments->setValue(comment_str);
176 domAsset::domUnitRef
units = daeSafeCast<domAsset::domUnit>( asset->add( COLLADA_ELEMENT_UNIT ) );
178 units->setName(
"meter");
180 domAsset::domUp_axisRef zup = daeSafeCast<domAsset::domUp_axis>( asset->add( COLLADA_ELEMENT_UP_AXIS ) );
181 zup->setValue(UP_AXIS_Z_UP);
184 _globalscene = _dom->getScene();
185 if( !_globalscene ) {
186 _globalscene = daeSafeCast<domCOLLADA::domScene>( _dom->add( COLLADA_ELEMENT_SCENE ) );
189 _visualScenesLib = daeSafeCast<domLibrary_visual_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_VISUAL_SCENES));
190 _visualScenesLib->setId(
"vscenes");
191 _geometriesLib = daeSafeCast<domLibrary_geometries>(_dom->add(COLLADA_ELEMENT_LIBRARY_GEOMETRIES));
192 _geometriesLib->setId(
"geometries");
193 _effectsLib = daeSafeCast<domLibrary_effects>(_dom->add(COLLADA_ELEMENT_LIBRARY_EFFECTS));
194 _effectsLib->setId(
"effects");
195 _imagesLib = daeSafeCast<domLibrary_images>(_dom->add(COLLADA_ELEMENT_LIBRARY_IMAGES));
196 _materialsLib = daeSafeCast<domLibrary_materials>(_dom->add(COLLADA_ELEMENT_LIBRARY_MATERIALS));
197 _materialsLib->setId(
"materials");
198 _kinematicsModelsLib = daeSafeCast<domLibrary_kinematics_models>(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_MODELS));
199 _kinematicsModelsLib->setId(
"kmodels");
200 _articulatedSystemsLib = daeSafeCast<domLibrary_articulated_systems>(_dom->add(COLLADA_ELEMENT_LIBRARY_ARTICULATED_SYSTEMS));
201 _articulatedSystemsLib->setId(
"asystems");
202 _kinematicsScenesLib = daeSafeCast<domLibrary_kinematics_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_SCENES));
203 _kinematicsScenesLib->setId(
"kscenes");
204 _physicsScenesLib = daeSafeCast<domLibrary_physics_scenes>(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_SCENES));
205 _physicsScenesLib->setId(
"pscenes");
206 _physicsModelsLib = daeSafeCast<domLibrary_physics_models>(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_MODELS));
207 _physicsModelsLib->setId(
"pmodels");
208 domExtraRef pextra_library_sensors = daeSafeCast<domExtra>(_dom->add(COLLADA_ELEMENT_EXTRA));
209 pextra_library_sensors->setId(
"sensors");
210 pextra_library_sensors->setType(
"library_sensors");
211 _sensorsLib = daeSafeCast<domTechnique>(pextra_library_sensors->add(COLLADA_ELEMENT_TECHNIQUE));
212 _sensorsLib->setProfile(
"OpenRAVE");
214 domExtraRef pextra_library_actuators = daeSafeCast<domExtra>(_dom->add(COLLADA_ELEMENT_EXTRA));
215 pextra_library_actuators->setId(
"actuators");
216 pextra_library_actuators->setType(
"library_actuators");
217 _actuatorsLib = daeSafeCast<domTechnique>(pextra_library_actuators->add(COLLADA_ELEMENT_TECHNIQUE));
218 _actuatorsLib->setProfile(
"OpenRAVE");
230 bool bcompress = filename.size() >= 4 && filename[filename.size()-4] ==
'.' && ::tolower(filename[filename.size()-3]) ==
'z' && ::tolower(filename[filename.size()-2]) ==
'a' && ::tolower(filename[filename.size()-1]) ==
'e';
232 if(!_collada->writeTo(_doc->getDocumentURI()->getURI(), filename.c_str()) ) {
233 throw ModelLoader::ModelLoaderException(str(boost::format(
"failed to save collada file to %s")%filename).c_str());
242 boost::shared_ptr<instance_articulated_system_output> iasout = _WriteRobot(bodyInfo);
246 _WriteBindingsInstance_kinematics_scene(_scene.kiscene,bodyInfo,iasout->vaxissids,iasout->vkinematicsbindings);
252 COLLADALOG_VERBOSE(str(boost::format(
"writing robot as instance_articulated_system (%d) %s\n")%_GetRobotId(bodyInfo)%bodyInfo->
name()));
253 string asid = str(boost::format(
"robot%d")%_GetRobotId(bodyInfo));
254 string askid = str(boost::format(
"%s_kinematics")%asid);
255 string asmid = str(boost::format(
"%s_motion")%asid);
256 string iassid = str(boost::format(
"%s_inst")%asmid);
258 domInstance_articulated_systemRef ias = daeSafeCast<domInstance_articulated_system>(_scene.kscene->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM));
259 ias->setSid(iassid.c_str());
260 ias->setUrl((
string(
"#")+asmid).c_str());
261 ias->setName(bodyInfo->
name());
267 domArticulated_systemRef articulated_system_motion = daeSafeCast<domArticulated_system>(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM));
268 articulated_system_motion->setId(asmid.c_str());
269 domMotionRef motion = daeSafeCast<domMotion>(articulated_system_motion->add(COLLADA_ELEMENT_MOTION));
270 domMotion_techniqueRef mt = daeSafeCast<domMotion_technique>(motion->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
271 domInstance_articulated_systemRef ias_motion = daeSafeCast<domInstance_articulated_system>(motion->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM));
272 ias_motion->setUrl(str(boost::format(
"#%s")%askid).c_str());
275 domArticulated_systemRef articulated_system_kinematics = daeSafeCast<domArticulated_system>(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM));
276 articulated_system_kinematics->setId(askid.c_str());
277 domKinematicsRef kinematics = daeSafeCast<domKinematics>(articulated_system_kinematics->add(COLLADA_ELEMENT_KINEMATICS));
278 domKinematics_techniqueRef kt = daeSafeCast<domKinematics_technique>(kinematics->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
280 boost::shared_ptr<instance_kinematics_model_output> ikmout = _WriteInstance_kinematics_model(bodyInfo,kinematics,askid);
281 LinkInfoSequence_var links = bodyInfo->
links();
282 for(
size_t idof = 0; idof < ikmout->vaxissids.size(); ++idof) {
283 string axis_infosid = str(boost::format(
"axis_info_inst%d")%idof);
284 LinkInfo& pjoint = links[ikmout->kmout->vaxissids.at(idof).ijoint];
285 string jointType(CORBA::String_var(pjoint.jointType));
288 domKinematics_axis_infoRef kai = daeSafeCast<domKinematics_axis_info>(kt->add(COLLADA_ELEMENT_AXIS_INFO));
289 kai->setAxis(str(boost::format(
"%s/%s")%ikmout->kmout->kmodel->getID()%ikmout->kmout->vaxissids.at(idof).sid).c_str());
290 kai->setSid(axis_infosid.c_str());
291 domCommon_bool_or_paramRef active = daeSafeCast<domCommon_bool_or_param>(kai->add(COLLADA_ELEMENT_ACTIVE));
292 daeSafeCast<domCommon_bool_or_param::domBool>(active->add(COLLADA_ELEMENT_BOOL))->setValue(jointType !=
"fixed");
293 domCommon_bool_or_paramRef locked = daeSafeCast<domCommon_bool_or_param>(kai->add(COLLADA_ELEMENT_LOCKED));
294 daeSafeCast<domCommon_bool_or_param::domBool>(locked->add(COLLADA_ELEMENT_BOOL))->setValue(
false);
296 dReal fmult = jointType ==
"rotate" ? (180.0/
M_PI) : 1.0;
297 vector<dReal> vmin, vmax;
298 if( jointType ==
"fixed" ) {
303 if( pjoint.llimit.length() > 0 ) {
304 vmin.push_back(fmult*pjoint.llimit[0]);
306 if( pjoint.ulimit.length() > 0 ) {
307 vmax.push_back(fmult*pjoint.ulimit[0]);
311 if( vmin.size() > 0 || vmax.size() > 0 ) {
312 domKinematics_limitsRef plimits = daeSafeCast<domKinematics_limits>(kai->add(COLLADA_ELEMENT_LIMITS));
313 if( vmin.size() > 0 ) {
314 daeSafeCast<domCommon_float_or_param::domFloat>(plimits->add(COLLADA_ELEMENT_MIN)->add(COLLADA_ELEMENT_FLOAT))->setValue(vmin[0]);
316 if( vmax.size() > 0 ) {
317 daeSafeCast<domCommon_float_or_param::domFloat>(plimits->add(COLLADA_ELEMENT_MAX)->add(COLLADA_ELEMENT_FLOAT))->setValue(vmax[0]);
322 domMotion_axis_infoRef mai = daeSafeCast<domMotion_axis_info>(mt->add(COLLADA_ELEMENT_AXIS_INFO));
323 mai->setAxis(str(boost::format(
"%s/%s")%askid%axis_infosid).c_str());
324 if( pjoint.uvlimit.length() > 0 ) {
325 domCommon_float_or_paramRef speed = daeSafeCast<domCommon_float_or_param>(mai->add(COLLADA_ELEMENT_SPEED));
326 daeSafeCast<domCommon_float_or_param::domFloat>(speed->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint.uvlimit[0]);
328 if( pjoint.climit.length() > 0 ) {
329 domCommon_float_or_paramRef accel = daeSafeCast<domCommon_float_or_param>(mai->add(COLLADA_ELEMENT_ACCELERATION));
330 daeSafeCast<domCommon_float_or_param::domFloat>(accel->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint.climit[0] * pjoint.torqueConst * pjoint.gearRatio);
335 string asmsym = str(boost::format(
"%s_%s")%asmid%ikmout->ikm->getSid());
336 string assym = str(boost::format(
"%s_%s")%_scene.kscene->getID()%ikmout->ikm->getSid());
337 for(std::vector<std::pair<std::string,std::string> >::iterator it = ikmout->vkinematicsbindings.begin(); it != ikmout->vkinematicsbindings.end(); ++it) {
338 domKinematics_newparamRef abm = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
339 abm->setSid(asmsym.c_str());
340 daeSafeCast<domKinematics_newparam::domSIDREF>(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s")%askid%it->first).c_str());
341 domKinematics_newparamRef ab = daeSafeCast<domKinematics_newparam>(ias->add(COLLADA_ELEMENT_NEWPARAM));
342 ab->setSid(assym.c_str());
343 daeSafeCast<domKinematics_newparam::domSIDREF>(ab->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s")%asmid%asmsym).c_str());
344 iasout->vkinematicsbindings.push_back(make_pair(
string(ab->getSid()), it->second));
346 for(
size_t idof = 0; idof < ikmout->vaxissids.size(); ++idof) {
347 const axis_sids& kas = ikmout->vaxissids.at(idof);
348 domKinematics_newparamRef abm = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
349 abm->setSid(str(boost::format(
"%s_%s")%asmid%kas.
axissid).c_str());
350 daeSafeCast<domKinematics_newparam::domSIDREF>(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s")%askid%kas.
axissid).c_str());
351 domKinematics_newparamRef ab = daeSafeCast<domKinematics_newparam>(ias->add(COLLADA_ELEMENT_NEWPARAM));
352 ab->setSid(str(boost::format(
"%s_%s")%assym%kas.
axissid).c_str());
353 daeSafeCast<domKinematics_newparam::domSIDREF>(ab->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s_%s")%asmid%asmid%kas.
axissid).c_str());
356 domKinematics_newparamRef abmvalue = daeSafeCast<domKinematics_newparam>(ias_motion->add(COLLADA_ELEMENT_NEWPARAM));
357 abmvalue->setSid(str(boost::format(
"%s_%s")%asmid%kas.
valuesid).c_str());
358 daeSafeCast<domKinematics_newparam::domSIDREF>(abmvalue->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s")%askid%kas.
valuesid).c_str());
359 domKinematics_newparamRef abvalue = daeSafeCast<domKinematics_newparam>(ias->add(COLLADA_ELEMENT_NEWPARAM));
360 valuesid = str(boost::format(
"%s_%s")%assym%kas.
valuesid);
361 abvalue->setSid(valuesid.c_str());
362 daeSafeCast<domKinematics_newparam::domSIDREF>(abvalue->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format(
"%s/%s_%s")%asmid%asmid%kas.
valuesid).c_str());
367 boost::shared_ptr<kinematics_model_output> kmout = _GetKinematics_model(bodyInfo);
368 string kmodelid = kmout->kmodel->getID(); kmodelid +=
"/";
371 for(std::list<ManipulatorInfo>::const_iterator itmanip = _listmanipulators.begin(); itmanip != _listmanipulators.end(); ++itmanip) {
372 if (kmout->maplinknames.find(itmanip->basename) == kmout->maplinknames.end()){
373 std::cerr <<
"can't find a link named " << itmanip->basename <<
", manipulator " << itmanip->name <<
" is not defined" << std::endl;
376 if (kmout->maplinknames.find(itmanip->effectorname) == kmout->maplinknames.end()){
377 std::cerr <<
"can't find a link named " << itmanip->effectorname <<
", manipulator " << itmanip->name <<
" is not defined" << std::endl;
380 domExtraRef pextra = daeSafeCast<domExtra>(articulated_system_motion->add(COLLADA_ELEMENT_EXTRA));
381 pextra->setName(itmanip->name.c_str());
382 pextra->setType(
"manipulator");
383 domTechniqueRef ptec = daeSafeCast<domTechnique>(pextra->add(COLLADA_ELEMENT_TECHNIQUE));
384 ptec->setProfile(
"OpenRAVE");
385 daeElementRef frame_origin = ptec->add(
"frame_origin");
386 frame_origin->setAttribute(
"link",(kmodelid+_GetLinkSid(kmout->maplinknames[itmanip->basename])).c_str());
387 daeElementRef frame_tip = ptec->add(
"frame_tip");
388 frame_tip->setAttribute(
"link",(kmodelid+_GetLinkSid(kmout->maplinknames[itmanip->effectorname])).c_str());
389 _WriteTransformation(frame_tip,itmanip->rotation, itmanip->translation);
390 BOOST_ASSERT(itmanip->gripperdir.size() == itmanip->grippernames.size());
391 std::list<std::string>::const_iterator itgripperdir = itmanip->gripperdir.begin();
392 std::list<std::string>::const_iterator itgrippername = itmanip->grippernames.begin();
393 while(itgrippername != itmanip->grippernames.end() ) {
394 daeElementRef gripper_joint = ptec->add(
"gripper_joint");
395 gripper_joint->setAttribute(
"joint", str(boost::format(
"%sjointsid%d")%kmodelid%kmout->mapjointnames[*itgrippername]).c_str());
396 daeElementRef closing_direction = gripper_joint->add(
"closing_direction");
397 closing_direction->setAttribute(
"axis",
"./axis0");
398 closing_direction->add(
"float")->setCharData(*itgripperdir);
404 boost::shared_ptr<instance_physics_model_output> ipmout = _WriteInstance_physics_model(bodyInfo,_scene.pscene,_scene.pscene->getID());
416 for(
size_t ilink = 0; ilink < links->length(); ++ilink) {
417 LinkInfo& linkInfo = links[ilink];
418 for(
size_t isensor = 0; isensor < linkInfo.sensors.length(); ++isensor) {
419 SensorInfo& sensor = linkInfo.sensors[isensor];
420 daeElementRef domsensor = WriteSensor(sensor, bodyInfo->
name());
422 domExtraRef extra_attach_sensor = daeSafeCast<domExtra>(articulated_system_motion->add(COLLADA_ELEMENT_EXTRA));
423 extra_attach_sensor->setName(sensor.name);
424 extra_attach_sensor->setType(
"attach_sensor");
425 domTechniqueRef attach_sensor = daeSafeCast<domTechnique>(extra_attach_sensor->add(COLLADA_ELEMENT_TECHNIQUE));
426 attach_sensor->setProfile(
"OpenRAVE");
428 string strurl = str(boost::format(
"#%s")%domsensor->getID());
429 daeElementRef isensor0 = attach_sensor->add(
"instance_sensor");
430 isensor0->setAttribute(
"url",strurl.c_str());
432 daeElementRef frame_origin = attach_sensor->add(
"frame_origin");
433 frame_origin->setAttribute(
"link",(kmodelid+_GetLinkSid(kmout->maplinknames[
string(linkInfo.segments[0].name)])).c_str());
434 if(
string(domsensor->getAttribute(
"type")).
find(
"camera") != string::npos ) {
436 DblArray4 rotation; rotation[0] = 1; rotation[1] = 0; rotation[2] = 0; rotation[3] =
M_PI;
437 _SetRotate(daeSafeCast<domRotate>(frame_origin->add(COLLADA_ELEMENT_ROTATE,0)), rotation);
439 _WriteTransformation(frame_origin,sensor.rotation, sensor.translation);
444 std::vector< pair<int, int> > vjointids(links->length());
445 for(
size_t ilink = 0; ilink < links->length(); ++ilink) {
446 vjointids[ilink].first = ilink;
447 vjointids[ilink].second = links[ilink].jointId;
449 sort(vjointids.begin(),vjointids.end(),ComparePair);
450 for(
size_t ipair = 0; ipair < vjointids.size(); ++ipair) {
451 size_t ilink = vjointids[ipair].first;
452 LinkInfo& linkInfo = links[ilink];
453 daeElementRef domactuator = WriteActuator(linkInfo, bodyInfo->
name());
455 domExtraRef extra_attach_actuator = daeSafeCast<domExtra>(articulated_system_motion->add(COLLADA_ELEMENT_EXTRA));
456 extra_attach_actuator->setName(linkInfo.name);
457 extra_attach_actuator->setType(
"attach_actuator");
458 domTechniqueRef attach_actuator = daeSafeCast<domTechnique>(extra_attach_actuator->add(COLLADA_ELEMENT_TECHNIQUE));
459 attach_actuator->setProfile(
"OpenRAVE");
461 string strurl = str(boost::format(
"#%s")%domactuator->getID());
462 daeElementRef iactuator = attach_actuator->add(
"instance_actuator");
463 iactuator->setAttribute(
"url",strurl.c_str());
464 attach_actuator->add(
"bind_actuator")->setAttribute(
"joint",str(boost::format(
"%sjointsid%d")%kmodelid%kmout->mapjointnames[
string(linkInfo.name)]).c_str());
473 COLLADALOG_VERBOSE(str(boost::format(
"writing instance_kinematics_model (%d) %s\n")%_GetRobotId(bodyInfo)%bodyInfo->
name()));
474 boost::shared_ptr<kinematics_model_output> kmout = WriteKinematics_model(bodyInfo);
477 ikmout->kmout = kmout;
478 ikmout->ikm = daeSafeCast<domInstance_kinematics_model>(parent->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_MODEL));
480 string symscope, refscope;
481 if( sidscope.size() > 0 ) {
482 symscope = sidscope+string(
"_");
483 refscope = sidscope+string(
"/");
485 string ikmsid = str(boost::format(
"%s_inst")%kmout->kmodel->getID());
486 ikmout->ikm->setUrl(str(boost::format(
"#%s")%kmout->kmodel->getID()).c_str());
487 ikmout->ikm->setSid(ikmsid.c_str());
489 domKinematics_newparamRef kbind = daeSafeCast<domKinematics_newparam>(ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
490 kbind->setSid((symscope+ikmsid).c_str());
491 daeSafeCast<domKinematics_newparam::domSIDREF>(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid).c_str());
492 ikmout->vkinematicsbindings.push_back(make_pair(
string(kbind->getSid()), str(boost::format(
"visual%d/node0")%_GetRobotId(bodyInfo))));
493 LinkInfoSequence_var links = bodyInfo->
links();
494 ikmout->vaxissids.reserve(kmout->vaxissids.size());
496 for(std::vector<kinematics_model_output::axis_output>::iterator it = kmout->vaxissids.begin(); it != kmout->vaxissids.end(); ++it) {
497 domKinematics_newparamRef kbind = daeSafeCast<domKinematics_newparam>(ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
498 string ref = it->sid;
499 size_t index = ref.find(
"/");
500 while(index != string::npos) {
502 index = ref.find(
"/",index+1);
504 string sid = symscope+ikmsid+
"_"+ref;
505 kbind->setSid(sid.c_str());
506 daeSafeCast<domKinematics_newparam::domSIDREF>(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid+
"/"+it->sid).c_str());
507 domKinematics_newparamRef pvalueparam = daeSafeCast<domKinematics_newparam>(ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM));
508 pvalueparam->setSid((sid+
string(
"_value")).c_str());
509 daeSafeCast<domKinematics_newparam::domFloat>(pvalueparam->add(COLLADA_ELEMENT_FLOAT))->setValue(links[it->ijoint].jointValue);
510 ikmout->vaxissids.push_back(
axis_sids(sid,pvalueparam->getSid(),kmout->vaxissids.at(i).jointnodesid));
519 boost::shared_ptr<physics_model_output> pmout = WritePhysics_model(bodyInfo);
521 ipmout->pmout = pmout;
522 ipmout->ipm = daeSafeCast<domInstance_physics_model>(parent->add(COLLADA_ELEMENT_INSTANCE_PHYSICS_MODEL));
523 ipmout->ipm->setParent(xsAnyURI(*ipmout->ipm,
string(
"#")+_GetNodeId(bodyInfo)));
524 string symscope, refscope;
525 if( sidscope.size() > 0 ) {
526 symscope = sidscope+string(
"_");
527 refscope = sidscope+string(
"/");
529 string ipmsid = str(boost::format(
"%s_inst")%pmout->pmodel->getID());
530 ipmout->ipm->setUrl(str(boost::format(
"#%s")%pmout->pmodel->getID()).c_str());
531 ipmout->ipm->setSid(ipmsid.c_str());
532 for(
size_t i = 0;
i < pmout->vrigidbodysids.size(); ++
i) {
533 domInstance_rigid_bodyRef pirb = daeSafeCast<domInstance_rigid_body>(ipmout->ipm->add(COLLADA_ELEMENT_INSTANCE_RIGID_BODY));
534 pirb->setBody(pmout->vrigidbodysids[
i].c_str());
535 pirb->setTarget(xsAnyURI(*pirb,str(boost::format(
"#%s")%_GetNodeId(bodyInfo,
i))));
538 if ( pmout->vrigidbodysids.size() >= 0) {
539 LinkInfoSequence_var links = bodyInfo->
links();
540 if ( links->length() > 0 ) {
541 LinkInfo& linkInfo = links[0];
542 string jointType(CORBA::String_var(linkInfo.jointType));
543 if ( jointType ==
"fixed" ) {
544 domInstance_rigid_constraintRef pirc = daeSafeCast<domInstance_rigid_constraint>(ipmout->ipm->add(COLLADA_ELEMENT_INSTANCE_RIGID_CONSTRAINT));
545 pirc->setConstraint(
"rigid_constraint0");
553 boost::shared_ptr<kinematics_model_output> kmout = _GetKinematics_model(bodyInfo);
558 domKinematics_modelRef kmodel = daeSafeCast<domKinematics_model>(_kinematicsModelsLib->add(COLLADA_ELEMENT_KINEMATICS_MODEL));
559 string kmodelid = str(boost::format(
"kmodel%d")%_GetRobotId(bodyInfo));
560 kmodel->setId(kmodelid.c_str());
561 kmodel->setName(bodyInfo->
name());
563 domKinematics_model_techniqueRef ktec = daeSafeCast<domKinematics_model_technique>(kmodel->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
566 domNodeRef pnoderoot = daeSafeCast<domNode>(_scene.vscene->add(COLLADA_ELEMENT_NODE));
567 string bodyid = _GetNodeId(bodyInfo);
568 pnoderoot->setId(bodyid.c_str());
569 pnoderoot->setSid(bodyid.c_str());
570 pnoderoot->setName(bodyInfo->
name());
572 LinkInfoSequence_var links = bodyInfo->
links();
573 vector<domJointRef> vdomjoints(links->length());
575 kmout->kmodel = kmodel;
576 kmout->vaxissids.resize(0);
577 kmout->vlinksids.resize(links->length());
580 kmout->mapjointnames[std::string(links[0].
name)] = 1000;
581 for(
size_t ilink = 0; ilink < vdomjoints.size(); ++ilink) {
582 LinkInfo& linkInfo = links[ilink];
583 if (!linkInfo.segments.length()){
584 std::cerr <<
"Collada Warning: segment node for " << ilink <<
"th joint is not defined" << std::endl;
586 kmout->maplinknames[std::string(linkInfo.segments[0].name)] = ilink;
588 string jointType(CORBA::String_var(linkInfo.jointType));
589 daeString colladaelement;
592 vector<dReal> lmin, lmax;
593 if( jointType ==
"fixed" ) {
594 colladaelement = COLLADA_ELEMENT_REVOLUTE;
599 if( jointType ==
"rotate" ) {
600 colladaelement = COLLADA_ELEMENT_REVOLUTE;
603 else if( jointType ==
"slide" ) {
604 colladaelement = COLLADA_ELEMENT_PRISMATIC;
607 COLLADALOG_INFO(str(boost::format(
"joint type %s not supported")%jointType));
610 if( linkInfo.llimit.length() > 0 ) {
611 lmin.push_back(fmult*linkInfo.llimit[0]);
613 if( linkInfo.ulimit.length() > 0 ) {
614 lmax.push_back(fmult*linkInfo.ulimit[0]);
618 if ( linkInfo.jointId >= 0 ) {
619 kmout->mapjointnames[std::string(linkInfo.name)] = linkInfo.jointId;
621 kmout->mapjointnames[std::string(linkInfo.name)] = 1000+ilink;
624 domJointRef pdomjoint = daeSafeCast<domJoint>(ktec->add(COLLADA_ELEMENT_JOINT));
625 string jointsid = str(boost::format(
"jointsid%d")%kmout->mapjointnames[std::string(linkInfo.name)]);
626 pdomjoint->setSid( jointsid.c_str() );
628 pdomjoint->setName(linkInfo.name);
629 vector<domAxis_constraintRef> vaxes(dof);
630 for(
int ia = 0; ia < dof; ++ia) {
631 vaxes[ia] = daeSafeCast<domAxis_constraint>(pdomjoint->add(colladaelement));
632 string axisid = str(boost::format(
"axis%d")%ia);
633 vaxes[ia]->setSid(axisid.c_str());
636 axissid.
sid = jointsid+string(
"/")+axisid;
638 axissid.
jointnodesid = str(boost::format(
"%s/%s")%bodyid%_GetJointNodeSid(ilink,ia));
639 kmout->vaxissids.push_back(axissid);
640 domAxisRef paxis = daeSafeCast<domAxis>(vaxes.at(ia)->add(COLLADA_ELEMENT_AXIS));
641 paxis->getValue().setCount(3);
642 paxis->getValue()[0] = linkInfo.jointAxis[0];
643 paxis->getValue()[1] = linkInfo.jointAxis[1];
644 paxis->getValue()[2] = linkInfo.jointAxis[2];
645 if( lmin.size() > 0 || lmax.size() > 0 ) {
646 domJoint_limitsRef plimits = daeSafeCast<domJoint_limits>(vaxes[ia]->add(COLLADA_TYPE_LIMITS));
647 if( ia < (
int)lmin.size() ) {
648 daeSafeCast<domMinmax>(plimits->add(COLLADA_ELEMENT_MIN))->getValue() = lmin.at(ia);
650 if( ia < (
int)lmax.size() ) {
651 daeSafeCast<domMinmax>(plimits->add(COLLADA_ELEMENT_MAX))->getValue() = lmax.at(ia);
655 vdomjoints.at(ilink) = pdomjoint;
658 list<int> listunusedlinks;
659 for(
unsigned int i = 0;
i < links->length(); ++
i) {
660 listunusedlinks.push_back(
i);
663 while(listunusedlinks.size()>0) {
664 int ilink = listunusedlinks.front();
665 LINKOUTPUT childinfo = _WriteLink(bodyInfo, ilink, ktec, pnoderoot, kmodel->getID(), kmout->mapjointnames);
666 _WriteTransformation(childinfo.
plink, links[ilink].rotation, links[ilink].translation);
667 _WriteTransformation(childinfo.
pnode, links[ilink].rotation, links[ilink].translation);
668 for(list<pair<int,std::string> >::iterator itused = childinfo.
listusedlinks.begin(); itused != childinfo.
listusedlinks.end(); ++itused) {
669 kmout->vlinksids.at(itused->first) = itused->second;
670 listunusedlinks.remove(itused->first);
700 _AddKinematics_model(bodyInfo,kmout);
705 boost::shared_ptr<physics_model_output> pmout = _GetPhysics_model(bodyInfo);
710 pmout->pmodel = daeSafeCast<domPhysics_model>(_physicsModelsLib->add(COLLADA_ELEMENT_PHYSICS_MODEL));
711 string pmodelid = str(boost::format(
"pmodel%d")%_GetRobotId(bodyInfo));
712 pmout->pmodel->setId(pmodelid.c_str());
713 pmout->pmodel->setName(bodyInfo->
name());
714 LinkInfoSequence_var links = bodyInfo->
links();
715 for(
unsigned int ilink = 0; ilink < links->length(); ++ilink) {
716 LinkInfo& link = links[ilink];
717 domRigid_bodyRef rigid_body = daeSafeCast<domRigid_body>(pmout->pmodel->add(COLLADA_ELEMENT_RIGID_BODY));
718 string rigidsid = str(boost::format(
"rigid%d")%ilink);
719 pmout->vrigidbodysids.push_back(rigidsid);
720 rigid_body->setId(rigidsid.c_str());
721 rigid_body->setSid(rigidsid.c_str());
722 rigid_body->setName(link.segments[0].name);
723 domRigid_body::domTechnique_commonRef ptec = daeSafeCast<domRigid_body::domTechnique_common>(rigid_body->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
724 domTargetable_floatRef mass = daeSafeCast<domTargetable_float>(ptec->add(COLLADA_ELEMENT_MASS));
725 mass->setValue(link.mass);
729 inertia(0,0) = link.inertia[0]; inertia(0,1) = link.inertia[1]; inertia(0,2) = link.inertia[2];
730 inertia(1,0) = link.inertia[3]; inertia(1,1) = link.inertia[4]; inertia(1,2) = link.inertia[5];
731 inertia(2,0) = link.inertia[6]; inertia(2,1) = link.inertia[7]; inertia(2,2) = link.inertia[8];
735 if (
det(evec) < 0.0) {
737 evec(2,0) *= -1.0; evec(2,1) *= -1.0; evec(2,2) *= -1.0;
739 DblArray12 tinertiaframe;
740 for(
int j = 0;
j < 3; ++
j) {
742 tinertiaframe[4*0+
j] = evec(
j, 0);
743 tinertiaframe[4*1+
j] = evec(
j, 1);
744 tinertiaframe[4*2+
j] = evec(
j, 2);
746 DblArray4 quat, rotation;
747 DblArray3 translation;
750 domTargetable_float3Ref pdominertia = daeSafeCast<domTargetable_float3>(ptec->add(COLLADA_ELEMENT_INERTIA));
751 pdominertia->getValue().setCount(3);
752 pdominertia->getValue()[0] = eval[0]; pdominertia->getValue()[1] = eval[1]; pdominertia->getValue()[2] = eval[2];
753 daeElementRef mass_frame = ptec->add(COLLADA_ELEMENT_MASS_FRAME);
754 _WriteTransformation(mass_frame, rotation, link.centerOfMass);
756 int icurlink = ilink;
757 while(icurlink > 0) {
758 _WriteTransformation(mass_frame, links[icurlink].rotation, links[icurlink].translation);
759 icurlink = links[icurlink].parentIndex;
763 for(
unsigned int igeom = 0; igeom < link.shapeIndices.length(); ++igeom) {
764 const TransformedShapeIndex& tsi = link.shapeIndices[igeom];
765 DblArray12 transformMatrix;
766 if( tsi.inlinedShapeTransformMatrixIndex >= 0 ) {
767 PoseMult(transformMatrix, link.inlinedShapeTransformMatrices[tsi.inlinedShapeTransformMatrixIndex],tsi.transformMatrix);
770 for(
int i = 0;
i < 12; ++
i) {
771 transformMatrix[
i] = tsi.transformMatrix[
i];
774 domRigid_body::domTechnique_common::domShapeRef pdomshape = daeSafeCast<domRigid_body::domTechnique_common::domShape>(ptec->add(COLLADA_ELEMENT_SHAPE));
778 translation[0] = transformMatrix[4*0+3]; translation[1] = transformMatrix[4*1+3]; translation[2] = transformMatrix[4*2+3];
779 _WriteTransformation(pdomshape,rotation,translation);
781 while(icurlink >= 0) {
782 _WriteTransformation(pdomshape, links[icurlink].rotation, links[icurlink].translation);
783 icurlink = links[icurlink].parentIndex;
785 domInstance_geometryRef pinstgeom = daeSafeCast<domInstance_geometry>(pdomshape->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
786 pinstgeom->setUrl(xsAnyURI(*pinstgeom,
string(
"#")+_GetGeometryId(bodyInfo, ilink,igeom)));
789 if ( links->length() > 0 && std::string(CORBA::String_var(links[0].jointType)) == std::string(
"fixed") ) {
790 domRigid_constraintRef rigid_constraint = daeSafeCast<domRigid_constraint>(pmout->pmodel->add(COLLADA_ELEMENT_RIGID_CONSTRAINT));
791 rigid_constraint->setSid(
"rigid_constraint0");
792 rigid_constraint->setName(links[0].segments[0].
name);
793 domRigid_constraint::domAttachmentRef patt = daeSafeCast<domRigid_constraint::domAttachment>(rigid_constraint->add(COLLADA_TYPE_ATTACHMENT));
794 patt->setRigid_body(
"#rigid0");
795 domRigid_constraint::domRef_attachmentRef prefatt = daeSafeCast<domRigid_constraint::domRef_attachment>(rigid_constraint->add(COLLADA_TYPE_REF_ATTACHMENT));
796 prefatt->setRigid_body(
"#visual1");
805 virtual domGeometryRef
WriteGeometry(
BodyInfo_impl* bodyInfo,
const ShapeInfo& shapeInfo,
const DblArray12& transformMatrix,
const string& parentid)
807 const FloatSequence& vertices = shapeInfo.vertices;
808 const LongSequence& triangles = shapeInfo.triangles;
809 string effid = parentid+string(
"_eff");
810 string matid = parentid+string(
"_mat");
811 string texid = parentid+string(
"_tex");
813 AppearanceInfo& appearanceInfo = (*bodyInfo->
appearances())[shapeInfo.appearanceIndex];
814 const FloatSequence& normals = appearanceInfo.normals;
815 const FloatSequence& textures = appearanceInfo.textureCoordinate;
816 domEffectRef pdomeff;
817 if ( appearanceInfo.materialIndex < 0 ) {
818 MaterialInfo matInfo;
819 pdomeff = WriteEffect(matInfo);
821 pdomeff = WriteEffect((*bodyInfo->
materials())[appearanceInfo.materialIndex]);
823 pdomeff->setId(effid.c_str());
825 if ( appearanceInfo.textureIndex >= 0 ) {
826 TextureInfo texture = (*bodyInfo->
textures())[appearanceInfo.textureIndex];
828 domProfile_commonRef pprofile = daeSafeCast<domProfile_common>(pdomeff->getDescendant(daeElement::matchType(domProfile_common::ID())));
830 domFx_common_newparamRef pparam = daeSafeCast<domFx_common_newparam>(pprofile->add(COLLADA_ELEMENT_NEWPARAM));
831 pparam->setSid(
"file1-sampler");
832 domFx_sampler2DRef psampler = daeSafeCast<domFx_sampler2D>(pparam->add(COLLADA_ELEMENT_SAMPLER2D));
833 daeElementRef psurface = pparam->add(
"surface");
834 daeSafeCast<domInstance_image>(psampler->add(
"instance_image"))->setUrl(
string(
"#"+texid).c_str());
835 psampler->add(
"minfilter")->setCharData(
"LINEAR_MIPMAP_LINEAR");
836 psampler->add(
"magfilter")->setCharData(
"LINEAR");
838 domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast<domProfile_common::domTechnique::domPhong>(pdomeff->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domPhong::ID())));
840 domFx_common_color_or_textureRef pdiffuse = daeSafeCast<domFx_common_color_or_texture>(pphong->getDescendant(daeElement::matchType(domFx_common_color_or_texture::ID())));
841 pphong->removeFromParent(pphong->getDiffuse());
844 domFx_common_color_or_textureRef pdiffuse = daeSafeCast<domFx_common_color_or_texture>(pphong->add(COLLADA_ELEMENT_DIFFUSE));
845 domFx_common_color_or_texture::domTextureRef pdiffusetexture = daeSafeCast<domFx_common_color_or_texture::domTexture>(pdiffuse->add(COLLADA_ELEMENT_TEXTURE));
846 pdiffusetexture->setAttribute(
"texture",
"file1-sampler");
847 pdiffusetexture->setAttribute(
"texcoord",
"TEX0");
850 pdomtex = WriteTexture((*bodyInfo->
textures())[appearanceInfo.textureIndex]);
851 pdomtex->setId(texid.c_str());
854 domMaterialRef pdommat = daeSafeCast<domMaterial>(_materialsLib->add(COLLADA_ELEMENT_MATERIAL));
855 pdommat->setId(matid.c_str());
856 domInstance_effectRef pdominsteff = daeSafeCast<domInstance_effect>(pdommat->add(COLLADA_ELEMENT_INSTANCE_EFFECT));
857 pdominsteff->setUrl((
string(
"#")+effid).c_str());
860 if( shapeInfo.primitiveType != SP_MESH ) {
861 COLLADALOG_WARN(
"shape index is not SP_MESH type, could result in inaccuracies");
863 domGeometryRef pdomgeom = daeSafeCast<domGeometry>(_geometriesLib->add(COLLADA_ELEMENT_GEOMETRY));
865 pdomgeom->setId(parentid.c_str());
866 domMeshRef pdommesh = daeSafeCast<domMesh>(pdomgeom->add(COLLADA_ELEMENT_MESH));
868 domSourceRef pvertsource = daeSafeCast<domSource>(pdommesh->add(COLLADA_ELEMENT_SOURCE));
870 pvertsource->setId((parentid+
string(
"_positions")).c_str());
872 domFloat_arrayRef parray = daeSafeCast<domFloat_array>(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY));
873 parray->setId((parentid+
string(
"_positions-array")).c_str());
874 parray->setCount(vertices.length());
875 parray->setDigits(6);
876 parray->getValue().setCount(vertices.length());
878 for(
size_t ind = 0; ind < vertices.length(); ind += 3) {
880 v[0] = vertices[ind]; v[1] = vertices[ind+1]; v[2] = vertices[ind+2];
882 parray->getValue()[ind+0] = vnew[0];
883 parray->getValue()[ind+1] = vnew[1];
884 parray->getValue()[ind+2] = vnew[2];
887 domSource::domTechnique_commonRef psourcetec = daeSafeCast<domSource::domTechnique_common>(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
888 domAccessorRef pacc = daeSafeCast<domAccessor>(psourcetec->add(COLLADA_ELEMENT_ACCESSOR));
889 pacc->setCount(vertices.length()/3);
890 pacc->setSource(xsAnyURI(*pacc,
string(
"#")+parentid+
string(
"_positions-array")));
893 domParamRef px = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
894 px->setName(
"X"); px->setType(
"float");
895 domParamRef py = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
896 py->setName(
"Y"); py->setType(
"float");
897 domParamRef pz = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
898 pz->setName(
"Z"); pz->setType(
"float");
901 domVerticesRef pverts = daeSafeCast<domVertices>(pdommesh->add(COLLADA_ELEMENT_VERTICES));
903 pverts->setId(
"vertices");
904 domInput_localRef pvertinput = daeSafeCast<domInput_local>(pverts->add(COLLADA_ELEMENT_INPUT));
905 pvertinput->setSemantic(
"POSITION");
906 pvertinput->setSource(domUrifragment(*pvertsource,
string(
"#")+parentid+
string(
"_positions")));
909 domSourceRef pnormsource = daeSafeCast<domSource>(pdommesh->add(COLLADA_ELEMENT_SOURCE));
910 if ( normals.length() > 0 && appearanceInfo.normalIndices.length() > 0 )
912 pnormsource->setId((parentid+
string(
"_normals")).c_str());
914 domFloat_arrayRef parray = daeSafeCast<domFloat_array>(pnormsource->add(COLLADA_ELEMENT_FLOAT_ARRAY));
915 parray->setId((parentid+
string(
"_normals-array")).c_str());
916 parray->setCount(normals.length());
917 parray->setDigits(6);
918 parray->getValue().setCount(normals.length());
920 for(
size_t ind = 0; ind < normals.length(); ++ind) {
921 parray->getValue()[ind] = normals[ind];
924 domSource::domTechnique_commonRef psourcetec = daeSafeCast<domSource::domTechnique_common>(pnormsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
925 domAccessorRef pacc = daeSafeCast<domAccessor>(psourcetec->add(COLLADA_ELEMENT_ACCESSOR));
926 pacc->setCount(normals.length()/3);
927 pacc->setSource(xsAnyURI(*pacc,
string(
"#")+parentid+
string(
"_normals-array")));
930 domParamRef px = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
931 px->setName(
"X"); px->setType(
"float");
932 domParamRef py = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
933 py->setName(
"Y"); py->setType(
"float");
934 domParamRef pz = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
935 pz->setName(
"Z"); pz->setType(
"float");
938 domSourceRef ptexsource = daeSafeCast<domSource>(pdommesh->add(COLLADA_ELEMENT_SOURCE));
939 if ( textures.length() > 0 && appearanceInfo.textureCoordIndices.length() >= 0 )
941 ptexsource->setId((parentid+
string(
"_texcoords")).c_str());
943 domFloat_arrayRef parray = daeSafeCast<domFloat_array>(ptexsource->add(COLLADA_ELEMENT_FLOAT_ARRAY));
944 parray->setId((parentid+
string(
"_texcoords-array")).c_str());
945 parray->setCount(textures.length());
946 parray->setDigits(6);
947 parray->getValue().setCount(textures.length());
949 for(
size_t ind = 0; ind < textures.length(); ++ind) {
950 parray->getValue()[ind] = textures[ind];
953 domSource::domTechnique_commonRef psourcetec = daeSafeCast<domSource::domTechnique_common>(ptexsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
954 domAccessorRef pacc = daeSafeCast<domAccessor>(psourcetec->add(COLLADA_ELEMENT_ACCESSOR));
955 pacc->setCount(vertices.length()/2);
956 pacc->setSource(xsAnyURI(*pacc,
string(
"#")+parentid+
string(
"_textures-array")));
959 domParamRef ps = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
960 ps->setName(
"S"); ps->setType(
"float");
961 domParamRef pt = daeSafeCast<domParam>(pacc->add(COLLADA_ELEMENT_PARAM));
962 pt->setName(
"T"); pt->setType(
"float");
965 domTrianglesRef ptris = daeSafeCast<domTriangles>(pdommesh->add(COLLADA_ELEMENT_TRIANGLES));
968 ptris->setCount(triangles.length()/3);
969 ptris->setMaterial(
"mat0");
971 domInput_local_offsetRef pvertoffset = daeSafeCast<domInput_local_offset>(ptris->add(COLLADA_ELEMENT_INPUT));
972 pvertoffset->setSemantic(
"VERTEX");
973 pvertoffset->setOffset(offset++);
974 pvertoffset->setSource(domUrifragment(*pverts,
string(
"#")+parentid+
string(
"/vertices")));
976 domPRef pindices = daeSafeCast<domP>(ptris->add(COLLADA_ELEMENT_P));
978 if ( normals.length() > 0 && appearanceInfo.normalIndices.length() > 0 ){
979 domInput_local_offsetRef pnormoffset = daeSafeCast<domInput_local_offset>(ptris->add(COLLADA_ELEMENT_INPUT));
980 pnormoffset->setSemantic(
"NORMAL");
981 pnormoffset->setOffset(offset++);
982 pnormoffset->setSource(domUrifragment(*pverts,
string(
"#")+parentid+
string(
"_normals")));
985 if ( textures.length() > 0 && appearanceInfo.textureCoordIndices.length() > 0 ){
986 domInput_local_offsetRef ptexoffset = daeSafeCast<domInput_local_offset>(ptris->add(COLLADA_ELEMENT_INPUT));
987 ptexoffset->setSemantic(
"TEXCOORD");
988 ptexoffset->setOffset(offset++);
989 ptexoffset->setSource(domUrifragment(*pverts,
string(
"#")+parentid+
string(
"_texcoords")));
991 pindices->getValue().setCount(triangles.length()*offset);
993 for(
size_t ind = 0; ind < triangles.length(); ++ind) {
994 int i = ind * offset;
995 pindices->getValue()[i++] = triangles[ind];
996 if ( normals.length() > 0 && appearanceInfo.normalIndices.length() > 0 ){
997 if ( appearanceInfo.normalPerVertex == 1 ) {
998 pindices->getValue()[i++] = appearanceInfo.normalIndices[ind];
1000 pindices->getValue()[i++] = appearanceInfo.normalIndices[triangles[ind]/3];
1003 if (textures.length() > 0 && appearanceInfo.textureCoordIndices.length() > 0 ){
1004 pindices->getValue()[i++] = appearanceInfo.textureCoordIndices[ind];
1019 domEffectRef pdomeff = daeSafeCast<domEffect>(_effectsLib->add(COLLADA_ELEMENT_EFFECT));
1021 domProfile_commonRef pprofile = daeSafeCast<domProfile_common>(pdomeff->add(COLLADA_ELEMENT_PROFILE_COMMON));
1023 domProfile_common::domTechniqueRef ptec = daeSafeCast<domProfile_common::domTechnique>(pprofile->add(COLLADA_ELEMENT_TECHNIQUE));
1025 domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast<domProfile_common::domTechnique::domPhong>(ptec->add(COLLADA_ELEMENT_PHONG));
1027 domFx_common_color_or_textureRef pambient = daeSafeCast<domFx_common_color_or_texture>(pphong->add(COLLADA_ELEMENT_AMBIENT));
1028 domFx_common_color_or_texture::domColorRef pambientcolor = daeSafeCast<domFx_common_color_or_texture::domColor>(pambient->add(COLLADA_ELEMENT_COLOR));
1029 pambientcolor->getValue().setCount(4);
1030 pambientcolor->getValue()[0] = material.diffuseColor[0];
1031 pambientcolor->getValue()[1] = material.diffuseColor[1];
1032 pambientcolor->getValue()[2] = material.diffuseColor[2];
1033 pambientcolor->getValue()[3] = 1;
1035 domFx_common_color_or_textureRef pdiffuse = daeSafeCast<domFx_common_color_or_texture>(pphong->add(COLLADA_ELEMENT_DIFFUSE));
1036 domFx_common_color_or_texture::domColorRef pdiffusecolor = daeSafeCast<domFx_common_color_or_texture::domColor>(pdiffuse->add(COLLADA_ELEMENT_COLOR));
1037 pdiffusecolor->getValue().setCount(4);
1038 pdiffusecolor->getValue()[0] = material.diffuseColor[0];
1039 pdiffusecolor->getValue()[1] = material.diffuseColor[1];
1040 pdiffusecolor->getValue()[2] = material.diffuseColor[2];
1041 pdiffusecolor->getValue()[3] = 1;
1043 domFx_common_color_or_textureRef pspecular = daeSafeCast<domFx_common_color_or_texture>(pphong->add(COLLADA_ELEMENT_SPECULAR));
1044 domFx_common_color_or_texture::domColorRef pspecularcolor = daeSafeCast<domFx_common_color_or_texture::domColor>(pspecular->add(COLLADA_ELEMENT_COLOR));
1045 pspecularcolor->getValue().setCount(4);
1046 pspecularcolor->getValue()[0] = material.specularColor[0];
1047 pspecularcolor->getValue()[1] = material.specularColor[1];
1048 pspecularcolor->getValue()[2] = material.specularColor[2];
1049 pspecularcolor->getValue()[3] = 1;
1051 domFx_common_color_or_textureRef pemission = daeSafeCast<domFx_common_color_or_texture>(pphong->add(COLLADA_ELEMENT_EMISSION));
1052 domFx_common_color_or_texture::domColorRef pemissioncolor = daeSafeCast<domFx_common_color_or_texture::domColor>(pemission->add(COLLADA_ELEMENT_COLOR));
1053 pemissioncolor->getValue().setCount(4);
1054 pemissioncolor->getValue()[0] = material.emissiveColor[0];
1055 pemissioncolor->getValue()[1] = material.emissiveColor[1];
1056 pemissioncolor->getValue()[2] = material.emissiveColor[2];
1057 pemissioncolor->getValue()[3] = 1;
1067 domImageRef pdomimg = daeSafeCast<domImage>(_imagesLib->add(COLLADA_ELEMENT_IMAGE));
1068 pdomimg->setName(texture.url);
1069 domImage::domInit_fromRef pdominitfrom = daeSafeCast<domImage::domInit_from>(pdomimg->add(COLLADA_ELEMENT_INIT_FROM));
1070 if ( ! pdominitfrom->setCharData(
string(texture.url)) ) {
1071 domImage_source::domRefRef pdomref = daeSafeCast<domImage_source::domRef>(pdominitfrom->add(COLLADA_ELEMENT_REF));
1072 pdomref->setValue(texture.url);
1077 virtual daeElementRef
WriteSensor(
const SensorInfo& sensor,
const string& parentid)
1079 daeElementRef domsensor = _sensorsLib->add(
"sensor");
1080 _nextsensorid++; domsensor->setAttribute(
"id",str(boost::format(
"sensor%d")%_nextsensorid).c_str());
1083 domsensor->setAttribute(
"sid",str(boost::format(
"%d")%sensor.id).c_str());
1084 if( vrmltype ==
"force" ) {
1085 domsensor->setAttribute(
"type",
"base_force6d");
1086 domsensor->add(
"load_range_force")->setCharData(str(boost::format(
"%f %f %f")%sensor.specValues[0]%sensor.specValues[1]%sensor.specValues[2]));
1087 domsensor->add(
"load_range_torque")->setCharData(str(boost::format(
"%f %f %f")%sensor.specValues[3]%sensor.specValues[4]%sensor.specValues[5]));
1089 else if( vrmltype ==
"rategyro") {
1090 domsensor->setAttribute(
"type",
"base_imu");
1091 domsensor->add(
"max_angular_velocity")->setCharData(str(boost::format(
"%f %f %f")%sensor.specValues[0]%sensor.specValues[1]%sensor.specValues[2]));
1093 else if( vrmltype ==
"acceleration" ) {
1094 domsensor->setAttribute(
"type",
"base_imu");
1095 domsensor->add(
"max_acceleration")->setCharData(str(boost::format(
"%f %f %f")%sensor.specValues[0]%sensor.specValues[1]%sensor.specValues[2]));
1097 else if( vrmltype ==
"vision" ) {
1098 domsensor->setAttribute(
"type",
"base_pinhole_camera");
1100 if( sensor.specValues.length() != 7 ) {
1101 COLLADALOG_WARN(str(boost::format(
"vision sensor has wrong number of values! %d!=7")%sensor.specValues.length()));
1103 domsensor->add(
"focal_length")->setCharData(str(boost::format(
"%f")%sensor.specValues[0]));
1104 double fieldOfView = sensor.specValues[2],
width = sensor.specValues[4],
height = sensor.specValues[5];
1105 stringstream sintrinsic; sintrinsic << std::setprecision(15);
1106 double fx = 0.5/(tanf(fieldOfView*0.5));
1108 domsensor->add(
"intrinsic")->setCharData(sintrinsic.str());
1109 stringstream simage_dimensions; simage_dimensions << (
int)
width <<
" " << (
int)
height <<
" ";
1110 string format =
"uint8";
1111 Camera::CameraType cameratype = Camera::CameraType((
int)sensor.specValues[3]);
1112 switch(cameratype) {
1117 simage_dimensions << 3;
1120 simage_dimensions << 1;
1123 simage_dimensions << 1;
1126 case Camera::COLOR_DEPTH:
1128 simage_dimensions << 4;
1130 case Camera::MONO_DEPTH:
1132 simage_dimensions << 2;
1135 domsensor->add(
"format")->setCharData(format);
1136 domsensor->add(
"image_dimensions")->setCharData(simage_dimensions.str());
1137 domsensor->add(
"measurement_time")->setCharData(str(boost::format(
"%f")%(1.0/sensor.specValues[6])));
1139 else if( vrmltype ==
"range" ) {
1140 domsensor->setAttribute(
"type",
"base_laser1d");
1141 domsensor->add(
"angle_range")->setCharData(str(boost::format(
"%f")%(sensor.specValues[0])));
1142 domsensor->add(
"angle_increment")->setCharData(str(boost::format(
"%f")%(sensor.specValues[1])));
1143 domsensor->add(
"measurement_time")->setCharData(str(boost::format(
"%f")%(1.0/sensor.specValues[2])));
1144 domsensor->add(
"distance_range")->setCharData(str(boost::format(
"%f")%(sensor.specValues[3])));
1149 virtual daeElementRef
WriteActuator(
const LinkInfo& plink,
const string& parentid)
1151 daeElementRef domactuator = _actuatorsLib->add(
"actuator");
1152 _nextactuatorid++; domactuator->setAttribute(
"id",str(boost::format(
"actuator%d")%_nextactuatorid).c_str());
1153 domactuator->setAttribute(
"type",
"electric_motor");
1154 domactuator->add(
"assigned_power_rating")->setCharData(
"1.0");
1155 double max_speed = plink.uvlimit.length()/2*
M_PI > 0 ? plink.uvlimit[0] : 0;
1156 domactuator->add(
"max_speed")->setCharData(str(boost::format(
"%f")%max_speed));
1157 domactuator->add(
"no_load_speed")->setCharData(str(boost::format(
"%f")%max_speed));
1158 double max_torque = (plink.climit.length() > 0 ? plink.climit[0] : 0)*plink.gearRatio*plink.torqueConst;
1159 domactuator->add(
"nominal_torque")->setCharData(str(boost::format(
"%f")%max_torque));
1160 domactuator->add(
"nominal_voltage")->setCharData(
"0");
1161 domactuator->add(
"rotor_inertia")->setCharData(str(boost::format(
"%f")%(plink.rotorInertia)));
1162 domactuator->add(
"speed_constant")->setCharData(
"0");
1163 domactuator->add(
"speed_torque_gradient")->setCharData(
"0");
1164 domactuator->add(
"starting_current")->setCharData(
"0");
1165 domactuator->add(
"terminal_resistance")->setCharData(str(boost::format(
"%f")%(plink.rotorResistor)));
1166 domactuator->add(
"torque_constant")->setCharData(str(boost::format(
"%f")%(plink.torqueConst)));
1167 domactuator->add(
"gear_ratio")->setCharData(str(boost::format(
"%f")%(plink.gearRatio)));
1168 domactuator->add(
"encoder_pulse")->setCharData(str(boost::format(
"%f")%(plink.encoderPulse)));
1179 _scene.vscene = daeSafeCast<domVisual_scene>(_visualScenesLib->add(COLLADA_ELEMENT_VISUAL_SCENE));
1180 _scene.vscene->setId(
"vscene");
1181 _scene.vscene->setName(
"OpenRAVE Visual Scene");
1184 _scene.kscene = daeSafeCast<domKinematics_scene>(_kinematicsScenesLib->add(COLLADA_ELEMENT_KINEMATICS_SCENE));
1185 _scene.kscene->setId(
"kscene");
1186 _scene.kscene->setName(
"OpenRAVE Kinematics Scene");
1189 _scene.pscene = daeSafeCast<domPhysics_scene>(_physicsScenesLib->add(COLLADA_ELEMENT_PHYSICS_SCENE));
1190 _scene.pscene->setId(
"pscene");
1191 _scene.pscene->setName(
"OpenRAVE Physics Scene");
1194 _scene.viscene = daeSafeCast<domInstance_with_extra>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_VISUAL_SCENE ));
1195 _scene.viscene->setUrl( (
string(
"#") +
string(_scene.vscene->getID())).c_str() );
1198 _scene.kiscene = daeSafeCast<domInstance_kinematics_scene>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_KINEMATICS_SCENE ));
1199 _scene.kiscene->setUrl( (
string(
"#") +
string(_scene.kscene->getID())).c_str() );
1202 _scene.piscene = daeSafeCast<domInstance_with_extra>(_globalscene->add( COLLADA_ELEMENT_INSTANCE_PHYSICS_SCENE ));
1203 _scene.piscene->setUrl( (
string(
"#") +
string(_scene.pscene->getID())).c_str() );
1214 virtual LINKOUTPUT _WriteLink(
BodyInfo_impl* bodyInfo,
int ilink, daeElementRef pkinparent, domNodeRef pnodeparent,
const string& strModelUri, std::map<std::string, int> mapjointnames)
1216 LinkInfo& plink = (*bodyInfo->
links())[ilink];
1218 string linksid = _GetLinkSid(ilink);
1219 domLinkRef pdomlink = daeSafeCast<domLink>(pkinparent->add(COLLADA_ELEMENT_LINK));
1220 pdomlink->setName(plink.segments[0].name);
1221 pdomlink->setSid(linksid.c_str());
1223 domNodeRef pnode = daeSafeCast<domNode>(pnodeparent->add(COLLADA_ELEMENT_NODE));
1224 std::string nodeid = _GetNodeId(bodyInfo,ilink);
1225 pnode->setId( nodeid.c_str() );
1226 string nodesid = str(boost::format(
"node%d")%ilink);
1227 pnode->setSid(nodesid.c_str());
1228 pnode->setName(plink.segments[0].name);
1229 ShapeInfoSequence* curShapeInfoSeq = bodyInfo->
shapes();
1231 for(
unsigned int igeom = 0; igeom < plink.shapeIndices.length(); ++igeom) {
1232 string geomid = _GetGeometryId(bodyInfo, ilink,igeom);
1233 const TransformedShapeIndex& tsi = plink.shapeIndices[igeom];
1234 DblArray12 transformMatrix;
1236 for(
int i = 0;
i < 12; ++
i) {
1237 transformMatrix[
i] = tsi.transformMatrix[
i];
1239 domGeometryRef pdomgeom = WriteGeometry(bodyInfo,(*curShapeInfoSeq)[tsi.shapeIndex], transformMatrix, geomid);
1240 domInstance_geometryRef pinstgeom = daeSafeCast<domInstance_geometry>(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
1241 pinstgeom->setUrl((
string(
"#")+geomid).c_str());
1243 domBind_materialRef pmat = daeSafeCast<domBind_material>(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL));
1244 domBind_material::domTechnique_commonRef pmattec = daeSafeCast<domBind_material::domTechnique_common>(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
1245 domInstance_materialRef pinstmat = daeSafeCast<domInstance_material>(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL));
1246 pinstmat->setTarget(xsAnyURI(*pinstmat,
string(
"#")+geomid+
string(
"_mat")));
1247 pinstmat->setSymbol(
"mat0");
1251 int igeomid = plink.shapeIndices.length();
1252 for(
size_t isensor = 0; isensor < plink.sensors.length(); ++isensor) {
1253 SensorInfo& sensor = plink.sensors[isensor];
1255 for(
unsigned int igeom = 0; igeom < sensor.shapeIndices.length(); ++igeom) {
1256 string geomid = _GetGeometryId(bodyInfo, ilink, igeomid++);
1258 const TransformedShapeIndex& tsi = sensor.shapeIndices[igeom];
1259 DblArray12 sensorMatrix, transformMatrix,sensorgeomMatrix;
1261 for(
int i = 0;
i < 12; ++
i) {
1262 sensorgeomMatrix[
i] = tsi.transformMatrix[
i];
1264 PoseMult(transformMatrix, sensorMatrix, sensorgeomMatrix);
1266 domGeometryRef pdomgeom = WriteGeometry(bodyInfo,(*bodyInfo->
shapes())[tsi.shapeIndex], transformMatrix, geomid);
1267 domInstance_geometryRef pinstgeom = daeSafeCast<domInstance_geometry>(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY));
1268 pinstgeom->setUrl((
string(
"#")+geomid).c_str());
1270 domBind_materialRef pmat = daeSafeCast<domBind_material>(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL));
1271 domBind_material::domTechnique_commonRef pmattec = daeSafeCast<domBind_material::domTechnique_common>(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON));
1272 domInstance_materialRef pinstmat = daeSafeCast<domInstance_material>(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL));
1273 pinstmat->setTarget(xsAnyURI(*pinstmat,
string(
"#")+geomid+
string(
"_mat")));
1274 pinstmat->setSymbol(
"mat0");
1279 for(
unsigned int _ichild = 0; _ichild < plink.childIndices.length(); ++_ichild) {
1280 int ichild = plink.childIndices[_ichild];
1281 LinkInfo& childlink = (*bodyInfo->
links())[ichild];
1282 domLink::domAttachment_fullRef pattfull = daeSafeCast<domLink::domAttachment_full>(pdomlink->add(COLLADA_TYPE_ATTACHMENT_FULL));
1284 string jointid = str(boost::format(
"%s/jointsid%d")%strModelUri%mapjointnames[
string(childlink.name)]);
1285 pattfull->setJoint(jointid.c_str());
1287 LINKOUTPUT childinfo = _WriteLink(bodyInfo, ichild, pattfull, pnode, strModelUri, mapjointnames);
1290 _WriteTransformation(pattfull, childlink.rotation, childlink.translation);
1294 string jointnodesid = _GetJointNodeSid(ichild,0);
1295 string jointType(CORBA::String_var(childlink.jointType));
1296 if( jointType ==
"rotate" || jointType ==
"fixed" ) {
1297 domRotateRef protate = daeSafeCast<domRotate>(childinfo.
pnode->add(COLLADA_ELEMENT_ROTATE,0));
1298 protate->setSid(jointnodesid.c_str());
1299 protate->getValue().setCount(4);
1300 protate->getValue()[0] = childlink.jointAxis[0];
1301 protate->getValue()[1] = childlink.jointAxis[1];
1302 protate->getValue()[2] = childlink.jointAxis[2];
1303 protate->getValue()[3] = 0;
1305 else if( jointType ==
"slide" ) {
1306 domTranslateRef ptrans = daeSafeCast<domTranslate>(childinfo.
pnode->add(COLLADA_ELEMENT_TRANSLATE,0));
1307 ptrans->setSid(jointnodesid.c_str());
1308 ptrans->getValue().setCount(3);
1309 ptrans->getValue()[0] = 0;
1310 ptrans->getValue()[1] = 0;
1311 ptrans->getValue()[2] = 0;
1314 COLLADALOG_WARN(str(boost::format(
"unsupported joint type specified %s")%jointType));
1316 _WriteTransformation(childinfo.
pnode, childlink.rotation, childlink.translation);
1320 out.
plink = pdomlink;
1325 void _SetRotate(domTargetable_float4Ref prot,
const DblArray4& rotation)
1327 prot->getValue().setCount(4);
1328 prot->getValue()[0] = rotation[0];
1329 prot->getValue()[1] = rotation[1];
1330 prot->getValue()[2] = rotation[2];
1331 prot->getValue()[3] = rotation[3]*(180.0/
M_PI);
1339 _SetRotate(daeSafeCast<domRotate>(pelt->add(COLLADA_ELEMENT_ROTATE,0)), rotation);
1340 _SetVector3(daeSafeCast<domTranslate>(pelt->add(COLLADA_ELEMENT_TRANSLATE,0))->getValue(),translation);
1346 for(std::vector<std::pair<std::string,std::string> >::const_iterator it = vkinematicsbindings.begin(); it != vkinematicsbindings.end(); ++it) {
1347 domBind_kinematics_modelRef pmodelbind = daeSafeCast<domBind_kinematics_model>(ikscene->add(COLLADA_ELEMENT_BIND_KINEMATICS_MODEL));
1348 pmodelbind->setNode(it->second.c_str());
1349 daeSafeCast<domCommon_param>(pmodelbind->add(COLLADA_ELEMENT_PARAM))->setValue(it->first.c_str());
1351 for(std::vector<axis_sids>::const_iterator it = vaxissids.begin(); it != vaxissids.end(); ++it) {
1352 domBind_joint_axisRef pjointbind = daeSafeCast<domBind_joint_axis>(ikscene->add(COLLADA_ELEMENT_BIND_JOINT_AXIS));
1353 pjointbind->setTarget(it->jointnodesid.c_str());
1354 daeSafeCast<domCommon_param>(pjointbind->add(COLLADA_ELEMENT_AXIS)->add(COLLADA_TYPE_PARAM))->setValue(it->axissid.c_str());
1355 daeSafeCast<domCommon_param>(pjointbind->add(COLLADA_ELEMENT_VALUE)->add(COLLADA_TYPE_PARAM))->setValue(it->valuesid.c_str());
1360 template <
typename T>
static void _SetVector3(T& t,
const DblArray3& v) {
1369 if( !!bodyInfo->
url() ) {
1370 xmlfilename = bodyInfo->
url();
1372 for(std::list<kinbody_models>::iterator it = _listkinbodies.begin(); it != _listkinbodies.end(); ++it) {
1373 if( it->xmlfilename == xmlfilename ) {
1374 BOOST_ASSERT(!it->kmout);
1382 cache.
kmout = kmout;
1383 _listkinbodies.push_back(cache);
1387 for(std::list<kinbody_models>::iterator it = _listkinbodies.begin(); it != _listkinbodies.end(); ++it) {
1388 if( !bodyInfo->
url() || it->xmlfilename == bodyInfo->
url() ) {
1392 return boost::shared_ptr<kinematics_model_output>();
1397 if( !!bodyInfo->
url() ) {
1398 xmlfilename = bodyInfo->
url();
1400 for(std::list<kinbody_models>::iterator it = _listkinbodies.begin(); it != _listkinbodies.end(); ++it) {
1401 if( it->xmlfilename == xmlfilename ) {
1402 BOOST_ASSERT(!it->pmout);
1410 cache.
pmout = pmout;
1411 _listkinbodies.push_back(cache);
1415 for(std::list<kinbody_models>::iterator it = _listkinbodies.begin(); it != _listkinbodies.end(); ++it) {
1416 if( !bodyInfo->
url() || it->xmlfilename == bodyInfo->
url() ) {
1420 return boost::shared_ptr<physics_model_output>();
1427 return str(boost::format(
"visual%d")%_GetRobotId(bodyInfo));
1430 return str(boost::format(
"v%d.node%d")%_GetRobotId(bodyInfo)%ilink);
1434 return str(boost::format(
"link%d")%ilink);
1438 return str(boost::format(
"g%d_%d_geom%d")%_GetRobotId(bodyInfo)%ilink%igeom);
1441 return str(boost::format(
"node_joint%d_axis%d")%ijoint%iaxis);
1446 cerr <<
"COLLADA error: " << msg << endl;
1451 cout <<
"COLLADA warning: " << msg << endl;
void AxisAngleFromQuat(OpenHRP::DblArray4 &rotation, const OpenHRP::DblArray4 &quat)
axis_sids(const string &axissid, const string &valuesid, const string &jointnodesid)
virtual MaterialInfoSequence * materials()
virtual daeElementRef WriteActuator(const LinkInfo &plink, const string &parentid)
png_infop png_charp png_int_32 png_int_32 int int png_charp * units
virtual boost::shared_ptr< instance_physics_model_output > _WriteInstance_physics_model(BodyInfo_impl *bodyInfo, daeElementRef parent, const string &sidscope)
virtual bool Write(BodyInfo_impl *bodyInfo)
virtual AppearanceInfoSequence * appearances()
std::vector< std::pair< std::string, std::string > > vkinematicsbindings
std::string tolowerstring(const std::string &s)
boost::shared_ptr< DAE > _collada
void PoseMult(OpenHRP::DblArray12 &mres, const T &m0, const OpenHRP::DblArray12 &m1)
std::string kinematicsgeometryhash
domInstance_articulated_systemRef ias
std::list< std::string > grippernames
domLibrary_geometriesRef _geometriesLib
virtual boost::shared_ptr< kinematics_model_output > _GetKinematics_model(BodyInfo_impl *bodyInfo)
virtual std::string _GetNodeId(BodyInfo_impl *bodyInfo, int ilink)
domInstance_with_extraRef piscene
domInstance_kinematics_modelRef ikm
domInstance_with_extraRef viscene
virtual void _CreateScene()
save all the loaded scene models and their current state.
virtual LinkInfoSequence * links()
virtual void Save(const string &filename)
Write down a COLLADA file.
png_infop png_charpp name
virtual boost::shared_ptr< kinematics_model_output > WriteKinematics_model(BodyInfo_impl *bodyInfo)
virtual boost::shared_ptr< physics_model_output > WritePhysics_model(BodyInfo_impl *bodyInfo)
void _WriteBindingsInstance_kinematics_scene(domInstance_kinematics_sceneRef ikscene, BodyInfo_impl *bodyInfo, const std::vector< axis_sids > &vaxissids, const std::vector< std::pair< std::string, std::string > > &vkinematicsbindings)
list< pair< int, std::string > > listusedlinks
virtual std::string _GetLinkSid(int ilink)
domKinematics_modelRef kmodel
void error(char *msg) const
virtual ShapeInfoSequence * shapes()
domInstance_kinematics_sceneRef kiscene
double det(const dmatrix &_a)
virtual TextureInfoSequence * textures()
png_infop png_uint_32 * width
virtual domImageRef WriteTexture(const TextureInfo &texture)
Write texture.
static bool ComparePair(const std::pair< int, int > &p0, const std::pair< int, int > &p1)
std::string basename(const std::string name)
domLibrary_articulated_systemsRef _articulatedSystemsLib
virtual boost::shared_ptr< physics_model_output > _GetPhysics_model(BodyInfo_impl *bodyInfo)
domTechniqueRef _actuatorsLib
custom actuators library
virtual domEffectRef WriteEffect(const MaterialInfo &material)
std::vector< std::string > vrigidbodysids
same ordering as the physics indices
png_infop png_uint_32 png_uint_32 * height
domLibrary_imagesRef _imagesLib
std::list< std::string > gripperdir
boost::shared_ptr< physics_model_output > pmout
virtual std::string _GetGeometryId(BodyInfo_impl *bodyInfo, int ilink, int igeom)
void PoseMultVector(OpenHRP::DblArray3 &vnew, const OpenHRP::DblArray12 &m, const OpenHRP::DblArray3 &v)
virtual void handleError(daeString msg)
def j(str, encoding="cp932")
CORBA::Long find(const CorbaSequence &seq, Functor f)
void PoseFromAxisAngleTranslation(OpenHRP::DblArray12 &pose, const OpenHRP::DblArray4 &rotation, const OpenHRP::DblArray3 &translation)
std::vector< axis_output > vaxissids
no ordering
ColladaWriter(const std::list< ManipulatorInfo > &listmanipulators, const char *comment_str)
domLibrary_physics_modelsRef _physicsModelsLib
domPhysics_sceneRef pscene
virtual void _AddKinematics_model(BodyInfo_impl *bodyInfo, boost::shared_ptr< kinematics_model_output > kmout)
domTechniqueRef _sensorsLib
custom sensors library
domInstance_physics_modelRef ipm
domKinematics_sceneRef kscene
virtual LINKOUTPUT _WriteLink(BodyInfo_impl *bodyInfo, int ilink, daeElementRef pkinparent, domNodeRef pnodeparent, const string &strModelUri, std::map< std::string, int > mapjointnames)
Write link of a kinematic body.
void _WriteTransformation(daeElementRef pelt, const DblArray4 &rotation, const DblArray3 &translation)
Write transformation.
std::vector< std::string > vlinksids
same ordering as the link indices
virtual int _GetRobotId(BodyInfo_impl *bodyInfo)
void COLLADALOG_WARN(const std::string &s)
virtual void handleWarning(daeString msg)
std::list< ManipulatorInfo > _listmanipulators
boost::shared_ptr< physics_model_output > pmout
static void _SetVector3(T &t, const DblArray3 &v)
Set vector of three elements.
void COLLADALOG_INFO(const std::string &s)
domLibrary_physics_scenesRef _physicsScenesLib
void QuatFromMatrix(OpenHRP::DblArray4 &quat, const T &mat)
std::vector< axis_sids > vaxissids
std::vector< std::pair< std::string, std::string > > vkinematicsbindings
virtual daeElementRef WriteSensor(const SensorInfo &sensor, const string &parentid)
virtual std::string _GetJointNodeSid(int ijoint, int iaxis)
virtual void _AddPhysics_model(BodyInfo_impl *bodyInfo, boost::shared_ptr< physics_model_output > pmout)
domLibrary_kinematics_scenesRef _kinematicsScenesLib
domVisual_sceneRef vscene
domLibrary_materialsRef _materialsLib
std::vector< axis_sids > vaxissids
std::list< kinbody_models > _listkinbodies
virtual boost::shared_ptr< instance_kinematics_model_output > _WriteInstance_kinematics_model(BodyInfo_impl *bodyInfo, daeElementRef parent, const string &sidscope)
Write kinematic body in a given scene.
domCOLLADA::domSceneRef _globalscene
void _SetRotate(domTargetable_float4Ref prot, const DblArray4 &rotation)
domLibrary_visual_scenesRef _visualScenesLib
boost::shared_ptr< kinematics_model_output > kmout
domLibrary_effectsRef _effectsLib
int calcEigenVectors(const dmatrix &_a, dmatrix &_evec, dvector &_eval)
virtual domGeometryRef WriteGeometry(BodyInfo_impl *bodyInfo, const ShapeInfo &shapeInfo, const DblArray12 &transformMatrix, const string &parentid)
Write geometry properties.
void COLLADALOG_VERBOSE(const std::string &s)
domLibrary_kinematics_modelsRef _kinematicsModelsLib
domPhysics_modelRef pmodel
std::map< std::string, int > maplinknames
virtual std::string _GetNodeId(BodyInfo_impl *bodyInfo)
virtual boost::shared_ptr< instance_articulated_system_output > _WriteRobot(BodyInfo_impl *bodyInfo)
Write kinematic body in a given scene.
boost::shared_ptr< kinematics_model_output > kmout