Skip to content

Commit 1769591

Browse files
committed
add [[nodiscard]] and some othe minor changes
1 parent a50c58f commit 1769591

File tree

2 files changed

+35
-27
lines changed

2 files changed

+35
-27
lines changed

include/behaviortree_cpp/basic_types.h

Lines changed: 27 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
1-
#ifndef BT_BASIC_TYPES_H
2-
#define BT_BASIC_TYPES_H
1+
#pragma once
32

43
#include <iostream>
54
#include <vector>
@@ -70,7 +69,7 @@ using StringView = std::string_view;
7069
*
7170
* If you have a custom type, you need to implement the corresponding template specialization.
7271
*/
73-
template <typename T>
72+
template <typename T> [[nodiscard]]
7473
inline T convertFromString(StringView /*str*/)
7574
{
7675
auto type_name = BT::demangle(typeid(T));
@@ -145,13 +144,13 @@ inline StringConverter GetAnyFromStringFunctor<void>()
145144

146145
//------------------------------------------------------------------
147146

148-
template <typename T>
147+
template <typename T> [[nodiscard]]
149148
std::string toStr(T value)
150149
{
151150
return std::to_string(value);
152151
}
153152

154-
std::string toStr(std::string value);
153+
std::string toStr(const std::string& value);
155154

156155
template <>
157156
std::string toStr<BT::NodeStatus>(BT::NodeStatus status);
@@ -166,17 +165,18 @@ std::ostream& operator<<(std::ostream& os, const BT::NodeStatus& status);
166165
/**
167166
* @brief toStr converts NodeType to string.
168167
*/
169-
template <>
168+
template <> [[nodiscard]]
170169
std::string toStr<BT::NodeType>(BT::NodeType type);
171170

172171
std::ostream& operator<<(std::ostream& os, const BT::NodeType& type);
173172

174-
template <>
173+
template <> [[nodiscard]]
175174
std::string toStr<BT::PortDirection>(BT::PortDirection direction);
176175

177176
std::ostream& operator<<(std::ostream& os, const BT::PortDirection& type);
178177

179178
// Small utility, unless you want to use <boost/algorithm/string.hpp>
179+
[[nodiscard]]
180180
std::vector<StringView> splitString(const StringView& strToSplit, char delimeter);
181181

182182
template <typename Predicate>
@@ -228,6 +228,7 @@ using Optional = nonstd::expected<T, std::string>;
228228
* */
229229
using Result = Expected<std::monostate>;
230230

231+
[[nodiscard]]
231232
bool IsAllowedPortName(StringView str);
232233

233234
class PortInfo
@@ -245,15 +246,15 @@ class PortInfo
245246
_type(direction), _type_info(type_info), _converter(conv)
246247
{}
247248

248-
PortDirection direction() const;
249+
[[nodiscard]] PortDirection direction() const;
249250

250-
const std::type_index& type() const;
251+
[[nodiscard]] const std::type_index& type() const;
251252

252-
Any parseString(const char* str) const;
253+
[[nodiscard]] Any parseString(const char* str) const;
253254

254-
Any parseString(const std::string& str) const;
255+
[[nodiscard]] Any parseString(const std::string& str) const;
255256

256-
template <typename T>
257+
template <typename T> [[nodiscard]]
257258
Any parseString(const T&) const
258259
{
259260
// avoid compilation errors
@@ -264,16 +265,16 @@ class PortInfo
264265

265266
void setDefaultValue(StringView default_value_as_string);
266267

267-
const std::string& description() const;
268+
[[nodiscard]] const std::string& description() const;
268269

269-
std::optional<std::string> defaultValue() const;
270+
[[nodiscard]] std::optional<std::string> defaultValue() const;
270271

271-
bool isStronglyTyped() const
272+
[[nodiscard]] bool isStronglyTyped() const
272273
{
273274
return _type_info != typeid(AnyTypeAllowed);
274275
}
275276

276-
const StringConverter& converter() const
277+
[[nodiscard]] const StringConverter& converter() const
277278
{
278279
return _converter;
279280
}
@@ -286,8 +287,9 @@ class PortInfo
286287
std::optional<std::string> default_value_;
287288
};
288289

289-
template <typename T = PortInfo::AnyTypeAllowed>
290-
std::pair<std::string, PortInfo> CreatePort(PortDirection direction, StringView name,
290+
template <typename T = PortInfo::AnyTypeAllowed> [[nodiscard]]
291+
std::pair<std::string, PortInfo> CreatePort(PortDirection direction,
292+
StringView name,
291293
StringView description = {})
292294
{
293295
auto sname = static_cast<std::string>(name);
@@ -316,28 +318,28 @@ std::pair<std::string, PortInfo> CreatePort(PortDirection direction, StringView
316318
}
317319

318320
//----------
319-
template <typename T = void>
321+
template <typename T = void> [[nodiscard]]
320322
inline std::pair<std::string, PortInfo> InputPort(StringView name,
321323
StringView description = {})
322324
{
323325
return CreatePort<T>(PortDirection::INPUT, name, description);
324326
}
325327

326-
template <typename T = void>
328+
template <typename T = void> [[nodiscard]]
327329
inline std::pair<std::string, PortInfo> OutputPort(StringView name,
328330
StringView description = {})
329331
{
330332
return CreatePort<T>(PortDirection::OUTPUT, name, description);
331333
}
332334

333-
template <typename T = void>
335+
template <typename T = void> [[nodiscard]]
334336
inline std::pair<std::string, PortInfo> BidirectionalPort(StringView name,
335337
StringView description = {})
336338
{
337339
return CreatePort<T>(PortDirection::INOUT, name, description);
338340
}
339341
//----------
340-
template <typename T = void>
342+
template <typename T = void> [[nodiscard]]
341343
inline std::pair<std::string, PortInfo> InputPort(StringView name, const T& default_value,
342344
StringView description)
343345
{
@@ -346,7 +348,7 @@ inline std::pair<std::string, PortInfo> InputPort(StringView name, const T& defa
346348
return out;
347349
}
348350

349-
template <typename T = void>
351+
template <typename T = void> [[nodiscard]]
350352
inline std::pair<std::string, PortInfo> BidirectionalPort(StringView name,
351353
const T& default_value,
352354
StringView description)
@@ -372,13 +374,13 @@ struct has_static_method_providedPorts<
372374
{
373375
};
374376

375-
template <typename T>
377+
template <typename T> [[nodiscard]]
376378
inline PortsList getProvidedPorts(enable_if<has_static_method_providedPorts<T>> = nullptr)
377379
{
378380
return T::providedPorts();
379381
}
380382

381-
template <typename T>
383+
template <typename T> [[nodiscard]]
382384
inline PortsList
383385
getProvidedPorts(enable_if_not<has_static_method_providedPorts<T>> = nullptr)
384386
{
@@ -390,4 +392,3 @@ typedef std::chrono::high_resolution_clock::duration Duration;
390392

391393
} // namespace BT
392394

393-
#endif // BT_BASIC_TYPES_H

src/basic_types.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ std::string toStr<NodeStatus>(NodeStatus status)
2525
return "";
2626
}
2727

28-
std::string toStr(std::string value)
28+
std::string toStr(const std::string &value)
2929
{
3030
return value;
3131
}
@@ -242,6 +242,9 @@ NodeStatus convertFromString<NodeStatus>(StringView str)
242242
return NodeStatus::SUCCESS;
243243
if (str == "FAILURE")
244244
return NodeStatus::FAILURE;
245+
if (str == "SKIPPED")
246+
return NodeStatus::SKIPPED;
247+
245248
throw RuntimeError(std::string("Cannot convert this to NodeStatus: ") +
246249
static_cast<std::string>(str));
247250
}
@@ -363,6 +366,10 @@ std::optional<std::string> PortInfo::defaultValue() const
363366

364367
bool IsAllowedPortName(StringView str)
365368
{
369+
if( str == "_autoremap")
370+
{
371+
return true;
372+
}
366373
if (str.empty())
367374
{
368375
return false;

0 commit comments

Comments
 (0)