00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <uwsim/ConfigXMLParser.h>
00014 #include <uwsim/SimulatorConfig.h>
00015 #include <osgDB/FileUtils>
00016
00017 void ConfigFile::esPi(string in, double ¶m)
00018 {
00019 in.erase(0, in.find_first_not_of("\t "));
00020 in.erase(in.find_last_not_of("\t ") + 1, -1);
00021
00022 if (in == "M_PI")
00023 param = M_PI;
00024 else if (in == "M_PI_2")
00025 param = M_PI_2;
00026 else if (in == "M_PI_4")
00027 param = M_PI_4;
00028 else if (in == "-M_PI")
00029 param = -M_PI;
00030 else if (in == "-M_PI_2")
00031 param = -M_PI_2;
00032 else if (in == "-M_PI_4")
00033 param = -M_PI_4;
00034 else
00035 param = boost::lexical_cast<double>(in.c_str());
00036 }
00037
00038 void ConfigFile::extractFloatChar(const xmlpp::Node* node, double ¶m)
00039 {
00040 xmlpp::Node::NodeList list = node->get_children();
00041
00042 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00043 {
00044 const xmlpp::TextNode* nodeText = dynamic_cast<const xmlpp::TextNode*>(*iter);
00045 if (nodeText)
00046 esPi(nodeText->get_content(), param);
00047
00048 }
00049 }
00050
00051 void ConfigFile::extractIntChar(const xmlpp::Node* node, int ¶m)
00052 {
00053 xmlpp::Node::NodeList list = node->get_children();
00054
00055 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00056 {
00057 const xmlpp::TextNode* nodeText = dynamic_cast<const xmlpp::TextNode*>(*iter);
00058 if (nodeText)
00059 param = atoi(nodeText->get_content().c_str());
00060 }
00061 }
00062
00063 void ConfigFile::extractUIntChar(const xmlpp::Node* node, unsigned int ¶m)
00064 {
00065 xmlpp::Node::NodeList list = node->get_children();
00066
00067 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00068 {
00069 const xmlpp::TextNode* nodeText = dynamic_cast<const xmlpp::TextNode*>(*iter);
00070 if (nodeText)
00071 param = (unsigned int)atoi(nodeText->get_content().c_str());
00072 }
00073 }
00074
00075 void ConfigFile::extractStringChar(const xmlpp::Node* node, string ¶m)
00076 {
00077 xmlpp::Node::NodeList list = node->get_children();
00078
00079 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00080 {
00081 const xmlpp::TextNode* nodeText = dynamic_cast<const xmlpp::TextNode*>(*iter);
00082 if (nodeText)
00083 param = nodeText->get_content();
00084 param.erase(0, param.find_first_not_of("\t "));
00085 param.erase(param.find_last_not_of("\t ") + 1, -1);
00086 }
00087 }
00088
00089 void ConfigFile::extractPositionOrColor(const xmlpp::Node* node, double param[3])
00090 {
00091 xmlpp::Node::NodeList list = node->get_children();
00092 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00093 {
00094 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00095
00096 if (child->get_name() == "x" || child->get_name() == "r")
00097 extractFloatChar(child, param[0]);
00098 else if (child->get_name() == "y" || child->get_name() == "g")
00099 extractFloatChar(child, param[1]);
00100 else if (child->get_name() == "z" || child->get_name() == "b")
00101 extractFloatChar(child, param[2]);
00102 }
00103 }
00104
00105 void ConfigFile::extractOrientation(const xmlpp::Node* node, double param[3])
00106 {
00107 xmlpp::Node::NodeList list = node->get_children();
00108 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00109 {
00110 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00111
00112 if (child->get_name() == "r")
00113 extractFloatChar(child, param[0]);
00114 else if (child->get_name() == "p")
00115 extractFloatChar(child, param[1]);
00116 else if (child->get_name() == "y")
00117 extractFloatChar(child, param[2]);
00118 }
00119 }
00120
00121 void ConfigFile::processFog(const xmlpp::Node* node)
00122 {
00123
00124 xmlpp::Node::NodeList list = node->get_children();
00125 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00126 {
00127 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00128 if (child->get_name() == "density")
00129 extractFloatChar(child, fogDensity);
00130 else if (child->get_name() == "color")
00131 extractPositionOrColor(child, fogColor);
00132 }
00133 }
00134
00135 void ConfigFile::processOceanState(const xmlpp::Node* node)
00136 {
00137
00138 xmlpp::Node::NodeList list = node->get_children();
00139 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00140 {
00141 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00142
00143 if (child->get_name() == "windx")
00144 extractFloatChar(child, windx);
00145 else if (child->get_name() == "windy")
00146 extractFloatChar(child, windy);
00147 else if (child->get_name() == "windSpeed")
00148 extractFloatChar(child, windSpeed);
00149 else if (child->get_name() == "depth")
00150 extractFloatChar(child, depth);
00151 else if (child->get_name() == "reflectionDamping")
00152 extractFloatChar(child, reflectionDamping);
00153 else if (child->get_name() == "waveScale")
00154 extractFloatChar(child, waveScale);
00155 else if (child->get_name() == "isNotChoppy")
00156 {
00157 extractIntChar(child, isNotChoppy);
00158 if (isNotChoppy != 0 && isNotChoppy != 1)
00159 {
00160 OSG_WARN << "ConfigFile::processOceanState: isNotChoppy is not a binary value ( 0 1), using default value (1)"
00161 << std::endl;
00162 isNotChoppy = 1;
00163 }
00164 }
00165 else if (child->get_name() == "choppyFactor")
00166 extractFloatChar(child, choppyFactor);
00167 else if (child->get_name() == "crestFoamHeight")
00168 extractFloatChar(child, crestFoamHeight);
00169 else if (child->get_name() == "oceanSurfaceHeight")
00170 extractFloatChar(child, oceanSurfaceHeight);
00171 else if (child->get_name() == "fog")
00172 processFog(child);
00173 else if (child->get_name() == "color")
00174 extractPositionOrColor(child, color);
00175 else if (child->get_name() == "attenuation")
00176 extractPositionOrColor(child, attenuation);
00177 }
00178
00179 }
00180
00181 void ConfigFile::processSimParams(const xmlpp::Node* node)
00182 {
00183 xmlpp::Node::NodeList list = node->get_children();
00184 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00185 {
00186 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00187
00188 if (child->get_name() == "disableShaders")
00189 {
00190 extractIntChar(child, disableShaders);
00191 if (disableShaders != 0 && disableShaders != 1)
00192 {
00193 OSG_WARN << "ConfigFile::processSimParams: disableShaders is not a binary value ( 0 1), using default value (0)"
00194 << std::endl;
00195 disableShaders = 0;
00196 }
00197 }
00198 else if (child->get_name() == "eye_in_hand")
00199 {
00200 extractIntChar(child, eye_in_hand);
00201 if (eye_in_hand != 0 && eye_in_hand != 1)
00202 {
00203 OSG_WARN << "ConfigFile::processSimParams: eye_in_hand is not a binary value ( 0 1), using default value (0)"
00204 << std::endl;
00205 eye_in_hand = 0;
00206 }
00207 }
00208 else if (child->get_name() == "resw")
00209 extractIntChar(child, resw);
00210 else if (child->get_name() == "resh")
00211 extractIntChar(child, resh);
00212 else if (child->get_name() == "offsetp")
00213 extractPositionOrColor(child, offsetp);
00214 else if (child->get_name() == "offsetr")
00215 extractPositionOrColor(child, offsetr);
00216 else if (child->get_name() == "gravity")
00217 extractPositionOrColor(child, gravity);
00218 else if (child->get_name() == "enablePhysics")
00219 {
00220 extractIntChar(child, enablePhysics);
00221 if (enablePhysics != 0 && enablePhysics != 1)
00222 {
00223 OSG_WARN << "ConfigFile::processSimParams: enablePhysics is not a binary value ( 0 1), using default value (0)"
00224 << std::endl;
00225 enablePhysics = 0;
00226 }
00227 physicsWater.init();
00228 }
00229 else if (child->get_name() == "physicsWater")
00230 {
00231 physicsWater.enable = 1;
00232 processPhysicsWater(child);
00233 }
00234 else if (child->get_name() == "physicsFrequency")
00235 extractFloatChar(child, physicsFrequency);
00236 else if (child->get_name() == "physicsSubSteps")
00237 extractIntChar(child, physicsSubSteps);
00238 else if (child->get_name() == "showTrajectory")
00239 {
00240 ShowTrajectory aux;
00241 aux.init();
00242 processShowTrajectory(child, aux);
00243 trajectories.push_back(aux);
00244 }
00245 }
00246 }
00247
00248 void ConfigFile::processPhysicsWater(const xmlpp::Node* node)
00249 {
00250 xmlpp::Node::NodeList list = node->get_children();
00251 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00252 {
00253 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00254 if (child->get_name() == "position")
00255 extractPositionOrColor(child, physicsWater.position);
00256 else if (child->get_name() == "size")
00257 processSize(child);
00258 else if (child->get_name() == "resolution")
00259 extractFloatChar(child, physicsWater.resolution);
00260 }
00261 }
00262
00263 void ConfigFile::processSize(const xmlpp::Node* node)
00264 {
00265 xmlpp::Node::NodeList list = node->get_children();
00266 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00267 {
00268 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00269 if (child->get_name() == "minX")
00270 extractFloatChar(child, physicsWater.size[0]);
00271 else if (child->get_name() == "maxX")
00272 extractFloatChar(child, physicsWater.size[1]);
00273 else if (child->get_name() == "minY")
00274 extractFloatChar(child, physicsWater.size[2]);
00275 else if (child->get_name() == "maxY")
00276 extractFloatChar(child, physicsWater.size[3]);
00277 else if (child->get_name() == "minZ")
00278 extractFloatChar(child, physicsWater.size[4]);
00279 else if (child->get_name() == "maxZ")
00280 extractFloatChar(child, physicsWater.size[5]);
00281
00282 }
00283 }
00284
00285 void ConfigFile::processShowTrajectory(const xmlpp::Node* node, ShowTrajectory & trajectory)
00286 {
00287 xmlpp::Node::NodeList list = node->get_children();
00288 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00289 {
00290 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00291 if (child->get_name() == "target")
00292 extractStringChar(child, trajectory.target);
00293 else if (child->get_name() == "color")
00294 extractPositionOrColor(child, trajectory.color);
00295 else if (child->get_name() == "lineStyle")
00296 extractIntChar(child, trajectory.lineStyle);
00297 }
00298 }
00299
00300 void ConfigFile::processParameters(const xmlpp::Node* node, Parameters *params)
00301 {
00302 xmlpp::Node::NodeList list = node->get_children();
00303 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00304 {
00305 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00306
00307 if (child->get_name() == "fx")
00308 extractFloatChar(child, params->fx);
00309 else if (child->get_name() == "fy")
00310 extractFloatChar(child, params->fy);
00311 else if (child->get_name() == "x0")
00312 extractFloatChar(child, params->x0);
00313 else if (child->get_name() == "y0")
00314 extractFloatChar(child, params->y0);
00315 else if (child->get_name() == "f")
00316 extractFloatChar(child, params->f);
00317 else if (child->get_name() == "n")
00318 extractFloatChar(child, params->n);
00319 else if (child->get_name() == "k")
00320 extractFloatChar(child, params->k);
00321
00322 }
00323 }
00324
00325 void ConfigFile::processVcam(const xmlpp::Node* node, Vcam &vcam)
00326 {
00327 xmlpp::Node::NodeList list = node->get_children();
00328 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00329 {
00330 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00331
00332 if (child->get_name() == "resw")
00333 extractIntChar(child, vcam.resw);
00334 else if (child->get_name() == "resh")
00335 extractIntChar(child, vcam.resh);
00336 else if (child->get_name() == "position")
00337 extractPositionOrColor(child, vcam.position);
00338 else if (child->get_name() == "relativeTo")
00339 extractStringChar(child, vcam.linkName);
00340 else if (child->get_name() == "orientation")
00341 extractOrientation(child, vcam.orientation);
00342 else if (child->get_name() == "name")
00343 extractStringChar(child, vcam.name);
00344 else if (child->get_name() == "baseline")
00345 {
00346 extractFloatChar(child, vcam.baseLine);
00347 }
00348 else if (child->get_name() == "frameId")
00349 {
00350 extractStringChar(child, vcam.frameId);
00351 }
00352 else if (child->get_name() == "parameters")
00353 {
00354 vcam.parameters.reset(new Parameters());
00355 processParameters(child, vcam.parameters.get());
00356 }
00357 else if (child->get_name() == "showpath")
00358 extractFloatChar(child, vcam.showpath);
00359 else if (child->get_name() == "grayscale")
00360 {
00361 extractIntChar(child, vcam.bw);
00362 if (vcam.bw != 0 && vcam.bw != 1)
00363 {
00364 OSG_WARN << "ConfigFile::processVcam: grayscale is not a binary value ( 0 1), using default value (0)"
00365 << std::endl;
00366 vcam.bw = 0;
00367 }
00368 }
00369 }
00370
00371 }
00372
00373 void ConfigFile::processSLProjector(const xmlpp::Node* node, slProjector &slp)
00374 {
00375 xmlpp::Node::NodeList list = node->get_children();
00376 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00377 {
00378 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00379 if (child->get_name() == "position")
00380 extractPositionOrColor(child, slp.position);
00381 else if (child->get_name() == "relativeTo")
00382 extractStringChar(child, slp.linkName);
00383 else if (child->get_name() == "orientation")
00384 extractOrientation(child, slp.orientation);
00385 else if (child->get_name() == "name")
00386 extractStringChar(child, slp.name);
00387 else if (child->get_name() == "fov")
00388 extractFloatChar(child, slp.fov);
00389 else if (child->get_name() == "laser")
00390 extractIntChar(child, slp.laser);
00391 else if (child->get_name() == "image_name")
00392 extractStringChar(child, slp.image_name);
00393 }
00394 }
00395
00396 void ConfigFile::processRangeSensor(const xmlpp::Node* node, rangeSensor &rs)
00397 {
00398 xmlpp::Node::NodeList list = node->get_children();
00399 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00400 {
00401 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00402
00403 if (child->get_name() == "position")
00404 extractPositionOrColor(child, rs.position);
00405 else if (child->get_name() == "relativeTo")
00406 extractStringChar(child, rs.linkName);
00407 else if (child->get_name() == "orientation")
00408 extractOrientation(child, rs.orientation);
00409 else if (child->get_name() == "name")
00410 extractStringChar(child, rs.name);
00411 else if (child->get_name() == "range")
00412 extractFloatChar(child, rs.range);
00413 else if (child->get_name() == "visible")
00414 extractIntChar(child, rs.visible);
00415 }
00416 }
00417
00418 void ConfigFile::processImu(const xmlpp::Node* node, Imu &imu)
00419 {
00420 xmlpp::Node::NodeList list = node->get_children();
00421 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00422 {
00423 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00424
00425 if (child->get_name() == "position")
00426 extractPositionOrColor(child, imu.position);
00427 else if (child->get_name() == "relativeTo")
00428 extractStringChar(child, imu.linkName);
00429 else if (child->get_name() == "orientation")
00430 extractOrientation(child, imu.orientation);
00431 else if (child->get_name() == "name")
00432 extractStringChar(child, imu.name);
00433 else if (child->get_name() == "std")
00434 extractFloatChar(child, imu.std);
00435 }
00436 }
00437
00438 void ConfigFile::processPressureSensor(const xmlpp::Node* node, XMLPressureSensor &ps)
00439 {
00440 xmlpp::Node::NodeList list = node->get_children();
00441 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00442 {
00443 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00444
00445 if (child->get_name() == "position")
00446 extractPositionOrColor(child, ps.position);
00447 else if (child->get_name() == "relativeTo")
00448 extractStringChar(child, ps.linkName);
00449 else if (child->get_name() == "orientation")
00450 extractOrientation(child, ps.orientation);
00451 else if (child->get_name() == "name")
00452 extractStringChar(child, ps.name);
00453 else if (child->get_name() == "std")
00454 extractFloatChar(child, ps.std);
00455 }
00456 }
00457
00458 void ConfigFile::processGPSSensor(const xmlpp::Node* node, XMLGPSSensor &s)
00459 {
00460 xmlpp::Node::NodeList list = node->get_children();
00461 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00462 {
00463 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00464
00465 if (child->get_name() == "position")
00466 extractPositionOrColor(child, s.position);
00467 else if (child->get_name() == "relativeTo")
00468 extractStringChar(child, s.linkName);
00469 else if (child->get_name() == "orientation")
00470 extractOrientation(child, s.orientation);
00471 else if (child->get_name() == "name")
00472 extractStringChar(child, s.name);
00473 else if (child->get_name() == "std")
00474 extractFloatChar(child, s.std);
00475 }
00476 }
00477
00478 void ConfigFile::processDVLSensor(const xmlpp::Node* node, XMLDVLSensor &s)
00479 {
00480 xmlpp::Node::NodeList list = node->get_children();
00481 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00482 {
00483 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00484
00485 if (child->get_name() == "position")
00486 extractPositionOrColor(child, s.position);
00487 else if (child->get_name() == "relativeTo")
00488 extractStringChar(child, s.linkName);
00489 else if (child->get_name() == "orientation")
00490 extractOrientation(child, s.orientation);
00491 else if (child->get_name() == "name")
00492 extractStringChar(child, s.name);
00493 else if (child->get_name() == "std")
00494 extractFloatChar(child, s.std);
00495 }
00496 }
00497
00498 void ConfigFile::processCamera(const xmlpp::Node* node)
00499 {
00500 xmlpp::Node::NodeList list = node->get_children();
00501 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00502 {
00503 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00504
00505 if (child->get_name() == "freeMotion")
00506 {
00507 extractIntChar(child, freeMotion);
00508 if (freeMotion != 0 && freeMotion != 1)
00509 {
00510 OSG_WARN << "ConfigFile::processCamera: freeMotion is not a binary value ( 0 1), using default value (1)"
00511 << std::endl;
00512 freeMotion = 1;
00513 }
00514 }
00515 else if (child->get_name() == "fov")
00516 extractFloatChar(child, camFov);
00517 else if (child->get_name() == "aspectRatio")
00518 extractFloatChar(child, camAspectRatio);
00519 else if (child->get_name() == "near")
00520 extractFloatChar(child, camNear);
00521 else if (child->get_name() == "far")
00522 extractFloatChar(child, camFar);
00523 else if (child->get_name() == "position")
00524 extractPositionOrColor(child, camPosition);
00525 else if (child->get_name() == "lookAt")
00526 extractPositionOrColor(child, camLookAt);
00527 if (child->get_name() == "objectToTrack")
00528 extractStringChar(child, vehicleToTrack);
00529 }
00530 }
00531
00532 void ConfigFile::processMultibeamSensor(const xmlpp::Node* node, XMLMultibeamSensor &MB)
00533 {
00534 xmlpp::Node::NodeList list = node->get_children();
00535 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00536 {
00537 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00538
00539 if (child->get_name() == "position")
00540 extractPositionOrColor(child, MB.position);
00541 else if (child->get_name() == "relativeTo")
00542 extractStringChar(child, MB.linkName);
00543 else if (child->get_name() == "orientation")
00544 extractOrientation(child, MB.orientation);
00545 else if (child->get_name() == "name")
00546 extractStringChar(child, MB.name);
00547 else if (child->get_name() == "initAngle")
00548 extractFloatChar(child, MB.initAngle);
00549 else if (child->get_name() == "finalAngle")
00550 extractFloatChar(child, MB.finalAngle);
00551 else if (child->get_name() == "angleIncr")
00552 extractFloatChar(child, MB.angleIncr);
00553 else if (child->get_name() == "range")
00554 extractFloatChar(child, MB.range);
00555 }
00556 }
00557
00558 void ConfigFile::processPose(urdf::Pose pose, double position[3], double rpy[3], double quat[4])
00559 {
00560 position[0] = pose.position.x;
00561 position[1] = pose.position.y;
00562 position[2] = pose.position.z;
00563 pose.rotation.getRPY(rpy[0], rpy[1], rpy[2]);
00564 pose.rotation.getQuaternion(quat[0], quat[1], quat[2], quat[3]);
00565 }
00566
00567 void ConfigFile::processGeometry(urdf::Geometry * geometry, Geometry * geom)
00568 {
00569
00570 if (geometry->type == urdf::Geometry::MESH)
00571 {
00572 urdf::Mesh *mesh = dynamic_cast<urdf::Mesh*>(geometry);
00573 geom->file = mesh->filename;
00574 geom->type = 0;
00575 }
00576 else if (geometry->type == urdf::Geometry::BOX)
00577 {
00578 urdf::Box *box = dynamic_cast<urdf::Box*>(geometry);
00579 geom->type = 1;
00580 geom->boxSize[0] = box->dim.x;
00581 geom->boxSize[1] = box->dim.y;
00582 geom->boxSize[2] = box->dim.z;
00583 }
00584 else if (geometry->type == urdf::Geometry::CYLINDER)
00585 {
00586 urdf::Cylinder *cylinder = dynamic_cast<urdf::Cylinder*>(geometry);
00587 geom->type = 2;
00588 geom->length = cylinder->length;
00589 geom->radius = cylinder->radius;
00590 }
00591 else if (geometry->type == urdf::Geometry::SPHERE)
00592 {
00593 urdf::Sphere *sphere = dynamic_cast<urdf::Sphere*>(geometry);
00594 geom->type = 3;
00595 geom->radius = sphere->radius;
00596 }
00597 }
00598
00599 void ConfigFile::processVisual(boost::shared_ptr<const urdf::Visual> visual, Link &link,
00600 std::map<std::string, Material> &materials)
00601 {
00602 processGeometry(visual->geometry.get(), link.geom.get());
00603 processPose(visual->origin, link.position, link.rpy, link.quat);
00604
00605
00606 link.material = visual->material_name;
00607 if (visual->material && materials.find(visual->material_name) == materials.end())
00608 {
00609 Material m;
00610 m.name = visual->material_name;
00611 m.r = visual->material->color.r;
00612 m.g = visual->material->color.g;
00613 m.b = visual->material->color.b;
00614 m.a = visual->material->color.a;
00615 materials[m.name] = m;
00616 }
00617 }
00618
00619 void ConfigFile::processJoint(boost::shared_ptr<const urdf::Joint> joint, Joint &jointVehicle, int parentLink,
00620 int childLink)
00621 {
00622 jointVehicle.name = joint->name;
00623 jointVehicle.axis[0] = joint->axis.x;
00624 jointVehicle.axis[1] = joint->axis.y;
00625 jointVehicle.axis[2] = joint->axis.z;
00626 processPose(joint->parent_to_joint_origin_transform, jointVehicle.position, jointVehicle.rpy, jointVehicle.quat);
00627 jointVehicle.child = childLink;
00628 jointVehicle.parent = parentLink;
00629
00630 if (joint->type == 6)
00631 jointVehicle.type = 0;
00632 else if (joint->type == 1 || joint->type == 2)
00633 jointVehicle.type = 1;
00634 else if (joint->type == 3)
00635 jointVehicle.type = 2;
00636 else
00637 {
00638 OSG_WARN << "Unsupported type of joint in " << joint->name << ", fixed joint will be used." << std::endl;
00639 jointVehicle.type = 0;
00640 }
00641
00642
00643 if (joint->mimic != NULL)
00644 {
00645 jointVehicle.mimic.reset(new Mimic);
00646 jointVehicle.mimic->jointName = joint->mimic->joint_name;
00647 jointVehicle.mimic->offset = joint->mimic->offset;
00648 jointVehicle.mimic->multiplier = joint->mimic->multiplier;
00649 }
00650 else
00651 jointVehicle.mimic.reset();
00652
00653
00654 if (joint->limits != NULL)
00655 {
00656 jointVehicle.lowLimit = joint->limits->lower;
00657 jointVehicle.upLimit = joint->limits->upper;
00658 }
00659 else
00660 {
00661 jointVehicle.lowLimit = -M_PI;
00662 jointVehicle.upLimit = M_PI;
00663 }
00664 }
00665
00666 int ConfigFile::processLink(boost::shared_ptr<const urdf::Link> link, Vehicle &vehicle, int nlink, int njoint,
00667 std::map<std::string, Material> &materials)
00668 {
00669 vehicle.links[nlink].name = link->name;
00670 vehicle.links[nlink].geom.reset(new Geometry);
00671 if (link->visual)
00672 processVisual(link->visual, vehicle.links[nlink], materials);
00673 else
00674 {
00675 vehicle.links[nlink].geom->type = 4;
00676 vehicle.links[nlink].material = std::string();
00677 memset(vehicle.links[nlink].position, 0, 3 * sizeof(double));
00678 memset(vehicle.links[nlink].rpy, 0, 3 * sizeof(double));
00679 memset(vehicle.links[nlink].quat, 0, 4 * sizeof(double));
00680 vehicle.links[nlink].quat[3] = 1;
00681 }
00682
00683 if (link->collision)
00684 {
00685 vehicle.links[nlink].cs.reset(new Geometry);
00686 processGeometry(link->collision->geometry.get(), vehicle.links[nlink].cs.get());
00687 }
00688 else
00689 vehicle.links[nlink].cs.reset();
00690
00691 if(link->inertial)
00692 vehicle.links[nlink].mass=link->inertial->mass;
00693 else
00694 vehicle.links[nlink].mass=-1;
00695
00696 int linkNumber = nlink;
00697 for (uint i = 0; i < link->child_joints.size(); i++)
00698 {
00699 processJoint(link->child_joints[i], vehicle.joints[linkNumber], nlink, linkNumber + 1);
00700 linkNumber = processLink(link->child_links[i], vehicle, linkNumber + 1, linkNumber + 1, materials);
00701 }
00702 return linkNumber;
00703 }
00704
00705 int ConfigFile::processURDFFile(string file, Vehicle &vehicle)
00706 {
00707 urdf::Model model;
00708
00709 std::string file_fullpath = osgDB::findDataFile(file);
00710 if (file_fullpath == std::string("") || !model.initFile(file_fullpath))
00711 {
00712 std::cerr << "Failed to parse urdf file " << file << std::endl;
00713 exit(0);
00714 }
00715 vehicle.URDFFile=file_fullpath;
00716 OSG_INFO << "Successfully parsed urdf file " << file << std::endl;
00717
00718 vehicle.nlinks = model.links_.size();
00719 vehicle.links.resize(vehicle.nlinks);
00720 vehicle.njoints = model.joints_.size();
00721 vehicle.joints.resize(vehicle.njoints);
00722 boost::shared_ptr<const urdf::Link> root = model.getRoot();
00723 processLink(root, vehicle, 0, 0, vehicle.materials);
00724 return 0;
00725 }
00726
00727 void ConfigFile::processJointValues(const xmlpp::Node* node, std::vector<double> &jointValues, int &ninitJoints)
00728 {
00729 xmlpp::Node::NodeList list = node->get_children();
00730 ninitJoints = (list.size() - 1) / 2;
00731 jointValues.resize((list.size() - 1) / 2);
00732 int pos = 0;
00733 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
00734 {
00735 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
00736 if (child->get_name() == "joint")
00737 {
00738 extractFloatChar(child, jointValues[pos++]);
00739 }
00740 }
00741 }
00742
00743 void ConfigFile::postprocessVehicle(Vehicle &vehicle)
00744 {
00745
00746 int found;
00747 for (int i = 0; i < vehicle.njoints; i++)
00748 {
00749 if (vehicle.joints[i].mimic != NULL)
00750 {
00751 found = 0;
00752 for (int j = 0; j < vehicle.njoints && !found; j++)
00753 {
00754 if (vehicle.joints[j].name == vehicle.joints[i].mimic->jointName)
00755 {
00756 vehicle.joints[i].mimicp = j;
00757 found = 1;
00758 }
00759 }
00760 if (found == 0)
00761 {
00762 vehicle.joints[i].mimicp = -1;
00763 }
00764 }
00765 else
00766 {
00767 vehicle.joints[i].mimicp = -1;
00768 }
00769 }
00770
00771
00772 Vcam aux;
00773 for (unsigned int i = 0; i < vehicle.Vcams.size(); i++)
00774 {
00775 found = 0;
00776 aux = vehicle.Vcams.front();
00777 vehicle.Vcams.pop_front();
00778 for (int j = 0; j < vehicle.nlinks && !found; j++)
00779 {
00780 if (vehicle.links[j].name == aux.linkName)
00781 {
00782 aux.link = j;
00783 found = 1;
00784 }
00785 }
00786 if (found == 0)
00787 {
00788 OSG_WARN << "ConfigFile::postProcessVehicle: Camera attached to unknown link: " << aux.linkName
00789 << " camera will be ignored" << std::endl;
00790 }
00791 else
00792 vehicle.Vcams.push_back(aux);
00793 }
00794
00795
00796 Vcam aux2;
00797 for (unsigned int i = 0; i < vehicle.VRangecams.size(); i++)
00798 {
00799 found = 0;
00800 aux2 = vehicle.VRangecams.front();
00801 vehicle.VRangecams.pop_front();
00802 for (int j = 0; j < vehicle.nlinks && !found; j++)
00803 {
00804 if (vehicle.links[j].name == aux2.linkName)
00805 {
00806 aux2.link = j;
00807 found = 1;
00808 }
00809 }
00810 if (found == 0)
00811 {
00812 OSG_WARN << "ConfigFile::postProcessVehicle: Range Camera attached to unknown link: " << aux.linkName
00813 << " camera will be ignored" << std::endl;
00814 }
00815 else
00816 vehicle.VRangecams.push_back(aux2);
00817 }
00818
00819
00820 slProjector slp;
00821 for (unsigned int i = 0; i < vehicle.sls_projectors.size(); i++)
00822 {
00823 found = 0;
00824 slp = vehicle.sls_projectors.front();
00825 vehicle.sls_projectors.pop_front();
00826 for (int j = 0; j < vehicle.nlinks && !found; j++)
00827 {
00828 if (vehicle.links[j].name == slp.linkName)
00829 {
00830 slp.link = j;
00831 found = 1;
00832 }
00833 }
00834 if (found == 0)
00835 {
00836 OSG_WARN << "ConfigFile::postProcessVehicle: Structured Light Projector attached to unknown link: "
00837 << slp.linkName << ". Will be ignored" << std::endl;
00838 }
00839 else
00840 {
00841 vehicle.sls_projectors.push_back(slp);
00842 }
00843 }
00844
00845
00846 rangeSensor rs;
00847 for (unsigned int i = 0; i < vehicle.range_sensors.size(); i++)
00848 {
00849 found = 0;
00850 rs = vehicle.range_sensors.front();
00851 vehicle.range_sensors.pop_front();
00852 for (int j = 0; j < vehicle.nlinks && !found; j++)
00853 {
00854 if (vehicle.links[j].name == rs.linkName)
00855 {
00856 rs.link = j;
00857 found = 1;
00858 }
00859 }
00860 if (found == 0)
00861 {
00862 OSG_WARN << "ConfigFile::postProcessVehicle: RangeSensor attached to unknown link: " << rs.linkName
00863 << ". Will be ignored" << std::endl;
00864 }
00865 else
00866 vehicle.range_sensors.push_back(rs);
00867 }
00868
00869
00870 Imu imu;
00871 for (unsigned int i = 0; i < vehicle.imus.size(); i++)
00872 {
00873 found = 0;
00874 imu = vehicle.imus.front();
00875 vehicle.imus.pop_front();
00876 for (int j = 0; j < vehicle.nlinks && !found; j++)
00877 {
00878 if (vehicle.links[j].name == imu.linkName)
00879 {
00880 imu.link = j;
00881 found = 1;
00882 }
00883 }
00884 if (found == 0)
00885 {
00886 OSG_WARN << "ConfigFile::postProcessVehicle: IMU attached to unknown link: " << imu.linkName
00887 << ". Will be ignored" << std::endl;
00888 }
00889 else
00890 vehicle.imus.push_back(imu);
00891 }
00892
00893
00894 XMLPressureSensor ps;
00895 for (unsigned int i = 0; i < vehicle.pressure_sensors.size(); i++)
00896 {
00897 found = 0;
00898 ps = vehicle.pressure_sensors.front();
00899 vehicle.pressure_sensors.pop_front();
00900 for (int j = 0; j < vehicle.nlinks && !found; j++)
00901 {
00902 if (vehicle.links[j].name == ps.linkName)
00903 {
00904 ps.link = j;
00905 found = 1;
00906 }
00907 }
00908 if (found == 0)
00909 {
00910 OSG_WARN << "ConfigFile::postProcessVehicle: PressureSensor attached to unknown link: " << ps.linkName
00911 << ". Will be ignored" << std::endl;
00912 }
00913 else
00914 vehicle.pressure_sensors.push_back(ps);
00915 }
00916
00917
00918 {
00919 XMLGPSSensor s;
00920 for (unsigned int i = 0; i < vehicle.gps_sensors.size(); i++)
00921 {
00922 found = 0;
00923 s = vehicle.gps_sensors.front();
00924 vehicle.gps_sensors.pop_front();
00925 for (int j = 0; j < vehicle.nlinks && !found; j++)
00926 {
00927 if (vehicle.links[j].name == s.linkName)
00928 {
00929 s.link = j;
00930 found = 1;
00931 }
00932 }
00933 if (found == 0)
00934 {
00935 OSG_WARN << "ConfigFile::postProcessVehicle: GPSSensor attached to unknown link: " << s.linkName
00936 << ". Will be ignored" << std::endl;
00937 }
00938 else
00939 vehicle.gps_sensors.push_back(s);
00940 }
00941 }
00942
00943
00944 {
00945 XMLDVLSensor s;
00946 for (unsigned int i = 0; i < vehicle.dvl_sensors.size(); i++)
00947 {
00948 found = 0;
00949 s = vehicle.dvl_sensors.front();
00950 vehicle.dvl_sensors.pop_front();
00951 for (int j = 0; j < vehicle.nlinks && !found; j++)
00952 {
00953 if (vehicle.links[j].name == s.linkName)
00954 {
00955 s.link = j;
00956 found = 1;
00957 }
00958 }
00959 if (found == 0)
00960 {
00961 OSG_WARN << "ConfigFile::postProcessVehicle: DVLSensor attached to unknown link: " << s.linkName
00962 << ". Will be ignored" << std::endl;
00963 }
00964 else
00965 vehicle.dvl_sensors.push_back(s);
00966 }
00967 }
00968
00969
00970 {
00971 XMLMultibeamSensor MB;
00972 for (unsigned int i = 0; i < vehicle.multibeam_sensors.size(); i++)
00973 {
00974 found = 0;
00975 MB = vehicle.multibeam_sensors.front();
00976 vehicle.multibeam_sensors.pop_front();
00977 for (int j = 0; j < vehicle.nlinks && !found; j++)
00978 {
00979 if (vehicle.links[j].name == MB.linkName)
00980 {
00981 MB.link = j;
00982 found = 1;
00983 }
00984 }
00985 if (found == 0)
00986 {
00987 OSG_WARN << "ConfigFile::postProcessVehicle: multibeamSensor attached to unknown link: " << MB.linkName
00988 << ". Will be ignored" << std::endl;
00989 }
00990 else
00991 vehicle.multibeam_sensors.push_back(MB);
00992 }
00993 }
00994
00995
00996 for (unsigned int i = 0; i < vehicle.object_pickers.size(); i++)
00997 {
00998 found = 0;
00999 rs = vehicle.object_pickers.front();
01000 vehicle.object_pickers.pop_front();
01001 for (int j = 0; j < vehicle.nlinks && !found; j++)
01002 {
01003 if (vehicle.links[j].name == rs.linkName)
01004 {
01005 rs.link = j;
01006 found = 1;
01007 }
01008 }
01009 if (found == 0)
01010 {
01011 OSG_WARN << "ObjectPicker attached to unknown link: " << rs.linkName << ". Will be ignored" << std::endl;
01012 }
01013 else
01014 vehicle.object_pickers.push_back(rs);
01015 }
01016 }
01017
01018 void ConfigFile::processVehicle(const xmlpp::Node* node, Vehicle &vehicle)
01019 {
01020 xmlpp::Node::NodeList list = node->get_children();
01021 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01022 {
01023 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01024
01025 if (child->get_name() == "name")
01026 extractStringChar(child, vehicle.name);
01027 else if (child->get_name() == "file")
01028 {
01029 string aux;
01030 extractStringChar(child, aux);
01031 processURDFFile(aux, vehicle);
01032 }
01033 else if (child->get_name() == "position")
01034 extractPositionOrColor(child, vehicle.position);
01035 else if (child->get_name() == "orientation")
01036 extractOrientation(child, vehicle.orientation);
01037 else if (child->get_name() == "jointValues")
01038 processJointValues(child, vehicle.jointValues, vehicle.ninitJoints);
01039 else if (child->get_name() == "virtualCamera")
01040 {
01041 Vcam aux;
01042 aux.init();
01043 processVcam(child, aux);
01044 vehicle.Vcams.push_back(aux);
01045 }
01046 else if (child->get_name() == "virtualRangeImage")
01047 {
01048 Vcam aux;
01049 aux.init();
01050 aux.range = 1;
01051 processVcam(child, aux);
01052 vehicle.VRangecams.push_back(aux);
01053 }
01054 else if (child->get_name() == "structuredLightProjector")
01055 {
01056 slProjector aux;
01057 aux.init();
01058 processSLProjector(child, aux);
01059 vehicle.sls_projectors.push_back(aux);
01060 }
01061 else if (child->get_name() == "rangeSensor")
01062 {
01063 rangeSensor aux;
01064 aux.init();
01065 processRangeSensor(child, aux);
01066 vehicle.range_sensors.push_back(aux);
01067 }
01068 else if (child->get_name() == "objectPicker")
01069 {
01070 rangeSensor aux;
01071 aux.init();
01072 processRangeSensor(child, aux);
01073 vehicle.object_pickers.push_back(aux);
01074 }
01075 else if (child->get_name() == "imu")
01076 {
01077 Imu aux;
01078 aux.init();
01079 processImu(child, aux);
01080 vehicle.imus.push_back(aux);
01081 }
01082 else if (child->get_name() == "pressureSensor")
01083 {
01084 XMLPressureSensor aux;
01085 aux.init();
01086 processPressureSensor(child, aux);
01087 vehicle.pressure_sensors.push_back(aux);
01088 }
01089 else if (child->get_name() == "gpsSensor")
01090 {
01091 XMLGPSSensor aux;
01092 aux.init();
01093 processGPSSensor(child, aux);
01094 vehicle.gps_sensors.push_back(aux);
01095 }
01096 else if (child->get_name() == "dvlSensor")
01097 {
01098 XMLDVLSensor aux;
01099 aux.init();
01100 processDVLSensor(child, aux);
01101 vehicle.dvl_sensors.push_back(aux);
01102 }
01103 else if (child->get_name() == "multibeamSensor")
01104 {
01105 XMLMultibeamSensor aux;
01106 aux.init();
01107 processMultibeamSensor(child, aux);
01108 vehicle.multibeam_sensors.push_back(aux);
01109 }
01110 else
01111 {
01112 std::vector < uwsim::SimulatedDeviceConfig::Ptr > auxs = SimulatedDevices::processConfig(
01113 child, this, child->get_name() != "simulatedDevices");
01114 for (size_t i = 0; i < auxs.size(); ++i)
01115 if (auxs[i])
01116 vehicle.simulated_devices.push_back(auxs[i]);
01117 }
01118 }
01119 }
01120
01121 void ConfigFile::processPhysicProperties(const xmlpp::Node* node, PhysicProperties &pp)
01122 {
01123 xmlpp::Node::NodeList list = node->get_children();
01124 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01125 {
01126 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01127
01128 if (child->get_name() == "mass")
01129 extractFloatChar(child, pp.mass);
01130 else if (child->get_name() == "inertia")
01131 extractPositionOrColor(child, pp.inertia);
01132 else if (child->get_name() == "collisionShapeType")
01133 extractStringChar(child, pp.csType);
01134 else if (child->get_name() == "collisionShape")
01135 extractStringChar(child, pp.cs);
01136 else if (child->get_name() == "linearDamping")
01137 {
01138 extractFloatChar(child, pp.linearDamping);
01139 if (pp.linearDamping > 1.0)
01140 OSG_WARN << "ConfigFile::PhysicProperties: linearDamping is higher than 1.0." << std::endl;
01141 }
01142 else if (child->get_name() == "angularDamping")
01143 {
01144 extractFloatChar(child, pp.angularDamping);
01145 if (pp.linearDamping > 1.0)
01146 OSG_WARN << "ConfigFile::PhysicProperties: angularDamping is higher than 1.0." << std::endl;
01147 }
01148 else if (child->get_name() == "minLinearLimit")
01149 extractPositionOrColor(child, pp.minLinearLimit);
01150 else if (child->get_name() == "maxLinearLimit")
01151 extractPositionOrColor(child, pp.maxLinearLimit);
01152 else if (child->get_name() == "isKinematic")
01153 {
01154 extractIntChar(child, pp.isKinematic);
01155 if (pp.isKinematic != 0 && pp.isKinematic != 1)
01156 {
01157 OSG_WARN << "ConfigFile::PhysicProperties: isKinematic is not a binary value ( 0 1), using default value (0)"
01158 << std::endl;
01159 freeMotion = 0;
01160 }
01161 }
01162 else if (child->get_name() == "minAngularLimit")
01163 extractPositionOrColor(child, pp.minAngularLimit);
01164 else if (child->get_name() == "maxAngularLimit")
01165 extractPositionOrColor(child, pp.maxAngularLimit);
01166
01167 }
01168 }
01169
01170 void ConfigFile::processObject(const xmlpp::Node* node, Object &object)
01171 {
01172 xmlpp::Node::NodeList list = node->get_children();
01173 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01174 {
01175 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01176
01177 if (child->get_name() == "name")
01178 extractStringChar(child, object.name);
01179 else if (child->get_name() == "file")
01180 extractStringChar(child, object.file);
01181 else if (child->get_name() == "position")
01182 extractPositionOrColor(child, object.position);
01183 else if (child->get_name() == "orientation")
01184 extractOrientation(child, object.orientation);
01185 else if (child->get_name() == "offsetp")
01186 extractPositionOrColor(child, object.offsetp);
01187 else if (child->get_name() == "offsetr")
01188 extractPositionOrColor(child, object.offsetr);
01189 else if (child->get_name() == "physics")
01190 {
01191 object.physicProperties.reset(new PhysicProperties);
01192 object.physicProperties->init();
01193 processPhysicProperties(child, *object.physicProperties);
01194
01195 }
01196
01197 }
01198 }
01199
01200 void ConfigFile::processROSInterface(const xmlpp::Node* node, ROSInterfaceInfo &rosInterface)
01201 {
01202 xmlpp::Node::NodeList list = node->get_children();
01203 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01204 {
01205 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01206 if (child->get_name() != "text")
01207 {
01208 std::string text;
01209 extractStringChar(child, text);
01210 rosInterface.values[child->get_name()] = text;
01211 }
01212
01213 if (child->get_name() == "topic" || child->get_name() == "imageTopic")
01214 extractStringChar(child, rosInterface.topic);
01215 else if (child->get_name() == "vehicleName" || child->get_name() == "cameraName" || child->get_name() == "name")
01216 extractStringChar(child, rosInterface.targetName);
01217 else if (child->get_name() == "rate")
01218 extractIntChar(child, rosInterface.rate);
01219 else if (child->get_name() == "rootName")
01220 extractStringChar(child, rosInterface.rootName);
01221 else if (child->get_name() == "enableObjects")
01222 extractUIntChar(child, rosInterface.enableObjects);
01223 else if (child->get_name() == "infoTopic")
01224 extractStringChar(child, rosInterface.infoTopic);
01225 else if (child->get_name() == "width")
01226 extractUIntChar(child, rosInterface.w);
01227 else if (child->get_name() == "height")
01228 extractUIntChar(child, rosInterface.h);
01229 else if (child->get_name() == "posx")
01230 extractUIntChar(child, rosInterface.posx);
01231 else if (child->get_name() == "posy")
01232 extractUIntChar(child, rosInterface.posy);
01233 else if (child->get_name() == "blackWhite")
01234 {
01235 extractUIntChar(child, rosInterface.blackWhite);
01236 if (rosInterface.blackWhite != 0 && rosInterface.blackWhite != 1)
01237 {
01238 OSG_WARN << "ConfigFile::processROSInterface: blackWhite is not a binary value ( 0 1), using default value (0)"
01239 << std::endl;
01240 rosInterface.blackWhite = 0;
01241 }
01242 }
01243 else if (child->get_name() == "depth")
01244 {
01245 extractUIntChar(child, rosInterface.depth);
01246 if (rosInterface.depth != 0 && rosInterface.depth != 1)
01247 {
01248 osg::notify(osg::ALWAYS)
01249 << "ConfigFile::processROSInterface: depth is not a binary value ( 0 1), using default value (0)"
01250 << std::endl;
01251 rosInterface.depth = 0;
01252 }
01253 }
01254 else if (child->get_name() == "scale")
01255 extractFloatChar(child, rosInterface.scale);
01256 else if (child->get_name() == "text")
01257 {
01258 }
01259 else
01260 osg::notify(osg::ALWAYS) << "processROSInterface:: unexpected child: " << child->get_name() << std::endl;
01261 }
01262 }
01263
01264 void ConfigFile::processROSInterfaces(const xmlpp::Node* node)
01265 {
01266 xmlpp::Node::NodeList list = node->get_children();
01267 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01268 {
01269 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01270 xmlpp::Node* subchild = NULL;
01271
01272 ROSInterfaceInfo rosInterface;
01273 rosInterface.rate = 10;
01274 rosInterface.posx = rosInterface.posy = 0;
01275 rosInterface.scale = 1;
01276 rosInterface.type = ROSInterfaceInfo::Unknown;
01277 rosInterface.depth = 0;
01278 if (child->get_name() == "ROSOdomToPAT")
01279 {
01280 rosInterface.type = ROSInterfaceInfo::ROSOdomToPAT;
01281 }
01282 else if (child->get_name() == "PATToROSOdom")
01283 {
01284 rosInterface.type = ROSInterfaceInfo::PATToROSOdom;
01285 }
01286 else if (child->get_name() == "WorldToROSTF")
01287 {
01288 rosInterface.type = ROSInterfaceInfo::WorldToROSTF;
01289 }
01290 else if (child->get_name() == "ArmToROSJointState")
01291 {
01292 rosInterface.type = ROSInterfaceInfo::ArmToROSJointState;
01293 }
01294 else if (child->get_name() == "ROSJointStateToArm")
01295 {
01296 rosInterface.type = ROSInterfaceInfo::ROSJointStateToArm;
01297 }
01298 else if (child->get_name() == "VirtualCameraToROSImage")
01299 {
01300 rosInterface.type = ROSInterfaceInfo::VirtualCameraToROSImage;
01301 }
01302 else if (child->get_name() == "RangeImageSensorToROSImage")
01303 {
01304 rosInterface.type = ROSInterfaceInfo::RangeImageSensorToROSImage;
01305 }
01306 else if (child->get_name() == "RangeSensorToROSRange")
01307 {
01308 rosInterface.type = ROSInterfaceInfo::RangeSensorToROSRange;
01309 }
01310 else if (child->get_name() == "ROSImageToHUD")
01311 {
01312 rosInterface.type = ROSInterfaceInfo::ROSImageToHUD;
01313 }
01314 else if (child->get_name() == "ROSTwistToPAT")
01315 {
01316 rosInterface.type = ROSInterfaceInfo::ROSTwistToPAT;
01317 }
01318 else if (child->get_name() == "ROSPoseToPAT")
01319 {
01320 rosInterface.type = ROSInterfaceInfo::ROSPoseToPAT;
01321 }
01322 else if (child->get_name() == "ImuToROSImu")
01323 {
01324 rosInterface.type = ROSInterfaceInfo::ImuToROSImu;
01325 }
01326 else if (child->get_name() == "PressureSensorToROS")
01327 {
01328 rosInterface.type = ROSInterfaceInfo::PressureSensorToROS;
01329 }
01330 else if (child->get_name() == "GPSSensorToROS")
01331 {
01332 rosInterface.type = ROSInterfaceInfo::GPSSensorToROS;
01333 }
01334 else if (child->get_name() == "DVLSensorToROS")
01335 {
01336 rosInterface.type = ROSInterfaceInfo::DVLSensorToROS;
01337 }
01338 else if (child->get_name() == "multibeamSensorToLaserScan")
01339 {
01340 rosInterface.type = ROSInterfaceInfo::multibeamSensorToLaserScan;
01341 }
01342 else if (child->get_name() == "contactSensorToROS")
01343 {
01344 rosInterface.type = ROSInterfaceInfo::contactSensorToROS;
01345 }
01346 else if (child->get_name() == "SimulatedDeviceROS")
01347 {
01348 xmlpp::Node::NodeList sublist = child->get_children();
01349 for (xmlpp::Node::NodeList::iterator subiter = sublist.begin(); subiter != sublist.end(); ++subiter)
01350 {
01351 xmlpp::Node* tempchild = dynamic_cast<const xmlpp::Node*>(*subiter);
01352 if (tempchild != NULL && tempchild->get_name() != "text")
01353 {
01354 std::string subtype = tempchild->get_name();
01355 if (subtype.length() > 3 && subtype.substr(subtype.length() - 3, 3) == "ROS")
01356 {
01357 rosInterface.type = ROSInterfaceInfo::SimulatedDevice;
01358 rosInterface.subtype = subtype.substr(0, subtype.length() - 3);
01359 subchild = tempchild;
01360 }
01361 }
01362 }
01363 }
01364 else
01365 {
01366 std::string subtype = child->get_name();
01367 if (subtype.length() > 3 && subtype.substr(subtype.length() - 3, 3) == "ROS")
01368 {
01369 rosInterface.type = ROSInterfaceInfo::SimulatedDevice;
01370 rosInterface.subtype = subtype.substr(0, subtype.length() - 3);
01371 }
01372 }
01373
01374 if (rosInterface.type != ROSInterfaceInfo::Unknown)
01375 {
01376 processROSInterface(subchild != NULL ? subchild : child, rosInterface);
01377 if (rosInterface.type != ROSInterfaceInfo::contactSensorToROS)
01378 ROSInterfaces.push_back(rosInterface);
01379 else
01380 ROSPhysInterfaces.push_back(rosInterface);
01381 }
01382 }
01383 }
01384
01385 void ConfigFile::processXML(const xmlpp::Node* node)
01386 {
01387 if (node->get_name() != "UWSimScene")
01388 {
01389 OSG_WARN << "ConfigFile::processXML: XML file is not an UWSimScene file." << std::endl;
01390 }
01391 else
01392 {
01393 xmlpp::Node::NodeList list = node->get_children();
01394 for (xmlpp::Node::NodeList::iterator iter = list.begin(); iter != list.end(); ++iter)
01395 {
01396 xmlpp::Node* child = dynamic_cast<const xmlpp::Node*>(*iter);
01397 if (child->get_name() == "oceanState")
01398 processOceanState(child);
01399 else if (child->get_name() == "simParams")
01400 processSimParams(child);
01401 else if (child->get_name() == "camera")
01402 processCamera(child);
01403 else if (child->get_name() == "vehicle")
01404 {
01405 Vehicle vehicle;
01406 processVehicle(child, vehicle);
01407 postprocessVehicle(vehicle);
01408 vehicles.push_back(vehicle);
01409 }
01410 else if (child->get_name() == "object")
01411 {
01412 Object object;
01413 memset(object.offsetp, 0, 3 * sizeof(double));
01414 memset(object.offsetr, 0, 3 * sizeof(double));
01415 object.physicProperties.reset();
01416 processObject(child, object);
01417 objects.push_back(object);
01418 }
01419 else if (child->get_name() == "rosInterfaces")
01420 processROSInterfaces(child);
01421 }
01422 }
01423
01424 }
01425
01426 ConfigFile::ConfigFile(const std::string &fName)
01427 {
01428 memset(offsetr, 0, 3 * sizeof(double));
01429 memset(offsetp, 0, 3 * sizeof(double));
01430 memset(gravity, 0, 3 * sizeof(double));
01431 camNear = camFar = -1;
01432 enablePhysics = 0;
01433 physicsFrequency = 60;
01434 physicsSubSteps = 0;
01435 try
01436 {
01437 xmlpp::DomParser parser;
01438 parser.set_validate();
01439 parser.set_substitute_entities();
01440 std::string fName_fullpath = osgDB::findDataFile(fName);
01441 if (fName_fullpath != std::string(""))
01442 {
01443 parser.parse_file(fName_fullpath);
01444 if (parser)
01445 {
01446
01447 const xmlpp::Node* pNode = parser.get_document()->get_root_node();
01448 processXML(pNode);
01449 }
01450 }
01451 else
01452 {
01453 std::cerr << "Cannot locate file " << fName << std::endl;
01454 exit(0);
01455 }
01456 }
01457 catch (const std::exception& ex)
01458 {
01459 std::cerr << "Exception caught: " << ex.what() << std::endl;
01460 std::cerr << "Please check your XML file" << std::endl;
01461 exit(0);
01462 }
01463
01464 }