mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
SITL: prevent a conflict with a _serialize() macro on cygwin
some cygwin versions define a macro _serialize with 1 argument
This commit is contained in:
parent
fa2c7113c9
commit
d659642826
@ -225,8 +225,8 @@ public:
|
||||
private:
|
||||
template <typename T> value(const T *); // intentionally defined to block implicit conversion of pointer to bool
|
||||
template <typename Iter> static void _indent(Iter os, int indent);
|
||||
template <typename Iter> void _serialize(Iter os, int indent) const;
|
||||
std::string _serialize(int indent) const;
|
||||
template <typename Iter> void _Serialize(Iter os, int indent) const;
|
||||
std::string _Serialize(int indent) const;
|
||||
void clear();
|
||||
};
|
||||
|
||||
@ -590,11 +590,11 @@ template <typename Iter> void serialize_str(const std::string &s, Iter oi) {
|
||||
}
|
||||
|
||||
template <typename Iter> void value::serialize(Iter oi, bool prettify) const {
|
||||
return _serialize(oi, prettify ? 0 : -1);
|
||||
return _Serialize(oi, prettify ? 0 : -1);
|
||||
}
|
||||
|
||||
inline std::string value::serialize(bool prettify) const {
|
||||
return _serialize(prettify ? 0 : -1);
|
||||
return _Serialize(prettify ? 0 : -1);
|
||||
}
|
||||
|
||||
template <typename Iter> void value::_indent(Iter oi, int indent) {
|
||||
@ -604,7 +604,7 @@ template <typename Iter> void value::_indent(Iter oi, int indent) {
|
||||
}
|
||||
}
|
||||
|
||||
template <typename Iter> void value::_serialize(Iter oi, int indent) const {
|
||||
template <typename Iter> void value::_Serialize(Iter oi, int indent) const {
|
||||
switch (type_) {
|
||||
case string_type:
|
||||
serialize_str(*u_.string_, oi);
|
||||
@ -621,7 +621,7 @@ template <typename Iter> void value::_serialize(Iter oi, int indent) const {
|
||||
if (indent != -1) {
|
||||
_indent(oi, indent);
|
||||
}
|
||||
i->_serialize(oi, indent);
|
||||
i->_Serialize(oi, indent);
|
||||
}
|
||||
if (indent != -1) {
|
||||
--indent;
|
||||
@ -649,7 +649,7 @@ template <typename Iter> void value::_serialize(Iter oi, int indent) const {
|
||||
if (indent != -1) {
|
||||
*oi++ = ' ';
|
||||
}
|
||||
i->second._serialize(oi, indent);
|
||||
i->second._Serialize(oi, indent);
|
||||
}
|
||||
if (indent != -1) {
|
||||
--indent;
|
||||
@ -669,9 +669,9 @@ template <typename Iter> void value::_serialize(Iter oi, int indent) const {
|
||||
}
|
||||
}
|
||||
|
||||
inline std::string value::_serialize(int indent) const {
|
||||
inline std::string value::_Serialize(int indent) const {
|
||||
std::string s;
|
||||
_serialize(std::back_inserter(s), indent);
|
||||
_Serialize(std::back_inserter(s), indent);
|
||||
return s;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user