groot2_publisher.cpp
Go to the documentation of this file.
4 #include "cppzmq/zmq.hpp"
5 #include "cppzmq/zmq_addon.hpp"
6 
7 namespace BT
8 {
9 //------------------------------------------------------
11 std::set<unsigned> Groot2Publisher::used_ports;
12 
13 enum
14 {
15  IDLE_FROM_SUCCESS = 10 + static_cast<int>(NodeStatus::SUCCESS),
16  IDLE_FROM_FAILURE = 10 + static_cast<int>(NodeStatus::FAILURE),
17  IDLE_FROM_RUNNING = 10 + static_cast<int>(NodeStatus::RUNNING)
18 };
19 
20 struct Transition
21 {
22  // when serializing, we will remove the initial time and serialize only
23  // 6 bytes, instead of 8
24  uint64_t timestamp_usec;
25  // if you have more than 64.000 nodes, you are doing something wrong :)
26  uint16_t node_uid;
27  // enough bits to contain NodeStatus
28  uint8_t status;
29 
30  uint8_t padding[5];
31 };
32 
33 std::array<char, 16> CreateRandomUUID()
34 {
35  std::mt19937 gen;
36  std::uniform_int_distribution<uint32_t> dist;
37  std::array<char, 16> out;
38  char* bytes = out.data();
39  for(int i = 0; i < 16; i += 4)
40  {
41  *reinterpret_cast<uint32_t*>(bytes + i) = dist(gen);
42  }
43  // variant must be 10xxxxxx
44  bytes[8] &= 0xBF;
45  bytes[8] |= 0x80;
46 
47  // version must be 0100xxxx
48  bytes[6] &= 0x4F;
49  bytes[6] |= 0x40;
50 
51  return out;
52 }
53 
55 {
56  PImpl() : context(), server(context, ZMQ_REP), publisher(context, ZMQ_PUB)
57  {
58  server.set(zmq::sockopt::linger, 0);
59  publisher.set(zmq::sockopt::linger, 0);
60 
61  int timeout_rcv = 100;
62  server.set(zmq::sockopt::rcvtimeo, timeout_rcv);
63  publisher.set(zmq::sockopt::rcvtimeo, timeout_rcv);
64 
65  int timeout_ms = 1000;
66  server.set(zmq::sockopt::sndtimeo, timeout_ms);
67  publisher.set(zmq::sockopt::sndtimeo, timeout_ms);
68  }
69 
70  unsigned server_port = 0;
71  std::string server_address;
72  std::string publisher_address;
73 
74  std::string tree_xml;
75 
76  std::atomic_bool active_server = false;
77  std::thread server_thread;
78 
80 
81  std::string status_buffer;
82  // each element of this map points to a character in _p->status_buffer
83  std::unordered_map<uint16_t, char*> status_buffermap;
84 
85  // weak reference to the tree.
86  std::unordered_map<std::string, std::weak_ptr<BT::Tree::Subtree>> subtrees;
87  std::unordered_map<uint16_t, std::weak_ptr<BT::TreeNode>> nodes_by_uid;
88 
90  std::unordered_map<uint16_t, Monitor::Hook::Ptr> pre_hooks;
91  std::unordered_map<uint16_t, Monitor::Hook::Ptr> post_hooks;
92 
93  std::chrono::system_clock::time_point last_heartbeat;
94  std::chrono::milliseconds max_heartbeat_delay = std::chrono::milliseconds(5000);
95 
96  std::atomic_bool recording = false;
97  std::deque<Transition> transitions_buffer;
98  std::chrono::microseconds recording_fist_time;
99 
100  std::thread heartbeat_thread;
101 
105 };
106 
107 Groot2Publisher::Groot2Publisher(const BT::Tree& tree, unsigned server_port)
108  : StatusChangeLogger(tree.rootNode()), _p(new PImpl())
109 {
110  _p->server_port = server_port;
111 
112  {
113  std::unique_lock<std::mutex> lk(Groot2Publisher::used_ports_mutex);
114  if(Groot2Publisher::used_ports.count(server_port) != 0 ||
115  Groot2Publisher::used_ports.count(server_port + 1) != 0)
116  {
117  auto msg = StrCat("Another instance of Groot2Publisher is using port ",
118  std::to_string(server_port));
119  throw LogicError(msg);
120  }
121  Groot2Publisher::used_ports.insert(server_port);
122  Groot2Publisher::used_ports.insert(server_port + 1);
123  }
124 
125  _p->tree_xml = WriteTreeToXML(tree, true, true);
126 
127  //-------------------------------
128  // Prepare the status buffer
129  size_t node_count = 0;
130  for(const auto& subtree : tree.subtrees)
131  {
132  node_count += subtree->nodes.size();
133  }
134  _p->status_buffer.resize(3 * node_count);
135 
136  unsigned ptr_offset = 0;
137  char* buffer_ptr = _p->status_buffer.data();
138 
139  for(const auto& subtree : tree.subtrees)
140  {
141  auto name =
142  subtree->instance_name.empty() ? subtree->tree_ID : subtree->instance_name;
143  _p->subtrees.insert({ name, subtree });
144 
145  for(const auto& node : subtree->nodes)
146  {
147  _p->nodes_by_uid.insert({ node->UID(), node });
148 
149  ptr_offset += Monitor::Serialize(buffer_ptr, ptr_offset, node->UID());
150  _p->status_buffermap.insert({ node->UID(), buffer_ptr + ptr_offset });
151  ptr_offset += Monitor::Serialize(buffer_ptr, ptr_offset, uint8_t(NodeStatus::IDLE));
152  }
153  }
154  //-------------------------------
155  _p->server_address = StrCat("tcp://*:", std::to_string(server_port));
156  _p->publisher_address = StrCat("tcp://*:", std::to_string(server_port + 1));
157 
158  _p->server.bind(_p->server_address.c_str());
159  _p->publisher.bind(_p->publisher_address.c_str());
160 
161  _p->server_thread = std::thread(&Groot2Publisher::serverLoop, this);
162  _p->heartbeat_thread = std::thread(&Groot2Publisher::heartbeatLoop, this);
163 }
164 
165 void Groot2Publisher::setMaxHeartbeatDelay(std::chrono::milliseconds delay)
166 {
167  _p->max_heartbeat_delay = delay;
168 }
169 
170 std::chrono::milliseconds Groot2Publisher::maxHeartbeatDelay() const
171 {
172  return _p->max_heartbeat_delay;
173 }
174 
176 {
177  removeAllHooks();
178 
179  _p->active_server = false;
180  if(_p->server_thread.joinable())
181  {
182  _p->server_thread.join();
183  }
184 
185  if(_p->heartbeat_thread.joinable())
186  {
187  _p->heartbeat_thread.join();
188  }
189 
190  flush();
191 
192  {
193  std::unique_lock<std::mutex> lk(Groot2Publisher::used_ports_mutex);
194  Groot2Publisher::used_ports.erase(_p->server_port);
195  Groot2Publisher::used_ports.erase(_p->server_port + 1);
196  }
197 }
198 
199 void Groot2Publisher::callback(Duration ts, const TreeNode& node, NodeStatus prev_status,
200  NodeStatus new_status)
201 {
202  std::unique_lock<std::mutex> lk(_p->status_mutex);
203  auto status = static_cast<char>(new_status);
204 
205  if(new_status == NodeStatus::IDLE)
206  {
207  status = 10 + static_cast<char>(prev_status);
208  }
209  *(_p->status_buffermap.at(node.UID())) = status;
210 
211  if(_p->recording)
212  {
213  Transition trans;
214  trans.node_uid = node.UID();
215  trans.status = static_cast<uint8_t>(new_status);
216  auto timestamp = ts - _p->recording_fist_time;
217  trans.timestamp_usec =
218  std::chrono::duration_cast<std::chrono::microseconds>(timestamp).count();
219  _p->transitions_buffer.push_back(trans);
220  while(_p->transitions_buffer.size() > 1000)
221  {
222  _p->transitions_buffer.pop_front();
223  }
224  }
225 }
226 
228 {
229  // nothing to do here...
230 }
231 
233 {
234  auto const serialized_uuid = CreateRandomUUID();
235 
236  _p->active_server = true;
237  auto& socket = _p->server;
238 
239  auto sendErrorReply = [&socket](const std::string& msg) {
240  zmq::multipart_t error_msg;
241  error_msg.addstr("error");
242  error_msg.addstr(msg);
243  error_msg.send(socket);
244  };
245 
246  // initialize _p->last_heartbeat
247  _p->last_heartbeat = std::chrono::system_clock::now();
248 
249  while(_p->active_server)
250  {
251  zmq::multipart_t requestMsg;
252  if(!requestMsg.recv(socket) || requestMsg.size() == 0)
253  {
254  continue;
255  }
256  // this heartbeat will help establishing if Groot is connected or not
257  _p->last_heartbeat = std::chrono::system_clock::now();
258 
259  std::string const request_str = requestMsg[0].to_string();
260  if(request_str.size() != Monitor::RequestHeader::size())
261  {
262  sendErrorReply("wrong request header");
263  continue;
264  }
265 
266  auto request_header = Monitor::DeserializeRequestHeader(request_str);
267 
268  Monitor::ReplyHeader reply_header;
269  reply_header.request = request_header;
270  reply_header.request.protocol = Monitor::kProtocolID;
271  reply_header.tree_id = serialized_uuid;
272 
273  zmq::multipart_t reply_msg;
274  reply_msg.addstr(Monitor::SerializeHeader(reply_header));
275 
276  switch(request_header.type)
277  {
279  reply_msg.addstr(_p->tree_xml);
280  }
281  break;
282 
284  std::unique_lock<std::mutex> lk(_p->status_mutex);
285  reply_msg.addstr(_p->status_buffer);
286  }
287  break;
288 
290  if(requestMsg.size() != 2)
291  {
292  sendErrorReply("must be 2 parts message");
293  continue;
294  }
295  std::string const bb_names_str = requestMsg[1].to_string();
296  auto msg = generateBlackboardsDump(bb_names_str);
297  reply_msg.addmem(msg.data(), msg.size());
298  }
299  break;
300 
302  if(requestMsg.size() != 2)
303  {
304  sendErrorReply("must be 2 parts message");
305  continue;
306  }
307 
308  auto InsertHook = [this](nlohmann::json const& json) {
309  uint16_t const node_uid = json["uid"].get<uint16_t>();
310  Position const pos = static_cast<Position>(json["position"].get<int>());
311 
312  if(auto hook = getHook(pos, node_uid))
313  {
314  std::unique_lock<std::mutex> lk(hook->mutex);
315  bool was_interactive = (hook->mode == Monitor::Hook::Mode::BREAKPOINT);
317 
318  // if it WAS interactive and it is not anymore, unlock it
319  if(was_interactive && (hook->mode == Monitor::Hook::Mode::REPLACE))
320  {
321  hook->ready = true;
322  lk.unlock();
323  hook->wakeup.notify_all();
324  }
325  }
326  else // if not found, create a new one
327  {
328  auto new_hook = std::make_shared<Monitor::Hook>();
329  BT::Monitor::from_json(json, *new_hook);
330  insertHook(new_hook);
331  }
332  };
333 
334  auto const received_json = nlohmann::json::parse(requestMsg[1].to_string());
335 
336  // the json may contain a Hook or an array of Hooks
337  if(received_json.is_array())
338  {
339  for(auto const& json : received_json)
340  {
341  InsertHook(json);
342  }
343  }
344  else
345  {
346  InsertHook(received_json);
347  }
348  }
349  break;
350 
352  if(requestMsg.size() != 2)
353  {
354  sendErrorReply("must be 2 parts message");
355  continue;
356  }
357 
358  auto json = nlohmann::json::parse(requestMsg[1].to_string());
359  uint16_t node_uid = json.at("uid").get<uint16_t>();
360  std::string status_str = json.at("desired_status").get<std::string>();
361  auto position = static_cast<Position>(json.at("position").get<int>());
362  bool remove = json.at("remove_when_done").get<bool>();
363 
364  NodeStatus desired_status = NodeStatus::SKIPPED;
365  if(status_str == "SUCCESS")
366  {
367  desired_status = NodeStatus::SUCCESS;
368  }
369  else if(status_str == "FAILURE")
370  {
371  desired_status = NodeStatus::FAILURE;
372  }
373 
374  if(!unlockBreakpoint(position, uint16_t(node_uid), desired_status, remove))
375  {
376  sendErrorReply("Node ID not found");
377  continue;
378  }
379  }
380  break;
381 
383  removeAllHooks();
384  }
385  break;
386 
388  enableAllHooks(false);
389  }
390  break;
391 
393  if(requestMsg.size() != 2)
394  {
395  sendErrorReply("must be 2 parts message");
396  continue;
397  }
398 
399  auto json = nlohmann::json::parse(requestMsg[1].to_string());
400  uint16_t node_uid = json.at("uid").get<uint16_t>();
401  auto position = static_cast<Position>(json.at("position").get<int>());
402 
403  if(!removeHook(position, uint16_t(node_uid)))
404  {
405  sendErrorReply("Node ID not found");
406  continue;
407  }
408  }
409  break;
410 
412  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
413  auto json_out = nlohmann::json::array();
414  for(auto [node_uid, breakpoint] : _p->pre_hooks)
415  {
416  json_out.push_back(*breakpoint);
417  }
418  reply_msg.addstr(json_out.dump());
419  }
420  break;
421 
423  if(requestMsg.size() != 2)
424  {
425  sendErrorReply("must be 2 parts message");
426  continue;
427  }
428 
429  auto const cmd = (requestMsg[1].to_string());
430  if(cmd == "start")
431  {
432  _p->recording = true;
433  // to keep the first time for callback
434  _p->recording_fist_time = std::chrono::duration_cast<std::chrono::microseconds>(
435  std::chrono::high_resolution_clock::now().time_since_epoch());
436  // to send consistent time for client
437  auto now = std::chrono::duration_cast<std::chrono::microseconds>(
438  std::chrono::system_clock::now().time_since_epoch());
439  reply_msg.addstr(std::to_string(now.count()));
440  std::unique_lock<std::mutex> lk(_p->status_mutex);
441  _p->transitions_buffer.clear();
442  }
443  else if(cmd == "stop")
444  {
445  _p->recording = false;
446  }
447  }
448  break;
449 
451  thread_local std::string trans_buffer;
452  trans_buffer.resize(9 * _p->transitions_buffer.size());
453 
454  std::unique_lock<std::mutex> lk(_p->status_mutex);
455  size_t offset = 0;
456  for(const auto& trans : _p->transitions_buffer)
457  {
458  std::memcpy(&trans_buffer[offset], &trans.timestamp_usec, 6);
459  offset += 6;
460  std::memcpy(&trans_buffer[offset], &trans.node_uid, 2);
461  offset += 2;
462  std::memcpy(&trans_buffer[offset], &trans.status, 1);
463  offset += 1;
464  }
465  _p->transitions_buffer.clear();
466  trans_buffer.resize(offset);
467  reply_msg.addstr(trans_buffer);
468  }
469  break;
470 
471  default: {
472  sendErrorReply("Request not recognized");
473  continue;
474  }
475  }
476  // send the reply
477  reply_msg.send(socket);
478  }
479 }
480 
482 {
483  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
484  for(auto& [node_uid, hook] : _p->pre_hooks)
485  {
486  std::unique_lock<std::mutex> lk(hook->mutex);
487  hook->enabled = enable;
488  // when disabling, remember to wake up blocked ones
489  if(!hook->enabled && hook->mode == Monitor::Hook::Mode::BREAKPOINT)
490  {
491  lk.unlock();
492  hook->wakeup.notify_all();
493  }
494  }
495 }
496 
498 {
499  bool has_heartbeat = true;
500 
501  while(_p->active_server)
502  {
503  std::this_thread::sleep_for(std::chrono::milliseconds(10));
504 
505  auto now = std::chrono::system_clock::now();
506  bool prev_heartbeat = has_heartbeat;
507 
508  has_heartbeat = (now - _p->last_heartbeat < _p->max_heartbeat_delay);
509 
510  // if we loose or gain heartbeat, disable/enable all breakpoints
511  if(has_heartbeat != prev_heartbeat)
512  {
513  enableAllHooks(has_heartbeat);
514  }
515  }
516 }
517 
518 std::vector<uint8_t> Groot2Publisher::generateBlackboardsDump(const std::string& bb_list)
519 {
520  auto json = nlohmann::json();
521  auto const bb_names = BT::splitString(bb_list, ';');
522  for(auto name : bb_names)
523  {
524  std::string const bb_name(name);
525  auto it = _p->subtrees.find(bb_name);
526 
527  if(it != _p->subtrees.end())
528  {
529  // lock the weak pointer
530  if(auto subtree = it->second.lock())
531  {
532  json[bb_name] = ExportBlackboardToJSON(*subtree->blackboard);
533  }
534  }
535  }
536  return nlohmann::json::to_msgpack(json);
537 }
538 
539 bool Groot2Publisher::insertHook(std::shared_ptr<Monitor::Hook> hook)
540 {
541  auto const node_uid = hook->node_uid;
542  auto it = _p->nodes_by_uid.find(node_uid);
543  if(it == _p->nodes_by_uid.end())
544  {
545  return false;
546  }
547  TreeNode::Ptr node = it->second.lock();
548  if(!node)
549  {
550  return false;
551  }
552 
553  auto injectedCallback = [hook, this](TreeNode& node) -> NodeStatus {
554  std::unique_lock<std::mutex> lk(hook->mutex);
555  if(!hook->enabled)
556  {
557  return NodeStatus::SKIPPED;
558  }
559 
560  // Notify that a breakpoint was reached, using the _p->publisher
562  zmq::multipart_t request_msg;
563  request_msg.addstr(Monitor::SerializeHeader(breakpoint_request));
564  request_msg.addstr(std::to_string(hook->node_uid));
565  request_msg.send(_p->publisher);
566 
567  // wait until someone wake us up
568  if(hook->mode == Monitor::Hook::Mode::BREAKPOINT)
569  {
570  hook->wakeup.wait(lk, [hook]() { return hook->ready || !hook->enabled; });
571 
572  hook->ready = false;
573  // wait was unblocked but it could be the breakpoint becoming disabled.
574  // in this case, just skip
575  if(!hook->enabled)
576  {
577  return NodeStatus::SKIPPED;
578  }
579  }
580 
581  if(hook->remove_when_done)
582  {
583  // self-destruction at the end of this lambda function
584  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
585  _p->pre_hooks.erase(hook->node_uid);
586  node.setPreTickFunction({});
587  }
588  return hook->desired_status;
589  };
590 
591  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
592  _p->pre_hooks[node_uid] = hook;
593  node->setPreTickFunction(injectedCallback);
594 
595  return true;
596 }
597 
598 bool Groot2Publisher::unlockBreakpoint(Position pos, uint16_t node_uid, NodeStatus result,
599  bool remove)
600 {
601  auto it = _p->nodes_by_uid.find(node_uid);
602  if(it == _p->nodes_by_uid.end())
603  {
604  return false;
605  }
606  TreeNode::Ptr node = it->second.lock();
607  if(!node)
608  {
609  return false;
610  }
611 
612  auto hook = getHook(pos, node_uid);
613  if(!hook)
614  {
615  return false;
616  }
617 
618  {
619  std::unique_lock<std::mutex> lk(hook->mutex);
620  hook->desired_status = result;
621  hook->remove_when_done |= remove;
622  if(hook->mode == Monitor::Hook::Mode::BREAKPOINT)
623  {
624  hook->ready = true;
625  lk.unlock();
626  hook->wakeup.notify_all();
627  }
628  }
629  return true;
630 }
631 
632 bool Groot2Publisher::removeHook(Position pos, uint16_t node_uid)
633 {
634  auto it = _p->nodes_by_uid.find(node_uid);
635  if(it == _p->nodes_by_uid.end())
636  {
637  return false;
638  }
639  TreeNode::Ptr node = it->second.lock();
640  if(!node)
641  {
642  return false;
643  }
644 
645  auto hook = getHook(pos, node_uid);
646  if(!hook)
647  {
648  return false;
649  }
650 
651  {
652  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
653  _p->pre_hooks.erase(node_uid);
654  }
655  node->setPreTickFunction({});
656 
657  // Disable breakpoint, if it was interactive and blocked
658  {
659  std::unique_lock<std::mutex> lk(hook->mutex);
660  if(hook->mode == Monitor::Hook::Mode::BREAKPOINT)
661  {
662  hook->enabled = false;
663  lk.unlock();
664  hook->wakeup.notify_all();
665  }
666  }
667  return true;
668 }
669 
671 {
672  std::vector<uint16_t> uids;
673 
674  for(auto pos : { Position::PRE, Position::POST })
675  {
676  uids.clear();
677  auto hooks = pos == Position::PRE ? &_p->pre_hooks : &_p->post_hooks;
678  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
679  if(!hooks->empty())
680  {
681  uids.reserve(hooks->size());
682  for(auto [node_uid, _] : *hooks)
683  {
684  uids.push_back(node_uid);
685  }
686 
687  lk.unlock();
688  for(auto node_uid : uids)
689  {
690  removeHook(pos, node_uid);
691  }
692  }
693  }
694 }
695 
697 {
698  auto hooks = pos == Position::PRE ? &_p->pre_hooks : &_p->post_hooks;
699  std::unique_lock<std::mutex> lk(_p->hooks_map_mutex);
700  auto bk_it = hooks->find(node_uid);
701  if(bk_it == hooks->end())
702  {
703  return {};
704  }
705  return bk_it->second;
706 }
707 
708 } // namespace BT
BT::Monitor::Hook::Mode::BREAKPOINT
@ BREAKPOINT
BT::Transition
Definition: groot2_publisher.cpp:20
BT
Definition: ex01_wrap_legacy.cpp:29
lexyd::position
constexpr auto position
Produces an iterator to the current reader position without parsing anything.
Definition: position.hpp:79
BT::Monitor::Hook::Position::POST
@ POST
BT::Monitor::Serialize
unsigned Serialize(char *buffer, unsigned offset, T value)
Definition: groot2_protocol.h:149
BT::IDLE_FROM_SUCCESS
@ IDLE_FROM_SUCCESS
Definition: groot2_publisher.cpp:15
BT::Groot2Publisher::_p
std::unique_ptr< PImpl > _p
Definition: groot2_publisher.h:72
BT::Monitor::ReplyHeader::tree_id
TreeUniqueUUID tree_id
Definition: groot2_protocol.h:135
BT::Monitor::Hook::Ptr
std::shared_ptr< Hook > Ptr
Definition: groot2_protocol.h:207
lexyd::bytes
constexpr auto bytes
Matches N arbitrary bytes.
Definition: byte.hpp:55
BT::TreeNode::UID
uint16_t UID() const
Definition: tree_node.cpp:330
BT::Groot2Publisher::insertHook
bool insertHook(Monitor::Hook::Ptr breakpoint)
Definition: groot2_publisher.cpp:539
BT::Transition::padding
uint8_t padding[5]
Definition: groot2_publisher.cpp:30
BT::Groot2Publisher::callback
void callback(Duration timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) override
Definition: groot2_publisher.cpp:199
BT::Groot2Publisher::PImpl::context
zmq::context_t context
Definition: groot2_publisher.cpp:102
BT::Groot2Publisher::removeHook
bool removeHook(Position pos, uint16_t node_uid)
Definition: groot2_publisher.cpp:632
BT::Transition::timestamp_usec
uint64_t timestamp_usec
Definition: groot2_publisher.cpp:24
BT::Monitor::DISABLE_ALL_HOOKS
@ DISABLE_ALL_HOOKS
Definition: groot2_protocol.h:51
BT::Monitor::BREAKPOINT_REACHED
@ BREAKPOINT_REACHED
Definition: groot2_protocol.h:42
BT::Monitor::BLACKBOARD
@ BLACKBOARD
Definition: groot2_protocol.h:35
BT::Groot2Publisher::getHook
Monitor::Hook::Ptr getHook(Position pos, uint16_t node_uid)
Definition: groot2_publisher.cpp:696
BT::Groot2Publisher::Groot2Publisher
Groot2Publisher(const BT::Tree &tree, unsigned server_port=1667)
Definition: groot2_publisher.cpp:107
BT::Groot2Publisher::PImpl::status_buffermap
std::unordered_map< uint16_t, char * > status_buffermap
Definition: groot2_publisher.cpp:83
BT::Monitor::HOOK_REMOVE
@ HOOK_REMOVE
Definition: groot2_protocol.h:40
zmq::socket_t
Definition: 3rdparty/cppzmq/zmq.hpp:2155
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:118
BT::Groot2Publisher::PImpl::server_address
std::string server_address
Definition: groot2_publisher.cpp:71
BT::Tree
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:91
BT::Monitor::RequestHeader
Definition: groot2_protocol.h:100
BT::CreateRandomUUID
std::array< char, 16 > CreateRandomUUID()
Definition: groot2_publisher.cpp:33
BT::TreeNode::Ptr
std::shared_ptr< TreeNode > Ptr
Definition: tree_node.h:121
BT::Groot2Publisher::PImpl::recording_fist_time
std::chrono::microseconds recording_fist_time
Definition: groot2_publisher.cpp:98
BT::Groot2Publisher::PImpl::transitions_buffer
std::deque< Transition > transitions_buffer
Definition: groot2_publisher.cpp:97
basic_json
namespace for Niels Lohmann
Definition: json.hpp:3411
BT::Groot2Publisher::serverLoop
void serverLoop()
Definition: groot2_publisher.cpp:232
BT::LogicError
Definition: exceptions.h:45
BT::StatusChangeLogger
Definition: abstract_logger.h:15
BT::Groot2Publisher::PImpl::subtrees
std::unordered_map< std::string, std::weak_ptr< BT::Tree::Subtree > > subtrees
Definition: groot2_publisher.cpp:86
BT::Duration
std::chrono::high_resolution_clock::duration Duration
Definition: basic_types.h:628
BT::Groot2Publisher::PImpl::last_heartbeat
std::chrono::system_clock::time_point last_heartbeat
Definition: groot2_publisher.cpp:93
BT::ExportBlackboardToJSON
nlohmann::json ExportBlackboardToJSON(const Blackboard &blackboard)
ExportBlackboardToJSON will create a JSON that contains the current values of the blackboard....
Definition: blackboard.cpp:263
BT::Monitor::Hook::Mode::REPLACE
@ REPLACE
BT::WriteTreeToXML
std::string WriteTreeToXML(const Tree &tree, bool add_metadata, bool add_builtin_models)
WriteTreeToXML create a string that contains the XML that corresponds to a given tree....
Definition: xml_parsing.cpp:1497
mutex
static pthread_mutex_t mutex
Definition: minitrace.cpp:77
BT::Monitor::Hook::Position
Position
Definition: groot2_protocol.h:212
BT::Monitor::FULLTREE
@ FULLTREE
Definition: groot2_protocol.h:31
zmq::context_t
Definition: 3rdparty/cppzmq/zmq.hpp:793
BT::Groot2Publisher::PImpl::nodes_by_uid
std::unordered_map< uint16_t, std::weak_ptr< BT::TreeNode > > nodes_by_uid
Definition: groot2_publisher.cpp:87
BT::Monitor::SerializeHeader
std::string SerializeHeader(const RequestHeader &header)
Definition: groot2_protocol.h:162
lexy::count
constexpr auto count
Sink that counts all arguments.
Definition: fold.hpp:88
BT::Monitor::ReplyHeader
Definition: groot2_protocol.h:132
BT::NodeStatus::FAILURE
@ FAILURE
BT::Transition::status
uint8_t status
Definition: groot2_publisher.cpp:28
BT::Groot2Publisher::PImpl::tree_xml
std::string tree_xml
Definition: groot2_publisher.cpp:74
lexy::parse
constexpr auto parse(const Input &input, const ErrorCallback &callback)
Parses the production into a value, invoking the callback on error.
Definition: parse.hpp:171
BT::NodeStatus::SKIPPED
@ SKIPPED
lexyd::bit::_
constexpr auto _
Matches any bit.
Definition: bits.hpp:91
BT::Monitor::kProtocolID
constexpr uint8_t kProtocolID
Definition: groot2_protocol.h:97
BT::Groot2Publisher::PImpl::pre_hooks
std::unordered_map< uint16_t, Monitor::Hook::Ptr > pre_hooks
Definition: groot2_publisher.cpp:90
BT::IDLE_FROM_FAILURE
@ IDLE_FROM_FAILURE
Definition: groot2_publisher.cpp:16
BT::Groot2Publisher::unlockBreakpoint
bool unlockBreakpoint(Position pos, uint16_t node_uid, NodeStatus result, bool remove)
Definition: groot2_publisher.cpp:598
BT::Groot2Publisher::PImpl::server
zmq::socket_t server
Definition: groot2_publisher.cpp:103
groot2_publisher.h
BT::Groot2Publisher::flush
void flush() override
Definition: groot2_publisher.cpp:227
BT::Groot2Publisher::PImpl::publisher_address
std::string publisher_address
Definition: groot2_publisher.cpp:72
BT::Groot2Publisher::used_ports_mutex
static std::mutex used_ports_mutex
Definition: groot2_publisher.h:21
BT::Groot2Publisher::PImpl::status_buffer
std::string status_buffer
Definition: groot2_publisher.cpp:81
BT::Groot2Publisher::generateBlackboardsDump
std::vector< uint8_t > generateBlackboardsDump(const std::string &bb_list)
Definition: groot2_publisher.cpp:518
BT::splitString
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
Definition: basic_types.cpp:348
BT::Monitor::TOGGLE_RECORDING
@ TOGGLE_RECORDING
Definition: groot2_protocol.h:54
to_string
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:24456
groot2_protocol.h
xml_parsing.h
BT::Groot2Publisher::PImpl::active_server
std::atomic_bool active_server
Definition: groot2_publisher.cpp:76
BT::Groot2Publisher::PImpl
Definition: groot2_publisher.cpp:54
BT::Monitor::HOOK_INSERT
@ HOOK_INSERT
Definition: groot2_protocol.h:38
BT::Groot2Publisher::PImpl::PImpl
PImpl()
Definition: groot2_publisher.cpp:56
BT::Monitor::HOOKS_DUMP
@ HOOKS_DUMP
Definition: groot2_protocol.h:46
BT::StrCat
std::string StrCat()
Definition: strcat.hpp:46
BT::Groot2Publisher::heartbeatLoop
void heartbeatLoop()
Definition: groot2_publisher.cpp:497
BT::NodeStatus::SUCCESS
@ SUCCESS
BT::Groot2Publisher::maxHeartbeatDelay
std::chrono::milliseconds maxHeartbeatDelay() const
Definition: groot2_publisher.cpp:170
BT::Groot2Publisher::PImpl::server_thread
std::thread server_thread
Definition: groot2_publisher.cpp:77
BT::Monitor::STATUS
@ STATUS
Definition: groot2_protocol.h:33
BT::Monitor::RequestHeader::protocol
uint8_t protocol
Definition: groot2_protocol.h:103
BT::Monitor::GET_TRANSITIONS
@ GET_TRANSITIONS
Definition: groot2_protocol.h:56
BT::Tree::subtrees
std::vector< Subtree::Ptr > subtrees
Definition: bt_factory.h:104
BT::NodeStatus::RUNNING
@ RUNNING
BT::Groot2Publisher::PImpl::max_heartbeat_delay
std::chrono::milliseconds max_heartbeat_delay
Definition: groot2_publisher.cpp:94
BT::Groot2Publisher::PImpl::recording
std::atomic_bool recording
Definition: groot2_publisher.cpp:96
BT::Monitor::from_json
void from_json(const nlohmann::json &js, Hook &bp)
Definition: groot2_protocol.h:256
BT::Monitor::Hook::Position::PRE
@ PRE
zmq.hpp
BT::Monitor::REMOVE_ALL_HOOKS
@ REMOVE_ALL_HOOKS
Definition: groot2_protocol.h:49
json
basic_json<> json
default specialization
Definition: json.hpp:3422
basic_json::get
auto get() const noexcept(noexcept(std::declval< const basic_json_t & >().template get_impl< ValueType >(detail::priority_tag< 4 > {}))) -> decltype(std::declval< const basic_json_t & >().template get_impl< ValueType >(detail::priority_tag< 4 >
get a (pointer) value (explicit)
Definition: json.hpp:21046
BT::NodeStatus::IDLE
@ IDLE
BT::Groot2Publisher::PImpl::post_hooks
std::unordered_map< uint16_t, Monitor::Hook::Ptr > post_hooks
Definition: groot2_publisher.cpp:91
BT::Monitor::BREAKPOINT_UNLOCK
@ BREAKPOINT_UNLOCK
Definition: groot2_protocol.h:44
BT::Groot2Publisher::PImpl::server_port
unsigned server_port
Definition: groot2_publisher.cpp:70
BT::Groot2Publisher::enableAllHooks
void enableAllHooks(bool enable)
Definition: groot2_publisher.cpp:481
BT::IDLE_FROM_RUNNING
@ IDLE_FROM_RUNNING
Definition: groot2_publisher.cpp:17
BT::Groot2Publisher::setMaxHeartbeatDelay
void setMaxHeartbeatDelay(std::chrono::milliseconds delay)
setMaxHeartbeatDelay is used to tell the publisher when a connection with Groot2 should be cancelled,...
Definition: groot2_publisher.cpp:165
BT::Transition::node_uid
uint16_t node_uid
Definition: groot2_publisher.cpp:26
BT::Monitor::ReplyHeader::request
RequestHeader request
Definition: groot2_protocol.h:134
time_since_epoch
double time_since_epoch()
BT::Groot2Publisher::PImpl::status_mutex
std::mutex status_mutex
Definition: groot2_publisher.cpp:79
BT::Groot2Publisher::PImpl::hooks_map_mutex
std::mutex hooks_map_mutex
Definition: groot2_publisher.cpp:89
BT::Groot2Publisher::PImpl::publisher
zmq::socket_t publisher
Definition: groot2_publisher.cpp:104
BT::Monitor::RequestHeader::size
static size_t size()
Definition: groot2_protocol.h:106
BT::Groot2Publisher::~Groot2Publisher
~Groot2Publisher() override
Definition: groot2_publisher.cpp:175
BT::Groot2Publisher::removeAllHooks
void removeAllHooks()
Definition: groot2_publisher.cpp:670
BT::Monitor::DeserializeRequestHeader
RequestHeader DeserializeRequestHeader(const std::string &buffer)
Definition: groot2_protocol.h:184
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
BT::Groot2Publisher::PImpl::heartbeat_thread
std::thread heartbeat_thread
Definition: groot2_publisher.cpp:100
basic_json::at
reference at(size_type idx)
access specified array element with bounds checking
Definition: json.hpp:21240
BT::Groot2Publisher::used_ports
static std::set< unsigned > used_ports
Definition: groot2_publisher.h:22
zmq_addon.hpp


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07