launchparser.cpp
Go to the documentation of this file.
1 //
2 // Created by rosuser on 11.07.19.
3 //
4 
5 #include "launchparser.h"
6 //#include "launchparser/launchparser.h"
8 
9 #include "tinystr.h"
10 #include "tinyxml.h"
11 
13 {
14 public:
15  paramEntryAscii(std::string _nameVal, std::string _typeVal, std::string _valueVal)
16  {
17  nameVal = _nameVal;
18  typeVal = _typeVal;
19  valueVal = _valueVal;
20  setCheckStatus(999,"untested");
21  minMaxGiven = false;
22  };
23 
24  void setPointerToXmlNode(TiXmlElement *paramEntryPtr)
25  {
26  this->nodePtr = paramEntryPtr;
27  }
28 
30  {
31  return( this->nodePtr);
32  }
33  void setValues(std::string _nameVal, std::string _typeVal, std::string _valueVal)
34  {
35  nameVal = _nameVal;
36  typeVal = _typeVal;
37  valueVal = _valueVal;
38  };
39 
40 
42  {
43  return(minMaxGiven);
44  }
45 
46  void setMinMaxValues(std::string _valueMinVal, std::string _valueMaxVal)
47  {
48 
49  valueMinVal = _valueMinVal;
50  valueMaxVal = _valueMaxVal;
51  minMaxGiven = true;
52 
53  };
54 
55  std::string getName()
56  {
57  return(nameVal);
58  }
59 
60  std::string getType()
61  {
62  return(typeVal);
63  }
64 
65  std::string getValue()
66  {
67  return(valueVal);
68  }
69 
70  std::string getMinValue()
71  {
72  return(valueMinVal);
73  }
74 
75  std::string getMaxValue()
76  {
77  return(valueMaxVal);
78  }
79 
80  void setCheckStatus(int errCode, std::string errMsg)
81  {
82  errorCode = errCode;
83  errorMsg = errMsg;
84  };
85 
87  {
88  return(errorCode);
89  }
90 
91  std::string getErrorMsg()
92  {
93  return(errorMsg);
94  }
95 
96 private:
97  std::string nameVal;
98  std::string typeVal;
99  std::string valueVal;
100  std::string valueMinVal;
101  std::string valueMaxVal;
104  std::string errorMsg;
106 };
107 
108 
109 #ifndef _MSC_VER
110 #include <signal.h>
111 //#include <unistd.h>
112 void sudokill(pid_t tokill)
113 {
114  kill(tokill, SIGTERM);
115  rosSleep(5); // sleep(5);
116 }
117 #endif
118 
119 std::vector<paramEntryAscii> getParamList(TiXmlNode *paramList)
120 {
121  std::vector<paramEntryAscii> tmpList;
122 
123 
124  TiXmlElement *paramEntry = (TiXmlElement *)paramList->FirstChild("param"); // first child
125  while (paramEntry)
126  {
127  std::string nameVal = "";
128  std::string typeVal = "";
129  std::string valueVal = "";
130  std::string minValueVal = "";
131  std::string maxValueVal = "";
132 
133  bool minValFnd = false;
134  bool maxValFnd = false;
135  // is this a param-node?
136  // if this is valid than process attributes
137  const char *entryVal = paramEntry->Value();
138  bool searchAttributes = true;
139  if (strcmp(entryVal,"param") == 0)
140  {
141  // expected value
142  }
143  else
144  {
145  searchAttributes = false;
146  }
147  if (paramEntry->Type() == TiXmlNode::TINYXML_ELEMENT)
148  {
149  // expected value
150  }
151  else
152  {
153  searchAttributes = false;
154  }
155  if (searchAttributes)
156  {
157  for (TiXmlAttribute* node = paramEntry->FirstAttribute(); ; node = node->Next())
158  {
159  const char *tag = node->Name();
160  const char *val = node->Value();
161 
162  if (strcmp(tag, "name") == 0)
163  {
164  nameVal = val;
165  }
166  if (strcmp(tag, "type") == 0)
167  {
168  typeVal = val;
169  }
170  if (strcmp(tag, "value") == 0)
171  {
172  valueVal = val;
173  }
174  if (strcmp(tag, "valueMin") == 0)
175  {
176  minValFnd = true;
177  minValueVal = val;
178 
179  }
180  if (strcmp(tag, "valueMax") == 0)
181  {
182  maxValFnd = true;
183  maxValueVal = val;
184  }
185  if (node == paramEntry->LastAttribute())
186  {
187 
188  break;
189  }
190  }
191 
192  paramEntryAscii tmpEntry(nameVal, typeVal, valueVal);
193  if (maxValFnd && minValFnd)
194  {
195  tmpEntry.setMinMaxValues(minValueVal, maxValueVal);
196  }
197 
198  tmpEntry.setPointerToXmlNode(paramEntry);
199  tmpList.push_back(tmpEntry);
200  }
201  paramEntry = (TiXmlElement *)paramEntry->NextSibling(); // go to next sibling
202  }
203 
204  return(tmpList);
205 }
206 
207 
208 
209 bool LaunchParser::parseFile(std::string launchFileFullName, std::vector<std::string>& nameVec,
210  std::vector<std::string>& typeVec, std::vector<std::string>& valVec)
211 {
212  bool ret = false;
213  ROS_INFO_STREAM("Try loading launchfile : " << launchFileFullName);
214  TiXmlDocument doc;
215  doc.LoadFile(launchFileFullName.c_str());
216 
217  if (doc.Error() == true)
218  {
219  ROS_ERROR_STREAM("## ERROR parsing launch file " << doc.ErrorDesc() << "\nRow: " << doc.ErrorRow() << "\nCol: " << doc.ErrorCol() << "");
220  return(ret);
221  }
222  TiXmlNode *node = doc.FirstChild("launch");
223  if (node != NULL)
224  {
225  std::map<std::string, std::string> default_args;
226  TiXmlElement *arg_node = (TiXmlElement *)node->FirstChild("arg");
227  while(arg_node)
228  {
229  if(strcmp(arg_node->Value(), "arg") == 0 && arg_node->Type() == TiXmlNode::TINYXML_ELEMENT)
230  {
231  // parse default arguments, f.e. <arg name="hostname" default="192.168.0.1"/>
232  const char* p_attr_name = arg_node->Attribute("name");
233  const char* p_attr_default = arg_node->Attribute("default");
234  if(p_attr_name && p_attr_default)
235  {
236  std::string attr_name(p_attr_name), attr_default(p_attr_default);
237  default_args[attr_name] = attr_default;
238  ROS_INFO_STREAM("LaunchParser::parseFile(" << launchFileFullName << "): default_args[\"" << attr_name << "\"]=\"" << default_args[attr_name] << "\"");
239  }
240  }
241  arg_node = (TiXmlElement *)arg_node->NextSibling(); // go to next sibling
242  }
243 
244  // Parse optional group for param "scanner_type"
245  bool node_with_scanner_type_found = false;
246  TiXmlNode * group_node = node->FirstChild("group");
247  if (group_node)
248  {
249  group_node = group_node->FirstChild("node");
250  if (group_node)
251  {
252  std::vector<paramEntryAscii> paramOrgList = getParamList(group_node);
253  for (size_t j = 0; j < paramOrgList.size(); j++)
254  {
255  if (paramOrgList[j].getName() == "scanner_type")
256  {
257  node_with_scanner_type_found = true;
258  ROS_INFO_STREAM("LaunchParser::parseFile(" << launchFileFullName << "): group node found with param scanner_type");
259  node = group_node;
260  break;
261  }
262  }
263  }
264  }
265  if (!node_with_scanner_type_found)
266  {
267  node = node->FirstChild("node");
268  }
269 
270  // parse all node specific parameters
271  std::vector<paramEntryAscii> paramOrgList = getParamList(node);
272 
273  for (size_t j = 0; j < paramOrgList.size(); j++)
274  {
275  nameVec.push_back(paramOrgList[j].getName());
276  typeVec.push_back(paramOrgList[j].getType());
277  valVec.push_back(paramOrgList[j].getValue());
278  if(valVec.back().substr(0, 6) == "$(arg ") // overwrite with default argument, f.e. name="hostname", type="string", value="$(arg hostname)"
279  {
280  std::string default_arg_name = valVec.back().substr(6, valVec.back().length() - 1 - 6);
281  if (default_args.find(default_arg_name) != default_args.end())
282  {
283  std::string default_arg_val = default_args[default_arg_name];
284  ROS_INFO_STREAM("LaunchParser::parseFile(" << launchFileFullName << "): name=\"" << nameVec.back() << "\", type=\"" << typeVec.back() << "\", value=\"" << valVec.back()
285  << "\" overwritten by default value \"" << default_arg_val << "\"");
286  valVec.back() = default_arg_val;
287  }
288  }
289  ROS_INFO_STREAM("LaunchParser::parseFile(" << launchFileFullName << "): name=\"" << nameVec.back() << "\", type=\"" << typeVec.back() << "\", value=\"" << valVec.back() << "\"");
290  }
291 
292  ret = true;
293 
294  }
295 
296  return(ret);
297 };
paramEntryAscii::valueMinVal
std::string valueMinVal
Definition: launchparser.cpp:100
TiXmlElement
Definition: tinyxml.h:1074
paramEntryAscii::setPointerToXmlNode
void setPointerToXmlNode(TiXmlElement *paramEntryPtr)
Definition: launchparser.cpp:24
TiXmlDocument
Definition: tinyxml.h:1593
TiXmlElement::Attribute
const char * Attribute(const char *name) const
Definition: tinyxml.cpp:577
NULL
#define NULL
paramEntryAscii::isMinMaxGiven
bool isMinMaxGiven()
Definition: launchparser.cpp:41
paramEntryAscii
Definition: launchparser.cpp:12
TiXmlElement::LastAttribute
TiXmlAttribute * LastAttribute()
Definition: tinyxml.h:1232
TiXmlNode::FirstChild
TiXmlNode * FirstChild()
Definition: tinyxml.h:581
TiXmlNode::Type
int Type() const
Definition: tinyxml.h:773
TiXmlNode::TINYXML_ELEMENT
@ TINYXML_ELEMENT
Definition: tinyxml.h:516
TiXmlNode::NextSibling
const TiXmlNode * NextSibling() const
Navigate to a sibling node.
Definition: tinyxml.h:707
tinyxml.h
paramEntryAscii::getMinValue
std::string getMinValue()
Definition: launchparser.cpp:70
paramEntryAscii::getValue
std::string getValue()
Definition: launchparser.cpp:65
rosSleep
void rosSleep(double seconds)
Definition: sick_ros_wrapper.h:210
TiXmlDocument::Error
bool Error() const
Definition: tinyxml.h:1671
paramEntryAscii::valueMaxVal
std::string valueMaxVal
Definition: launchparser.cpp:101
paramEntryAscii::paramEntryAscii
paramEntryAscii(std::string _nameVal, std::string _typeVal, std::string _valueVal)
Definition: launchparser.cpp:15
TiXmlDocument::ErrorRow
int ErrorRow() const
Definition: tinyxml.h:1691
launchparser.h
sick_ros_wrapper.h
sudokill
void sudokill(pid_t tokill)
Definition: launchparser.cpp:112
tinystr.h
paramEntryAscii::minMaxGiven
bool minMaxGiven
Definition: launchparser.cpp:102
ROS_INFO_STREAM
#define ROS_INFO_STREAM(...)
Definition: sick_scan_ros2_example.cpp:71
TiXmlAttribute
Definition: tinyxml.h:884
polar_to_cartesian_pointcloud_ros1.node
node
Definition: polar_to_cartesian_pointcloud_ros1.py:81
paramEntryAscii::getName
std::string getName()
Definition: launchparser.cpp:55
paramEntryAscii::getPointerToXmlNode
TiXmlElement * getPointerToXmlNode(void)
Definition: launchparser.cpp:29
paramEntryAscii::errorCode
int errorCode
Definition: launchparser.cpp:103
paramEntryAscii::getErrorCode
int getErrorCode()
Definition: launchparser.cpp:86
paramEntryAscii::setValues
void setValues(std::string _nameVal, std::string _typeVal, std::string _valueVal)
Definition: launchparser.cpp:33
paramEntryAscii::setCheckStatus
void setCheckStatus(int errCode, std::string errMsg)
Definition: launchparser.cpp:80
TiXmlNode
Definition: tinyxml.h:473
TINYXML_EXPORT_ATTR
#define TINYXML_EXPORT_ATTR
Definition: tinystr.h:42
paramEntryAscii::getErrorMsg
std::string getErrorMsg()
Definition: launchparser.cpp:91
paramEntryAscii::nameVal
std::string nameVal
Definition: launchparser.cpp:97
TiXmlDocument::ErrorDesc
const char * ErrorDesc() const
Contains a textual (english) description of the error if one occurs.
Definition: tinyxml.h:1675
paramEntryAscii::getType
std::string getType()
Definition: launchparser.cpp:60
LaunchParser::parseFile
bool parseFile(std::string launchFileFullName, std::vector< std::string > &nameVec, std::vector< std::string > &typeVec, std::vector< std::string > &valVec)
Definition: launchparser.cpp:209
paramEntryAscii::setMinMaxValues
void setMinMaxValues(std::string _valueMinVal, std::string _valueMaxVal)
Definition: launchparser.cpp:46
getParamList
std::vector< paramEntryAscii > getParamList(TiXmlNode *paramList)
Definition: launchparser.cpp:119
TiXmlNode::Value
const char * Value() const
Definition: tinyxml.h:538
paramEntryAscii::nodePtr
TiXmlElement * nodePtr
Definition: launchparser.cpp:105
TiXmlDocument::LoadFile
bool LoadFile(TiXmlEncoding encoding=TIXML_DEFAULT_ENCODING)
Definition: tinyxml.cpp:954
roswrap::this_node::getName
const ROSCPP_DECL std::string & getName()
Returns the name of the current node.
Definition: rossimu.cpp:343
TiXmlElement::FirstAttribute
TiXmlAttribute * FirstAttribute()
Definition: tinyxml.h:1227
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(...)
Definition: sick_scan_ros2_example.cpp:72
paramEntryAscii::valueVal
std::string valueVal
Definition: launchparser.cpp:99
paramEntryAscii::typeVal
std::string typeVal
Definition: launchparser.cpp:98
paramEntryAscii::errorMsg
std::string errorMsg
Definition: launchparser.cpp:104
paramEntryAscii::getMaxValue
std::string getMaxValue()
Definition: launchparser.cpp:75


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08