Go to the documentation of this file.00001
00020 #include <boost/algorithm/string.hpp>
00021 #include <boost/range/irange.hpp>
00022
00023 #include "robot_model_services/helper/DebugHelper.hpp"
00024
00025 namespace robot_model_services {
00026
00027 boost::shared_ptr<DebugHelper> DebugHelper::instancePtr;
00028
00029 boost::shared_ptr<DebugHelper> DebugHelper::getInstance() {
00030 if (!instancePtr)
00031 instancePtr = boost::shared_ptr<DebugHelper>(new DebugHelper());
00032 return instancePtr;
00033 }
00034
00035 DebugHelper::DebugHelper() {
00036 mNodeHandle = ros::NodeHandle(ros::this_node::getName());
00037 this->setLevels();
00038 }
00039
00040 void DebugHelper::write(const char *text, DebugHelper::DebugLevel level)
00041 {
00042 if (this->checkLevel(level)) {
00043 ROS_DEBUG("%s", text);
00044 }
00045 }
00046
00047 void DebugHelper::write(const std::string& text, DebugLevel level) {
00048 const char* cText = text.c_str();
00049
00050 this->write(cText, level);
00051 }
00052
00053 void DebugHelper::write(const std::ostream& text, DebugLevel level) {
00054 std::stringstream ss;
00055 ss << text.rdbuf();
00056 std::string s = ss.str();
00057
00058 this->write(s, level);
00059 }
00060
00061 void DebugHelper::writeNoticeably(const char *text, DebugHelper::DebugLevel level)
00062 {
00063 if (this->checkLevel(level)) {
00064 ROS_DEBUG(" ");
00065 ROS_DEBUG("%s", text);
00066 ROS_DEBUG(" ");
00067 }
00068 }
00069
00070 void DebugHelper::writeNoticeably(const std::string &text, DebugHelper::DebugLevel level)
00071 {
00072 const char* cText = text.c_str();
00073
00074 this->writeNoticeably(cText, level);
00075 }
00076
00077 void DebugHelper::writeNoticeably(const std::ostream &text, DebugHelper::DebugLevel level)
00078 {
00079 std::stringstream ss;
00080 ss << text.rdbuf();
00081 std::string s = ss.str();
00082
00083 this->writeNoticeably(s, level);
00084 }
00085
00086 unsigned int DebugHelper::getLevel()
00087 {
00088 return mLevels;
00089 }
00090
00091 std::string DebugHelper::getLevelString()
00092 {
00093 if (mLevels == ALL)
00094 return "ALL";
00095 if (mLevels == NONE)
00096 return "NONE";
00097
00098 std::string level = "";
00099
00100 if (mLevels & PARAMETERS)
00101 level += "PARAMETERS";
00102 if (mLevels & RATING) {
00103 addToString(level, "RATING");
00104 }
00105 if (mLevels & ROBOT_MODEL) {
00106 addToString(level, "ROBOT_MODEL");
00107 }
00108 if (mLevels & MAP) {
00109 addToString(level, "MAP");
00110 }
00111 if (mLevels & IK_RATING) {
00112 addToString(level, "IK_RATING");
00113 }
00114
00115 return level;
00116 }
00117
00118 bool DebugHelper::checkLevel(DebugLevel level) {
00119 return level & mLevels;
00120 }
00121
00122 void DebugHelper::setLevels() {
00123 std::vector<std::string> levels;
00124 mNodeHandle.param("debugLevels", levels, std::vector<std::string>());
00125 mLevels = parseLevels(levels);
00126 }
00127
00128 void DebugHelper::setLevels(std::string levelsStr) {
00129 std::vector<std::string> levels;
00130 boost::trim_if(levelsStr, boost::is_any_of("\"',[]{} "));
00131 boost::split(levels, levelsStr, boost::is_any_of(", "), boost::token_compress_on);
00132
00133 for (int i : boost::irange(0, (int) levels.size())) {
00134 boost::trim_if(levels[i], boost::is_any_of("\"',[]{} "));
00135 boost::to_upper(levels[i]);
00136 }
00137 mLevels = parseLevels(levels);
00138 }
00139
00140 int DebugHelper::parseLevels(std::vector<std::string> levels) {
00141 if (levels.size() == 0)
00142 return ALL;
00143 if (levels.size() == 1) {
00144 if (levels.at(0).compare("ALL") == 0)
00145 return ALL;
00146 if (levels.at(0).compare("NONE") == 0)
00147 return NONE;
00148 }
00149
00150 int level = 0;
00151
00152 for (unsigned int i = 0; i < levels.size(); i++) {
00153 if (levels.at(i).compare("PARAMETERS") == 0) {
00154 level += PARAMETERS;
00155 }
00156 else if (levels.at(i).compare("RATING") == 0) {
00157 level += RATING;
00158 }
00159 else if (levels.at(i).compare("ROBOT_MODEL") == 0) {
00160 level += ROBOT_MODEL;
00161 }
00162 else if (levels.at(i).compare("MAP") == 0) {
00163 level += MAP;
00164 }
00165 else if (levels.at(i).compare("IK_RATING") == 0) {
00166 level += IK_RATING;
00167 }
00168 else {
00169 ROS_ERROR_STREAM("Invalid debug level: " << levels.at(i));
00170 throw "Invalid debug level";
00171 }
00172 }
00173
00174 return level;
00175 }
00176
00177 void DebugHelper::addToString(std::string& s, const std::string& add)
00178 {
00179 if (s.size() != 0)
00180 s += ", ";
00181 s += add;
00182 }
00183
00184 }
asr_robot_model_services
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Sat Jun 8 2019 18:24:52