-
Notifications
You must be signed in to change notification settings - Fork 98
/
Param.cc
646 lines (599 loc) · 16.6 KB
/
Param.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
/*
* Copyright 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <algorithm>
#include <cctype>
#include <cstdint>
#include <locale>
#include <sstream>
#include <string>
#include <locale.h>
#include <math.h>
#include "sdf/Assert.hh"
#include "sdf/Param.hh"
#include "sdf/Types.hh"
using namespace sdf;
// For some locale, the decimal separator is not a point, but a
// comma. To avoid that the SDF parsing is influenced by the current
// global C or C++ locale, we define a custom std::stringstream variant
// that always uses the std::locale::classic() locale.
// See issues https://github.com/osrf/sdformat/issues/60
// and https://github.com/osrf/sdformat/issues/207 for more details.
namespace sdf
{
inline namespace SDF_VERSION_NAMESPACE {
class StringStreamClassicLocale : public std::stringstream
{
public: explicit StringStreamClassicLocale()
{
this->imbue(std::locale::classic());
}
public: explicit StringStreamClassicLocale(const std::string& str)
: std::stringstream(str)
{
this->imbue(std::locale::classic());
}
};
}
}
//////////////////////////////////////////////////
Param::Param(const std::string &_key, const std::string &_typeName,
const std::string &_default, bool _required,
const std::string &_description)
: dataPtr(new ParamPrivate)
{
this->dataPtr->key = _key;
this->dataPtr->required = _required;
this->dataPtr->typeName = _typeName;
this->dataPtr->description = _description;
this->dataPtr->set = false;
SDF_ASSERT(this->ValueFromString(_default), "Invalid parameter");
this->dataPtr->defaultValue = this->dataPtr->value;
}
//////////////////////////////////////////////////
Param::Param(const std::string &_key, const std::string &_typeName,
const std::string &_default, bool _required,
const std::string &_minValue, const std::string &_maxValue,
const std::string &_description)
: Param(_key, _typeName, _default, _required, _description)
{
auto valCopy = this->dataPtr->value;
if (!_minValue.empty())
{
SDF_ASSERT(
this->ValueFromString(_minValue),
std::string("Invalid [min] parameter in SDFormat description of [") +
_key + "]");
this->dataPtr->minValue = this->dataPtr->value;
}
if (!_maxValue.empty())
{
SDF_ASSERT(
this->ValueFromString(_maxValue),
std::string("Invalid [max] parameter in SDFormat description of [") +
_key + "]");
this->dataPtr->maxValue = this->dataPtr->value;
}
this->dataPtr->value = valCopy;
}
Param::Param(const Param &_param)
: dataPtr(std::make_unique<ParamPrivate>(*_param.dataPtr))
{
// We don't want to copy the updateFunc
this->dataPtr->updateFunc = nullptr;
}
//////////////////////////////////////////////////
Param::~Param()
{
}
/////////////////////////////////////////////////
Param &Param::operator=(const Param &_param)
{
auto updateFuncCopy = this->dataPtr->updateFunc;
*this = Param(_param);
// Restore the update func
this->dataPtr->updateFunc = updateFuncCopy;
return *this;
}
//////////////////////////////////////////////////
bool Param::GetAny(std::any &_anyVal) const
{
if (this->IsType<int>())
{
int ret = 0;
if (!this->Get<int>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<std::uint64_t>())
{
uint64_t ret = 0;
if (!this->Get<std::uint64_t>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<double>())
{
double ret = 0;
if (!this->Get<double>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<float>())
{
float ret = 0;
if (!this->Get<float>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<bool>())
{
bool ret = false;
if (!this->Get<bool>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<std::string>())
{
std::string ret;
if (!this->Get<std::string>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<unsigned int>())
{
unsigned int ret = 0;
if (!this->Get<unsigned int>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<char>())
{
char ret = 0;
if (!this->Get<char>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<sdf::Time>())
{
sdf::Time ret;
if (!this->Get<sdf::Time>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Color>())
{
ignition::math::Color ret;
if (!this->Get<ignition::math::Color>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Vector3d>())
{
ignition::math::Vector3d ret;
if (!this->Get<ignition::math::Vector3d>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Vector2i>())
{
ignition::math::Vector2i ret;
if (!this->Get<ignition::math::Vector2i>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Vector2d>())
{
ignition::math::Vector2d ret;
if (!this->Get<ignition::math::Vector2d>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Pose3d>())
{
ignition::math::Pose3d ret;
if (!this->Get<ignition::math::Pose3d>(ret))
{
return false;
}
_anyVal = ret;
}
else if (this->IsType<ignition::math::Quaterniond>())
{
ignition::math::Quaterniond ret;
if (!this->Get<ignition::math::Quaterniond>(ret))
{
return false;
}
_anyVal = ret;
}
else
{
sdferr << "Type of parameter not known: [" << this->GetTypeName() << "]\n";
return false;
}
return true;
}
//////////////////////////////////////////////////
void Param::Update()
{
if (this->dataPtr->updateFunc)
{
try
{
std::any newValue = this->dataPtr->updateFunc();
std::visit([&](auto &&arg)
{
using T = std::decay_t<decltype(arg)>;
arg = std::any_cast<T>(newValue);
}, this->dataPtr->value);
}
catch(...)
{
sdferr << "Unable to set value using Update for key["
<< this->dataPtr->key << "]\n";
}
}
}
//////////////////////////////////////////////////
std::string Param::GetAsString() const
{
StringStreamClassicLocale ss;
ss << ParamStreamer{ this->dataPtr->value };
return ss.str();
}
//////////////////////////////////////////////////
std::string Param::GetDefaultAsString() const
{
StringStreamClassicLocale ss;
ss << ParamStreamer{ this->dataPtr->defaultValue };
return ss.str();
}
//////////////////////////////////////////////////
std::optional<std::string> Param::GetMinValueAsString() const
{
if (this->dataPtr->minValue.has_value())
{
StringStreamClassicLocale ss;
ss << ParamStreamer{ *this->dataPtr->minValue };
return ss.str();
}
return std::nullopt;
}
//////////////////////////////////////////////////
std::optional<std::string> Param::GetMaxValueAsString() const
{
if (this->dataPtr->maxValue.has_value())
{
StringStreamClassicLocale ss;
ss << ParamStreamer{ *this->dataPtr->maxValue };
return ss.str();
}
return std::nullopt;
}
//////////////////////////////////////////////////
/// \brief Helper function for Param::ValueFromString
/// \param[in] _input Input string.
/// \param[in] _key Key of the parameter, used for error message.
/// \param[out] _value This will be set with the parsed value.
/// \return True if parsing succeeded.
template <typename T>
bool ParseUsingStringStream(const std::string &_input, const std::string &_key,
ParamPrivate::ParamVariant &_value)
{
StringStreamClassicLocale ss(_input);
T _val;
ss >> _val;
if (ss.fail())
{
sdferr << "Unknown error. Unable to set value [" << _input << " ] for key["
<< _key << "]\n";
return false;
}
_value = _val;
return true;
}
//////////////////////////////////////////////////
bool Param::ValueFromString(const std::string &_value)
{
// Under some circumstances, latin locales (es_ES or pt_BR) will return a
// comma for decimal position instead of a dot, making the conversion
// to fail. See bug #60 for more information. Force to use always C
setlocale(LC_NUMERIC, "C");
std::string trimmed = sdf::trim(_value);
std::string tmp(trimmed);
std::string lowerTmp = lowercase(trimmed);
// "true" and "false" doesn't work properly
if (lowerTmp == "true")
{
tmp = "1";
}
else if (lowerTmp == "false")
{
tmp = "0";
}
bool isHex = lowerTmp.compare(0, 2, "0x") == 0;
try
{
// Try to use stoi and stoul for integers, and
// stof and stod for scalar floating point values.
int numericBase = 10;
if (isHex)
{
numericBase = 16;
}
if (this->dataPtr->typeName == "bool")
{
if (lowerTmp == "true" || lowerTmp == "1")
{
this->dataPtr->value = true;
}
else if (lowerTmp == "false" || lowerTmp == "0")
{
this->dataPtr->value = false;
}
else
{
sdferr << "Invalid boolean value\n";
return false;
}
}
else if (this->dataPtr->typeName == "char")
{
this->dataPtr->value = tmp[0];
}
else if (this->dataPtr->typeName == "std::string" ||
this->dataPtr->typeName == "string")
{
this->dataPtr->value = tmp;
}
else if (this->dataPtr->typeName == "int")
{
this->dataPtr->value = std::stoi(tmp, nullptr, numericBase);
}
else if (this->dataPtr->typeName == "uint64_t")
{
return ParseUsingStringStream<std::uint64_t>(tmp, this->dataPtr->key,
this->dataPtr->value);
}
else if (this->dataPtr->typeName == "unsigned int")
{
this->dataPtr->value = static_cast<unsigned int>(
std::stoul(tmp, nullptr, numericBase));
}
else if (this->dataPtr->typeName == "double")
{
this->dataPtr->value = std::stod(tmp);
}
else if (this->dataPtr->typeName == "float")
{
this->dataPtr->value = std::stof(tmp);
}
else if (this->dataPtr->typeName == "sdf::Time" ||
this->dataPtr->typeName == "time")
{
return ParseUsingStringStream<sdf::Time>(tmp, this->dataPtr->key,
this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Color" ||
this->dataPtr->typeName == "color")
{
// The insertion operator (>>) expects 4 values, but the last value (the
// alpha) is optional. We first try to parse assuming the alpha is
// specified. If that fails, we append the default value of alpha to the
// string and try to parse again.
bool result = ParseUsingStringStream<ignition::math::Color>(
tmp, this->dataPtr->key, this->dataPtr->value);
if (!result)
{
ignition::math::Color colortmp;
return ParseUsingStringStream<ignition::math::Color>(
tmp + " " + std::to_string(colortmp.A()), this->dataPtr->key,
this->dataPtr->value);
}
else
return true;
}
else if (this->dataPtr->typeName == "ignition::math::Vector2i" ||
this->dataPtr->typeName == "vector2i")
{
return ParseUsingStringStream<ignition::math::Vector2i>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Vector2d" ||
this->dataPtr->typeName == "vector2d")
{
return ParseUsingStringStream<ignition::math::Vector2d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Vector3d" ||
this->dataPtr->typeName == "vector3")
{
return ParseUsingStringStream<ignition::math::Vector3d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else if (this->dataPtr->typeName == "ignition::math::Pose3d" ||
this->dataPtr->typeName == "pose" ||
this->dataPtr->typeName == "Pose")
{
if (!tmp.empty())
{
return ParseUsingStringStream<ignition::math::Pose3d>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
}
else if (this->dataPtr->typeName == "ignition::math::Quaterniond" ||
this->dataPtr->typeName == "quaternion")
{
return ParseUsingStringStream<ignition::math::Quaterniond>(
tmp, this->dataPtr->key, this->dataPtr->value);
}
else
{
sdferr << "Unknown parameter type[" << this->dataPtr->typeName << "]\n";
return false;
}
}
// Catch invalid argument exception from std::stoi/stoul/stod/stof
catch(std::invalid_argument &)
{
sdferr << "Invalid argument. Unable to set value ["
<< _value << " ] for key["
<< this->dataPtr->key << "].\n";
return false;
}
// Catch out of range exception from std::stoi/stoul/stod/stof
catch(std::out_of_range &)
{
sdferr << "Out of range. Unable to set value ["
<< _value << " ] for key["
<< this->dataPtr->key << "].\n";
return false;
}
return true;
}
//////////////////////////////////////////////////
bool Param::SetFromString(const std::string &_value)
{
std::string str = sdf::trim(_value.c_str());
if (str.empty() && this->dataPtr->required)
{
sdferr << "Empty string used when setting a required parameter. Key["
<< this->GetKey() << "]\n";
return false;
}
else if (str.empty())
{
this->dataPtr->value = this->dataPtr->defaultValue;
return true;
}
auto oldValue = this->dataPtr->value;
if (!this->ValueFromString(str))
{
return false;
}
// Check if the value is permitted
if (!this->ValidateValue())
{
this->dataPtr->value = oldValue;
return false;
}
this->dataPtr->set = true;
return this->dataPtr->set;
}
//////////////////////////////////////////////////
void Param::Reset()
{
this->dataPtr->value = this->dataPtr->defaultValue;
this->dataPtr->set = false;
}
//////////////////////////////////////////////////
ParamPtr Param::Clone() const
{
return std::make_shared<Param>(*this);
}
//////////////////////////////////////////////////
const std::string &Param::GetTypeName() const
{
return this->dataPtr->typeName;
}
/////////////////////////////////////////////////
void Param::SetDescription(const std::string &_desc)
{
this->dataPtr->description = _desc;
}
/////////////////////////////////////////////////
std::string Param::GetDescription() const
{
return this->dataPtr->description;
}
/////////////////////////////////////////////////
const std::string &Param::GetKey() const
{
return this->dataPtr->key;
}
/////////////////////////////////////////////////
bool Param::GetRequired() const
{
return this->dataPtr->required;
}
/////////////////////////////////////////////////
bool Param::GetSet() const
{
return this->dataPtr->set;
}
/////////////////////////////////////////////////
bool Param::ValidateValue() const
{
return std::visit(
[this](const auto &_val) -> bool
{
using T = std::decay_t<decltype(_val)>;
// cppcheck-suppress syntaxError
if constexpr (std::is_scalar_v<T>)
{
if (this->dataPtr->minValue.has_value())
{
if (_val < std::get<T>(*this->dataPtr->minValue))
{
sdferr << "The value [" << _val
<< "] is less than the minimum allowed value of ["
<< *this->GetMinValueAsString() << "] for key ["
<< this->GetKey() << "]\n";
return false;
}
}
if (this->dataPtr->maxValue.has_value())
{
if (_val > std::get<T>(*this->dataPtr->maxValue))
{
sdferr << "The value [" << _val
<< "] is greater than the maximum allowed value of ["
<< *this->GetMaxValueAsString() << "] for key ["
<< this->GetKey() << "]\n";
return false;
}
}
}
return true;
}, this->dataPtr->value);
}