File tree Expand file tree Collapse file tree 2 files changed +61
-5
lines changed Expand file tree Collapse file tree 2 files changed +61
-5
lines changed Original file line number Diff line number Diff line change @@ -62,26 +62,35 @@ enum class PostCond
6262 COUNT_
6363};
6464
65+ template <>
66+ std::string toStr<BT::PostCond>(BT::PostCond status);
67+
68+ template <>
69+ std::string toStr<BT::PreCond>(BT::PreCond status);
70+
6571using ScriptingEnumsRegistry = std::unordered_map<std::string, int >;
6672
6773struct NodeConfig
6874{
6975 NodeConfig ()
7076 {}
7177
78+ // Pointer to the blackboard used by this node
7279 Blackboard::Ptr blackboard;
80+ // List of enums available for scripting
7381 std::shared_ptr<ScriptingEnumsRegistry> enums;
82+ // input ports
7483 PortsRemapping input_ports;
84+ // output ports
7585 PortsRemapping output_ports;
7686
7787 std::map<PreCond, std::string> pre_conditions;
7888 std::map<PostCond, std::string> post_conditions;
7989};
8090
81- #ifdef USE_BTCPP3_OLD_NAMES
8291// back compatibility
8392using NodeConfiguration = NodeConfig;
84- # endif
93+
8594
8695template <typename T>
8796inline constexpr bool hasNodeNameCtor ()
@@ -360,7 +369,7 @@ inline Result TreeNode::getInput(const std::string& key, T& destination) const
360369 return nonstd::make_unexpected (" getInput(): trying to access an invalid Blackboard" );
361370 }
362371
363- std::unique_lock<std::mutex> entry_lock (config_.blackboard ->entryMutex ());
372+ std::unique_lock entry_lock (config_.blackboard ->entryMutex ());
364373 const Any* val = config_.blackboard ->getAny (static_cast <std::string>(remapped_key));
365374 if (val && !val->empty ())
366375 {
Original file line number Diff line number Diff line change @@ -170,8 +170,19 @@ void TreeNode::checkPostConditions(NodeStatus status)
170170
171171void TreeNode::resetStatus ()
172172{
173- std::unique_lock<std::mutex> lock (state_mutex_);
174- status_ = NodeStatus::IDLE;
173+ NodeStatus prev_status;
174+ {
175+ std::unique_lock<std::mutex> lock (state_mutex_);
176+ prev_status = status_;
177+ status_ = NodeStatus::IDLE;
178+ }
179+
180+ if (prev_status != NodeStatus::IDLE)
181+ {
182+ state_condition_variable_.notify_all ();
183+ state_change_signal_.notify (std::chrono::high_resolution_clock::now (), *this ,
184+ prev_status, NodeStatus::IDLE);
185+ }
175186}
176187
177188NodeStatus TreeNode::status () const
@@ -323,4 +334,40 @@ void TreeNode::modifyPortsRemapping(const PortsRemapping& new_remapping)
323334 }
324335}
325336
337+ template <>
338+ std::string toStr<PreCond>(PreCond pre )
339+ {
340+ switch (pre )
341+ {
342+ case PreCond::SUCCESS_IF:
343+ return " _successIf" ;
344+ case PreCond::FAILURE_IF:
345+ return " _failureIf" ;
346+ case PreCond::SKIP_IF:
347+ return " _skipIf" ;
348+ case PreCond::WHILE_TRUE:
349+ return " _while" ;
350+ default :
351+ return " Undefined" ;
352+ }
353+ }
354+
355+ template <>
356+ std::string toStr<PostCond>(PostCond pre )
357+ {
358+ switch (pre )
359+ {
360+ case PostCond::ON_SUCCESS:
361+ return " _onSuccess" ;
362+ case PostCond::ON_FAILURE:
363+ return " _onFailure" ;
364+ case PostCond::ALWAYS:
365+ return " _post" ;
366+ case PostCond::ON_HALTED:
367+ return " _onHalted" ;
368+ default :
369+ return " Undefined" ;
370+ }
371+ }
372+
326373} // namespace BT
You can’t perform that action at this time.
0 commit comments