00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047 #include "parameter_pa/parameter_pa_ros.h"
00048
00049
00050 #include <ros/package.h>
00051 #if ROS_VERSION_MINIMUM(1, 12, 0)
00052
00053 #include <xmlrpcpp/XmlRpcValue.h>
00054 #else //#if ROS_VERSION_MINIMUM(1, 12, 0)
00055
00056 #include <XmlRpcValue.h>
00057 #endif //#if ROS_VERSION_MINIMUM(1, 12, 0)
00058
00059
00060 #include <sstream>
00061
00062
00063 bool cParameterPaRos::load (const std::string name,
00064 bool &value, const bool print_default) const {
00065
00066 bool result;
00067
00068 result = nh_.getParam(resolveRessourcename(name), value);
00069
00070 loadSub(name, boolToStr(value), print_default, result);
00071
00072 return result;
00073 }
00074
00075
00076 bool cParameterPaRos::load (const std::string name,
00077 std::string &value, const bool print_default) const {
00078
00079 bool result;
00080
00081 result = nh_.getParam(resolveRessourcename(name), value);
00082
00083 loadSub(name, value, print_default, result);
00084
00085 return result;
00086 }
00087
00088
00089 bool cParameterPaRos::loadTopic (const std::string name,
00090 std::string &value, const bool print_default) const {
00091
00092 bool result;
00093 std::string value_resolved;
00094
00095 result = nh_.getParam(resolveRessourcename(name), value);
00096 value_resolved = resolveRessourcename(value);
00097
00098 if (value_resolved == value) {
00099 loadSub(name, value, print_default, result);
00100 } else {
00101 loadSub(name, value + " == " + value_resolved, print_default, result);
00102 value = value_resolved;
00103 }
00104
00105 return result;
00106 }
00107
00108
00109 bool cParameterPaRos::loadPath (const std::string name,
00110 std::string &value, const bool print_default) const {
00111
00112 bool result;
00113
00114 result = nh_.getParam(resolveRessourcename(name), value);
00115 replaceFindpack(value);
00116
00117 loadSub(name, value, print_default, result);
00118
00119 return result;
00120 }
00121
00122
00123 bool cParameterPaRos::load (const std::string name,
00124 int &value, const bool print_default) const {
00125
00126 bool result;
00127
00128 result = nh_.getParam(resolveRessourcename(name), value);
00129
00130 std::stringstream value_s;
00131 value_s << value;
00132 loadSub(name, value_s.str(), print_default, result);
00133
00134 return result;
00135 }
00136
00137
00138 bool cParameterPaRos::load (const std::string name,
00139 double &value, const bool print_default) const {
00140
00141 bool result;
00142
00143 result = nh_.getParam(resolveRessourcename(name), value);
00144
00145 std::stringstream value_s;
00146 value_s << value;
00147 loadSub(name, value_s.str(), print_default, result);
00148
00149 return result;
00150 }
00151
00152
00153 bool cParameterPaRos::load (const std::string name,
00154 std::vector<bool> &value, const bool print_default) const {
00155
00156 bool result;
00157
00158 std::vector<bool> value_temp;
00159 result = nh_.getParam(resolveRessourcename(name), value_temp);
00160 if (result) {value = value_temp;}
00161
00162 std::stringstream value_s;
00163 value_s << "[";
00164 if (value.size() > 0) {
00165 value_s << boolToStr(value[0]);
00166 for (int i = 1; i < value.size(); i++) {
00167 value_s << ", " << boolToStr(value[i]);
00168 }
00169 }
00170 value_s << "]";
00171 loadSub(name, value_s.str(), print_default, result);
00172
00173 return result;
00174 }
00175
00176
00177 bool cParameterPaRos::load (const std::string name,
00178 std::vector<std::string> &value, const bool print_default) const {
00179
00180 bool result;
00181
00182 std::vector<std::string> value_temp;
00183 result = nh_.getParam(resolveRessourcename(name), value_temp);
00184 if (result) {value = value_temp;}
00185
00186 std::stringstream value_s;
00187 value_s << "[";
00188 if (value.size() > 0) {
00189 value_s << value[0];
00190 for (int i = 1; i < value.size(); i++) {
00191 value_s << ", " << value[i];
00192 }
00193 }
00194 value_s << "]";
00195 loadSub(name, value_s.str(), print_default, result);
00196
00197 return result;
00198 }
00199
00200
00201 bool cParameterPaRos::load (const std::string name,
00202 std::vector<int> &value, const bool print_default) const {
00203
00204 bool result;
00205
00206 std::vector<int> value_temp;
00207 result = nh_.getParam(resolveRessourcename(name), value_temp);
00208 if (result) {value = value_temp;}
00209
00210 std::stringstream value_s;
00211 value_s << "[";
00212 if (value.size() > 0) {
00213 value_s << value[0];
00214 for (int i = 1; i < value.size(); i++) {
00215 value_s << ", " << value[i];
00216 }
00217 }
00218 value_s << "]";
00219 loadSub(name, value_s.str(), print_default, result);
00220
00221 return result;
00222 }
00223
00224
00225 bool cParameterPaRos::load (const std::string name,
00226 std::vector<double> &value, const bool print_default) const {
00227
00228 bool result;
00229
00230 std::vector<double> value_temp;
00231 result = nh_.getParam(resolveRessourcename(name), value_temp);
00232 if (result) {value = value_temp;}
00233
00234 std::stringstream value_s;
00235 value_s << "[";
00236 if (value.size() > 0) {
00237 value_s << value[0];
00238 for (int i = 1; i < value.size(); i++) {
00239 value_s << ", " << value[i];
00240 }
00241 }
00242 value_s << "]";
00243 loadSub(name, value_s.str(), print_default, result);
00244
00245 return result;
00246 }
00247
00248
00249 bool cParameterPaRos::load (const std::string name,
00250 Eigen::MatrixXf &value, const bool print_default) const {
00251
00252 bool result = true;
00253
00254 Eigen::MatrixXf mat;
00255
00256 XmlRpc::XmlRpcValue xml;
00257 nh_.getParam(resolveRessourcename(name), xml);
00258
00259
00260 if((xml.getType() != XmlRpc::XmlRpcValue::TypeArray) ||
00261 (xml.size() < 1)) {
00262 result = false;
00263 } else {
00264 for (int y = 0; y < xml.size(); y++) {
00265
00266 if ((xml[y].getType() != XmlRpc::XmlRpcValue::TypeArray) ||
00267 (xml[y].size() < 1)) {
00268 result = false;
00269 break;
00270 }
00271
00272
00273 if (y == 0) {
00274 mat.resize((int) xml.size(),(int) xml[y].size());
00275 } else if (xml[y].size() != mat.cols()){
00276 result = false;
00277 break;
00278 }
00279
00280 for (int x = 0; x < xml[y].size(); x++) {
00281 if (result == false) {break;}
00282
00283 switch (xml[y][x].getType()) {
00284 case XmlRpc::XmlRpcValue::TypeDouble:
00285 mat(y,x) = (double) xml[y][x];
00286 break;
00287 case XmlRpc::XmlRpcValue::TypeInt:
00288 mat(y,x) = (int) xml[y][x];
00289 break;
00290
00291 default:
00292 result = false;
00293 break;
00294 }
00295 }
00296 if (result == false) {
00297 break;
00298 }
00299 }
00300 }
00301
00302 if (result) {value = mat;}
00303
00304 std::stringstream value_s;
00305 value_s << '[';
00306 for (int y = 0; y < value.rows(); y++) {
00307 if (y > 0) { value_s << ", ";}
00308 value_s << '[';
00309 for (int x = 0; x < value.cols(); x++) {
00310 if (x > 0) { value_s << ", ";}
00311 value_s << value(y,x);
00312 }
00313 value_s << ']';
00314 }
00315 value_s << ']';
00316
00317
00318 value_s << std::endl << "Vergleich:" << std::endl << value;
00319
00320 loadSub(name, value_s.str(), print_default, result);
00321
00322 return result;
00323 }
00324
00325
00326 bool cParameterPaRos::replaceFindpack(std::string &path) {
00327
00328 while(1) {
00329
00330 std::string::size_type start;
00331 start = (int) path.find("$(find ");
00332 if ((start < 0) || (start >= path.length())) {return true;}
00333
00334 std::string::size_type end;
00335 end = path.find(")", (std::string::size_type) start);
00336 if ((end < 0) || (end >= path.length())) {return false;}
00337
00338
00339 std::string replace;
00340 try {
00341 replace = ros::package::command(
00342 path.substr(start + 2, end - start - 2));
00343 } catch (std::runtime_error &e) {
00344 return false;
00345 }
00346 if (replace == "") { return false;}
00347
00348
00349 std::string::size_type pos_save = 0;
00350 std::string::size_type pos_current;
00351 for (pos_current = 0; pos_current < replace.length(); pos_current++) {
00352 char c;
00353 c = replace[pos_current];
00354
00355 if ((c == '\r') || (c == '\n') || (c == ' ') || (c == '\t')) {
00356 continue;
00357 }
00358
00359 if (pos_save != pos_current) {
00360 replace[pos_save] = c;
00361 }
00362 pos_save++;
00363 }
00364 if (pos_save != replace.length()) {
00365 replace.resize(pos_save);
00366 }
00367
00368
00369 path = path.substr(0,start) + replace + path.substr(end + 1);
00370 }
00371 }
00372
00373
00374 std::string cParameterPaRos::resolveRessourcename(const std::string name) {
00375
00376 if (name == "") {return "";}
00377
00378 bool full_path = false;
00379 bool end_with_slash = name[name.length()-1] == '/';
00380 std::list<std::string> parts = splitRessourcename(name);
00381
00382 if (parts.empty()) {
00383 return "";
00384 }
00385
00386 if (parts.front() == "" ) {
00387 full_path = true;
00388 parts.pop_front();
00389 } else if (parts.front() == "." ) {
00390 parts.front() = "..";
00391 parts.push_front("~");
00392 }
00393
00394 std::list<std::string>::iterator iter = parts.begin();
00395 while (iter != parts.end()) {
00396
00397
00398 if (((parts.front() == "~") || (parts.front() == "")) &&
00399 (full_path == false)) {
00400
00401
00402 std::list<std::string> temp = splitRessourcename(
00403 ros::names::resolve("~"));
00404 std::list<std::string>::iterator iter_temp = temp.end();
00405 iter_temp--;
00406
00407
00408
00409
00410 if (parts.front() != "~") {
00411 iter_temp--;
00412 }
00413
00414
00415 parts.pop_front();
00416
00417 for ( ; iter_temp != temp.end(); iter_temp--) {
00418 parts.push_front(*iter_temp);
00419 }
00420
00421
00422 full_path = true;
00423 iter = parts.begin();
00424 continue;
00425 }
00426
00427
00428 if ((*iter == "") or (*iter == ".")) {
00429 iter = parts.erase(iter);
00430 continue;
00431 }
00432
00433
00434 if (*iter == "..") {
00435 if (iter == parts.begin()) {
00436 if (full_path) {
00437
00438
00439 iter = parts.erase(iter);
00440 continue;
00441 } else {
00442
00443 parts.push_front("");
00444 continue;
00445 }
00446 }
00447
00448 iter--;
00449 iter = parts.erase(iter);
00450 iter = parts.erase(iter);
00451 continue;
00452 }
00453
00454 iter++;
00455 }
00456
00457
00458 std::string result;
00459 if (full_path) { result = "/";}
00460
00461 if (parts.size() > 0) {
00462 result+= parts.front();
00463 }
00464 for (iter = ++parts.begin() ; iter != parts.end(); iter++) {
00465 result+= '/';
00466 result+= *iter;
00467 }
00468
00469 if (end_with_slash && (parts.size() > 0)) {
00470 result+= '/';
00471 }
00472
00473 return result;
00474 }
00475
00476
00477 std::string cParameterPaRos::boolToStr(const bool value) {
00478
00479 if (value) {
00480 return "true";
00481 } else {
00482 return "false";
00483 }
00484 }
00485
00487
00488
00489 bool cParameterPaRos::load_topic (const std::string name,
00490 std::string &value, const bool print_default) const {
00491
00492 return loadTopic(name, value, print_default);
00493 }
00494
00495
00496 bool cParameterPaRos::load_path (const std::string name,
00497 std::string &value, const bool print_default) const {
00498
00499 return loadPath(name, value, print_default);
00500 }
00501
00502
00503 bool cParameterPaRos::replace_findpack(std::string &path) {
00504
00505 return replaceFindpack(path);
00506 }
00507
00508
00509 void cParameterPaRos::resolve_ressourcename(std::string &name) {
00510
00511 name = resolveRessourcename(name);
00512 }
00513
00514
00515 std::string cParameterPaRos::bool_to_str(const bool value) {
00516
00517 return boolToStr(value);
00518 }
00519
00521
00522 void cParameterPaRos::loadSub(const std::string &n, const std::string &v,
00523 const bool p, const bool r) const {
00524
00525 std::string result;
00526
00527 if (r) {
00528 result = "load parameter " + n + " (" + v + ")";
00529 } else {
00530 result = "parameter " + n + " not set";
00531
00532 if (p) {
00533 result+= " (defaults to " + v + ")";
00534 }
00535 }
00536
00537 ROS_INFO_STREAM(result);
00538 }
00539
00540
00541 std::list<std::string> cParameterPaRos::splitRessourcename(
00542 const std::string name) {
00543
00544 std::list<std::string> result;
00545 int count = 0;
00546 std::string::size_type pos = 0;
00547
00548 while(pos < name.length()) {
00549
00550 std::string::size_type end;
00551 end = (int) name.find("/", pos);
00552
00553 if ((end < 0) || (end > name.length())) {
00554 end = name.length();
00555 }
00556
00557 if (pos < end) {
00558 result.push_back(name.substr(pos, end - pos));
00559 } else {
00560 result.push_back("");
00561 }
00562
00563 pos = end + 1;
00564 }
00565
00566 return result;
00567 }