Skip to content

Commit 2347130

Browse files
committed
fixes and simpler getAnyLocked
1 parent f4ccc74 commit 2347130

File tree

10 files changed

+98
-108
lines changed

10 files changed

+98
-108
lines changed

examples/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,10 @@ CompileExample("t08_additional_node_args")
2727
CompileExample("t09_scripting")
2828
CompileExample("t10_observer")
2929
CompileExample("t11_replace_rules")
30+
31+
if(BTCPP_GROOT_INTERFACE AND BTCPP_SQLITE_LOGGING)
3032
CompileExample("t12_groot_howto")
33+
endif()
3134

3235
CompileExample("ex01_wrap_legacy")
3336
CompileExample("ex02_runtime_ports")

include/behaviortree_cpp/blackboard.h

Lines changed: 18 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#include <stdint.h>
77
#include <unordered_map>
88
#include <mutex>
9-
#include <shared_mutex>
109
#include <sstream>
1110

1211
#include "behaviortree_cpp/basic_types.h"
@@ -16,13 +15,10 @@
1615

1716
namespace BT
1817
{
19-
/// This type contains pointer to Any.
20-
/// Protected with a read-only lock as long as the object is in scope
21-
using AnyPtrReadLock = LockedPtrConst<Any>;
2218

23-
/// This type contains pointer to Any.
24-
/// Protected with a read-write lock as long as the object is in scope
25-
using AnyPtrWriteLock = LockedPtr<Any>;
19+
/// This type contains a pointer to Any, protected
20+
/// with a locked mutex as long as the object is in scope
21+
using AnyPtrLocked = LockedPtr<Any>;
2622

2723
/**
2824
* @brief The Blackboard is the mechanism used by BehaviorTrees to exchange
@@ -45,7 +41,7 @@ class Blackboard
4541
{
4642
Any value;
4743
PortInfo port_info;
48-
std::shared_mutex entry_mutex;
44+
mutable std::mutex entry_mutex;
4945

5046
Entry(const PortInfo& info) : port_info(info)
5147
{}
@@ -91,43 +87,43 @@ class Blackboard
9187
return const_cast<Entry*>( static_cast<const Blackboard &>(*this).getEntry(key));
9288
}
9389

94-
[[nodiscard]] AnyPtrReadLock getAnyRead(const std::string& key) const
90+
[[nodiscard]] AnyPtrLocked getAnyLocked(const std::string& key)
9591
{
9692
if(auto entry = getEntry(key))
9793
{
98-
return AnyPtrReadLock(&entry->value, const_cast<std::shared_mutex*>(&entry->entry_mutex));
94+
return AnyPtrLocked(&entry->value, &entry->entry_mutex);
9995
}
10096
return {};
10197
}
10298

103-
[[nodiscard]] AnyPtrWriteLock getAnyWrite(const std::string& key)
99+
[[nodiscard]] AnyPtrLocked getAnyLocked(const std::string& key) const
104100
{
105101
if(auto entry = getEntry(key))
106102
{
107-
return AnyPtrWriteLock(&entry->value, &entry->entry_mutex);
103+
return AnyPtrLocked(&entry->value, const_cast<std::mutex*>(&entry->entry_mutex));
108104
}
109105
return {};
110106
}
111107

112-
[[deprecated("Use getAnyRead instead")]]
108+
[[deprecated("Use getAnyLocked instead")]]
113109
const Any* getAny(const std::string& key) const
114110
{
115-
return getAnyRead(key).get();
111+
return getAnyLocked(key).get();
116112
}
117113

118-
[[deprecated("Use getAnyWrite instead")]]
114+
[[deprecated("Use getAnyLocked instead")]]
119115
Any* getAny(const std::string& key)
120116
{
121-
return getAnyWrite(key).get();
117+
return const_cast<Any*>(getAnyLocked(key).get());
122118
}
123119

124120
/** Return true if the entry with the given key was found.
125-
* Note that this method may throw an exception if the cast to T failed.
126-
*/
121+
* Note that this method may throw an exception if the cast to T failed.
122+
*/
127123
template <typename T> [[nodiscard]]
128124
bool get(const std::string& key, T& value) const
129125
{
130-
if (auto any_ref = getAnyRead(key))
126+
if (auto any_ref = getAnyLocked(key))
131127
{
132128
value = any_ref.get()->cast<T>();
133129
return true;
@@ -136,12 +132,12 @@ class Blackboard
136132
}
137133

138134
/**
139-
* Version of get() that throws if it fails.
140-
*/
135+
* Version of get() that throws if it fails.
136+
*/
141137
template <typename T> [[nodiscard]]
142138
T get(const std::string& key) const
143139
{
144-
if (auto any_ref = getAnyRead(key))
140+
if (auto any_ref = getAnyLocked(key))
145141
{
146142
return any_ref.get()->cast<T>();
147143
}

include/behaviortree_cpp/decorators/loop_node.h

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,6 @@
1313
#pragma once
1414

1515
#include <deque>
16-
#include <shared_mutex>
1716
#include "behaviortree_cpp/decorator_node.h"
1817

1918
namespace BT
@@ -70,9 +69,9 @@ class LoopNode : public DecoratorNode
7069
{
7170
// if the port is static, any_ref is empty, otherwise it will keep access to
7271
// port locked for thread-safety
73-
AnyPtrWriteLock any_ref = static_queue_ ?
74-
AnyPtrWriteLock() :
75-
getLockedPortContent("queue");
72+
AnyPtrLocked any_ref = static_queue_ ?
73+
AnyPtrLocked() :
74+
getLockedPortContent("queue");
7675
if(any_ref)
7776
{
7877
current_queue_ = any_ref.get()->cast<SharedQueue<T>>();

include/behaviortree_cpp/scripting/operators.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ struct ExprName : ExprBase
6868
}
6969
}
7070
// search now in the variables table
71-
auto any_ref = env.vars->getAnyRead(name);
71+
auto any_ref = env.vars->getAnyLocked(name);
7272
if( !any_ref )
7373
{
7474
throw std::runtime_error("Variable not found");

include/behaviortree_cpp/tree_node.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -270,7 +270,7 @@ class TreeNode
270270
* @return empty AnyWriteRef if the blackboard entry doesn't exist or the content
271271
* of the port was a static string.
272272
*/
273-
[[nodiscard]] AnyPtrWriteLock getLockedPortContent(const std::string& key);
273+
[[nodiscard]] AnyPtrLocked getLockedPortContent(const std::string& key);
274274

275275
// function provided mostly for debugging purpose to see the raw value
276276
// in the port (no remapping and no conversion to a type)
@@ -426,7 +426,7 @@ inline Result TreeNode::getInput(const std::string& key, T& destination) const
426426
return nonstd::make_unexpected("getInput(): trying to access an invalid Blackboard");
427427
}
428428

429-
if (auto any_ref = config_.blackboard->getAnyRead(std::string(remapped_key)))
429+
if (auto any_ref = config_.blackboard->getAnyLocked(std::string(remapped_key)))
430430
{
431431
auto val = any_ref.get();
432432
if(!val->empty())

include/behaviortree_cpp/utils/locked_reference.hpp

Lines changed: 19 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -2,33 +2,46 @@
22

33
#include <memory>
44
#include <mutex>
5-
#include <shared_mutex>
65

76
namespace BT
87
{
98
/**
109
* @brief The LockedPtr class is used to share a pointer to an object
11-
* and a mutex that protects the write access to that object.
10+
* and a mutex that protects the read/write access to that object.
1211
*
13-
* As long as the object remains in scope, the mutex is locked
12+
* As long as the object remains in scope, the mutex is locked, therefore
13+
* you must destroy this object as soon as the pointer was used.
1414
*/
1515
template <typename T>
1616
class LockedPtr {
1717
public:
1818

1919
LockedPtr() = default;
2020

21-
LockedPtr(T* obj, std::shared_mutex* obj_mutex):
21+
LockedPtr(const T* obj, std::mutex* obj_mutex):
2222
ref_(obj), mutex_(obj_mutex) {
2323
mutex_->lock();
2424
}
2525

26-
~LockedPtr() {
26+
~LockedPtr() {
2727
if(mutex_) {
2828
mutex_->unlock();
2929
}
3030
}
3131

32+
LockedPtr(LockedPtr const&) = delete;
33+
LockedPtr& operator=(LockedPtr const&) = delete;
34+
35+
LockedPtr(LockedPtr && other) {
36+
std::swap(ref_, other.ref_);
37+
std::swap(mutex_, other.mutex_);
38+
}
39+
40+
LockedPtr& operator=(LockedPtr&& other) {
41+
std::swap(ref_, other.ref_);
42+
std::swap(mutex_, other.mutex_);
43+
}
44+
3245
operator bool() const {
3346
return ref_ != nullptr;
3447
}
@@ -53,60 +66,10 @@ class LockedPtr {
5366
return ref_;
5467
}
5568

56-
T* get() {
57-
return ref_;
58-
}
59-
60-
private:
61-
T* ref_ = nullptr;
62-
std::shared_mutex* mutex_ = nullptr;
63-
};
64-
65-
/**
66-
* @brief The LockedPtrConst class is used to share a pointer to an object
67-
* and a mutex that protects the access to that object.
68-
* It has a read-only interface, the object can not be modified.
69-
* Multiple instances of LockedPtrConst can exist without a dead-lock.
70-
*
71-
* As long as the object remains in scope, the shared mutex is locked
72-
*/
73-
template <typename T>
74-
class LockedPtrConst {
75-
public:
76-
77-
LockedPtrConst() = default;
78-
79-
LockedPtrConst(LockedPtrConst const&) = delete;
80-
LockedPtrConst& operator=(LockedPtrConst const&) = delete;
81-
82-
LockedPtrConst(const T* obj, std::shared_mutex* obj_mutex):
83-
ref_(obj), mutex_(obj_mutex) {
84-
mutex_->lock_shared();
85-
}
86-
87-
~LockedPtrConst() {
88-
if(mutex_) {
89-
mutex_->unlock_shared();
90-
}
91-
}
92-
93-
operator bool() const {
94-
return ref_ != nullptr;
95-
}
96-
97-
bool empty() const {
98-
return ref_ == nullptr;
99-
}
100-
101-
const T * get() const {
102-
return ref_;
103-
}
104-
10569
private:
10670
const T* ref_ = nullptr;
107-
std::shared_mutex* mutex_ = nullptr;
71+
std::mutex* mutex_ = nullptr;
10872
};
10973

11074

111-
11275
}

src/json_export.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ nlohmann::json ExportBlackboardToJSON(Blackboard &blackboard)
4444
for(auto entry_name: blackboard.getKeys())
4545
{
4646
std::string name(entry_name);
47-
if(auto any_ref = blackboard.getAnyRead(name))
47+
if(auto any_ref = blackboard.getAnyLocked(name))
4848
{
4949
if(auto any_ptr = any_ref.get())
5050
{

src/tree_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -411,11 +411,11 @@ std::string toStr<PostCond>(PostCond pre)
411411
}
412412
}
413413

414-
AnyPtrWriteLock BT::TreeNode::getLockedPortContent(const std::string &key)
414+
AnyPtrLocked BT::TreeNode::getLockedPortContent(const std::string &key)
415415
{
416416
if(auto remapped_key = getRemappedKey(key, getRawPortValue(key)))
417417
{
418-
return config_.blackboard->getAnyWrite(std::string(*remapped_key));
418+
return config_.blackboard->getAnyLocked(std::string(*remapped_key));
419419
}
420420
return {};
421421
}

tests/gtest_blackboard.cpp

Lines changed: 46 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -296,28 +296,57 @@ TEST(BlackboardTest, CheckTypeSafety)
296296
ASSERT_TRUE(is);
297297
}
298298

299-
TEST(BlackboardTest, AnyPtr)
299+
TEST(BlackboardTest, AnyPtrLocked)
300300
{
301301
auto blackboard = Blackboard::create();
302-
auto test_obj = std::make_shared<int>(42);
302+
long value = 0;
303+
long* test_obj = &value;
303304

304305
blackboard->set("testmove", test_obj);
305306

306-
// no deadlock if both are read-only
307+
auto const timeout = std::chrono::milliseconds(250);
308+
309+
// Safe way to access a pointer
307310
{
308-
auto r1 = blackboard->getAnyRead("testmove");
309-
auto r2 = blackboard->getAnyRead("testmove");
311+
std::atomic_llong cycles = 0;
312+
auto func = [&]()
313+
{
314+
auto start = std::chrono::system_clock::now();
315+
while( (std::chrono::system_clock::now() - start) < timeout)
316+
{
317+
auto r1 = blackboard->getAnyLocked("testmove");
318+
auto value_ptr = (r1.get()->cast<long*>());
319+
(*value_ptr)++;
320+
cycles++;
321+
}
322+
};
323+
324+
auto t1 = std::thread(func); // other thread
325+
func(); // this thread
326+
t1.join();
327+
328+
// number of increments and cycles is expected to be the same
329+
ASSERT_EQ(cycles, value);
330+
}
331+
//------------------
332+
// UNSAFE way to access a pointer
333+
{
334+
std::atomic_llong cycles = 0;
335+
auto func = [&]()
336+
{
337+
auto start = std::chrono::system_clock::now();
338+
while( (std::chrono::system_clock::now() - start) < timeout)
339+
{
340+
auto value_ptr = blackboard->get<long*>("testmove");
341+
(*value_ptr)++;
342+
cycles++;
343+
}
344+
};
345+
346+
auto t1 = std::thread(func);
347+
func();
348+
t1.join();
349+
// since the operation value_ptr++ is not thread safe, cycle and value will unlikely be the same
350+
ASSERT_NE(cycles, value);
310351
}
311-
312-
auto double_write = [&]() {
313-
auto w1 = blackboard->getAnyWrite("testmove");
314-
auto w2 = blackboard->getAnyWrite("testmove");
315-
};
316-
EXPECT_ANY_THROW(double_write());
317-
318-
auto write_read = [&]() {
319-
auto w1 = blackboard->getAnyWrite("testmove");
320-
auto r1 = blackboard->getAnyRead("testmove");
321-
};
322-
EXPECT_ANY_THROW(write_read());
323352
}

tests/gtest_factory.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -253,9 +253,9 @@ TEST(BehaviorTreeFactory, SubTreeWithRemapping)
253253
ASSERT_EQ(main_bb->get<std::string>("talk_out"), "done!");
254254

255255
// these ports should not be present in the subtree TalkToMe
256-
ASSERT_FALSE(talk_bb->getAnyRead("talk_hello"));
257-
ASSERT_FALSE(talk_bb->getAnyRead("talk_bye"));
258-
ASSERT_FALSE(talk_bb->getAnyRead("talk_out"));
256+
ASSERT_FALSE(talk_bb->getAnyLocked("talk_hello"));
257+
ASSERT_FALSE(talk_bb->getAnyLocked("talk_bye"));
258+
ASSERT_FALSE(talk_bb->getAnyLocked("talk_out"));
259259
}
260260

261261
std::string FilePath(const std::filesystem::path& relative_path)

0 commit comments

Comments
 (0)