xmlRpcTreeItem.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, C. Dornhege, University of Freiburg
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of the University of Freiburg nor the names
14  * of its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
21  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  */
28 
30 #include <QDateTime>
31 
32 #include <boost/foreach.hpp>
33 #define forEach BOOST_FOREACH
34 
35 XmlRpcTreeItem::XmlRpcTreeItem(XmlRpc::XmlRpcValue* data, XmlRpcTreeItem* parent, const std::string & path,
36  ros::NodeHandle* nh)
37  : _data(data), _parent(parent), _path(path), _nh(nh)
38 {
39  ROS_ASSERT(_nh != NULL);
40 
42 }
43 
45 {
47  delete child;
48  _children.clear();
49 }
50 
55 unsigned int XmlRpcTreeItem::childCount() const
56 {
57  if(_children.size() > 0)
58  return _children.size();
59 
60  return 0;
61 }
62 
64 {
65  int index = -1;
66  for(unsigned int i = 0; i < _children.size(); i++) {
67  if(child == _children[i]) {
68  index = i;
69  break;
70  }
71  }
72  return index;
73 }
74 
76 {
77  if(_parent) {
78  return _parent->childIndexOf(this);
79  }
80 
81  // root at index 0
82  return 0;
83 }
84 
86 {
87  switch(val.getType()) {
89  return QVariant( (bool)val );
90  break;
92  return QVariant( (int)val );
93  break;
95  return QVariant( (double)val );
96  break;
98  return QVariant( ((std::string)val).c_str() );
99  break;
101  {
102  ROS_WARN_THROTTLE(1.0, "Accessing TypeDateTime is untested.");
103  struct tm time = (struct tm)val;
104  int ms = 0;
105  if(time.tm_sec > 59) // might be > 59 for leap seconds, Qt wants 0-59
106  ms = 999;
107 
108  return QVariant( QDateTime(
109  /*
110  * tm_mday day of the month 1-31
111  * tm_mon months since January 0-11
112  * tm_year years since 1900
113  */
114  QDate(time.tm_year + 1900, time.tm_mon + 1, time.tm_mday),
115  /*
116  * tm_sec seconds after the minute 0-61
117  * tm_min minutes after the hour 0-59
118  * tm_hour hours since midnight 0-23
119  */
120  QTime(time.tm_hour, time.tm_min, time.tm_sec, ms)));
121  break;
122  }
124  {
125  ROS_WARN_THROTTLE(1.0, "Accessing TypeBase64 is untested.");
127  QByteArray ba;
128  for(std::vector<char>::iterator it = bd.begin(); it != bd.end(); it++)
129  ba.append(*it);
130  return QVariant(ba);
131  break;
132  }
133  default:
134  return QVariant();
135  }
136 
137  return QVariant();
138 }
139 
140 QVariant XmlRpcTreeItem::data(int row, int column) const
141 {
142  // this node always has to be a map!
143 
144  if(column > 1)
145  return QVariant();
146 
147  // get the row'th entry
149  int count = 0;
150  for(XmlRpc::XmlRpcValue::iterator it = _data->begin(); it != _data->end(); it++) {
151  if(count == row) { // at row'th entry
152  if(column == 0) { // get the rows'th key
153  return it->first.c_str();
154  }
155  if(column == 1) {
156  XmlRpc::XmlRpcValue & val = it->second;
157  return xmlToVariant(val);
158  }
159  }
160  count++;
161  }
162  } else if(_data->getType() == XmlRpc::XmlRpcValue::TypeArray) {
163  if(column == 0) {
164  return QString("[%1]").arg(row);
165  } else {
166  XmlRpc::XmlRpcValue & val = (*_data)[row];
167  return xmlToVariant(val);
168  }
169  }
170 
171  // nothing found
172  return QVariant();
173 }
174 
175 bool XmlRpcTreeItem::isBool(int row, int column) const
176 {
177  // this node always has to be a map!
178 
179  if(column != 1)
180  return false;
181 
182  // get the row'th entry
184  int count = 0;
185  for(XmlRpc::XmlRpcValue::iterator it = _data->begin(); it != _data->end(); it++) {
186  if(count == row) { // at row'th entry
187  XmlRpc::XmlRpcValue & val = it->second;
189  return true;
190  else
191  return false;
192  }
193  count++;
194  }
195  } else if(_data->getType() == XmlRpc::XmlRpcValue::TypeArray) {
196  XmlRpc::XmlRpcValue & val = (*_data)[row];
198  return true;
199  else
200  return false;
201  }
202 
203  // nothing found
204  return false;
205 }
206 
207 bool XmlRpcTreeItem::setData(QVariant val)
208 {
212  return false;
213  }
214 
215  bool setXmlOK = false;
216  switch(type) {
218  if(!val.canConvert(QVariant::Bool)) {
219  ROS_WARN("XmlRpcValue TypeBoolean -- setData cannot convert from QVariant type %d.", val.type());
220  break;
221  }
222  ROS_DEBUG("Setting bool param.");
223  (bool&)(*_data) = val.toBool();
224  setXmlOK = true;
225  break;
227  {
228  if(!val.canConvert(QVariant::Int)) {
229  ROS_WARN("XmlRpcValue TypeInt -- setData cannot convert from QVariant type %d.", val.type());
230  break;
231  }
232  bool ok = false;
233  int iVal = val.toInt(&ok);
234  if(ok) {
235  ROS_DEBUG("Setting int param.");
236  (int&)(*_data) = iVal;
237  setXmlOK = true;
238  }
239  break;
240  }
242  {
243  if(!val.canConvert(QVariant::Double)) {
244  ROS_WARN("XmlRpcValue TypeDouble -- setData cannot convert from QVariant type %d.", val.type());
245  break;
246  }
247  // although e.g. strings can be converted to double in principle, the conversion of "hallo" still fails
248  // -> check via OK and only update _data if the conversion succeeded.
249  bool ok = false;
250  double dVal = val.toDouble(&ok);
251  if(ok) {
252  ROS_DEBUG("Setting double param.");
253  (double&)(*_data) = dVal;
254  setXmlOK = true;
255  }
256  break;
257  }
259  if(!val.canConvert(QVariant::String)) {
260  ROS_WARN("XmlRpcValue TypeString -- setData cannot convert from QVariant type %d.", val.type());
261  break;
262  }
263  ROS_DEBUG("Setting string param.");
264  (std::string&)(*_data) = qPrintable(val.toString());
265  setXmlOK = true;
266  break;
268  {
269  ROS_WARN_THROTTLE(1.0, "Accessing TypeDateTime is untested.");
270  if(!val.canConvert(QVariant::DateTime)) {
271  ROS_WARN("XmlRpcValue TypeDateTime -- setData cannot convert from QVariant type %d.", val.type());
272  break;
273  }
274  QDateTime dt = val.toDateTime();
275  if(dt.isValid()) {
276  ROS_DEBUG("Setting datetime param.");
277  struct tm time;
278  time.tm_year = dt.date().year() - 1900;
279  time.tm_mon = dt.date().month() - 1;
280  time.tm_mday = dt.date().day();
281  time.tm_hour = dt.time().hour();
282  time.tm_min = dt.time().minute();
283  time.tm_sec = dt.time().second();
284  time.tm_wday = dt.date().dayOfWeek() - 1;
285  time.tm_yday = dt.date().dayOfYear() - 1;
286  time.tm_isdst = -1;
287  time.tm_zone = "";
288  time.tm_gmtoff = 0;
289 
290  (struct tm &)(*_data) = time;
291  setXmlOK = true;
292  }
293  break;
294  }
296  {
297  ROS_WARN_THROTTLE(1.0, "Accessing TypeBase64 is untested.");
298  if(!val.canConvert(QVariant::ByteArray)) {
299  ROS_WARN("XmlRpcValue TypeBase64 -- setData cannot convert from QVariant type %d.", val.type());
300  break;
301  }
302  QByteArray ba = val.toByteArray();
304  for(int i = 0; i < ba.size(); i++) {
305  bd.push_back(ba.at(i));
306  }
307  ROS_DEBUG("Setting base64 param.");
309  break;
310  }
311  default:
312  return false;
313  }
314  if(setXmlOK) {
315  if(!_path.empty()) {
316  ROS_DEBUG("Setting param type %d on server path %s.", _data->getType(), _path.c_str());
317  _nh->setParam(_path, *_data);
318  } else {
319  _parent->setParam();
320  }
321  }
322 
323  return true;
324 }
325 
327 {
329 
330  ROS_DEBUG("Setting param type %d on server path %s.", _data->getType(), _path.c_str());
331  if(!_path.empty())
332  _nh->setParam(_path, *_data);
333 }
334 
336 {
337  // only maps and arrays have children
338 
340  for(XmlRpc::XmlRpcValue::iterator it = _data->begin(); it != _data->end(); it++) {
341  addChild(it->first, &it->second);
342  }
343  } else if(_data->getType() == XmlRpc::XmlRpcValue::TypeArray) {
344  for(int i = 0; i < _data->size(); i++) {
345  addChild("", & ((*_data)[i]));
346  }
347  }
348 }
349 
350 void XmlRpcTreeItem::addChild(const std::string & name, XmlRpc::XmlRpcValue* childData)
351 {
352  std::string path = ros::names::append(this->_path, name);
353  if(name.empty())
354  path = name; // no path
355  XmlRpcTreeItem* child = new XmlRpcTreeItem(childData, this, path, _nh);
356  _children.push_back(child);
357 }
358 
QVariant xmlToVariant(XmlRpc::XmlRpcValue &val) const
Convert a XmlRpcValue to QVariant - only leaf values are supported.
A wrapper around the XmlRpcValue including a parent pointer and convenience functions for the qt mode...
ValueStruct::iterator iterator
bool setData(QVariant val)
set data for this item
void setParam()
write this XmlRpcValue to parameter server (for array childs).
#define ROS_WARN(...)
deque< XmlRpcTreeItem * > _children
Type const & getType() const
bool isBool(int row, int column) const
is the stored data a bool
void addChild(const std::string &name, XmlRpc::XmlRpcValue *childData)
Create a child from its data.
#define ROS_WARN_THROTTLE(period,...)
ROSCPP_DECL bool ok()
QVariant data(int row, int column) const
return the data in the map
int childIndexOf(const XmlRpcTreeItem *child) const
void createChildren()
Create all children based on data.
#define forEach
XmlRpc::XmlRpcValue * _data
XmlRpcTreeItem * child(unsigned int i)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
int row() const
Figure out which row/nth child we are for the parent.
std::string _path
unsigned int childCount() const
std::vector< char > BinaryData
#define ROS_ASSERT(cond)
ros::NodeHandle * _nh
XmlRpcTreeItem(XmlRpc::XmlRpcValue *data, XmlRpcTreeItem *parent, const std::string &path, ros::NodeHandle *nh)
XmlRpcTreeItem * _parent
#define ROS_DEBUG(...)


qt_paramedit
Author(s): Christian Dornhege
autogenerated on Mon Feb 28 2022 23:37:51