ZyreEndpoint.cpp
Go to the documentation of this file.
3 #include <swarmio/Exception.h>
4 #include <atomic>
5 #include <cstdio>
6 #include <iostream>
7 #include <fstream>
8 #include <string>
9 #include <libconfig.h++>
10 
11 using namespace swarmio;
12 using namespace swarmio::transport;
13 using namespace swarmio::transport::zyre;
14 
15 #define SWARMIO_ZYRE_GROUP_MESSAGES "messages"
16 #define SWARMIO_ZYRE_HEADER_DEVICE_CLASS "X-DeviceClass"
17 #define SODIUM_STATIC
18 
19 ZyreEndpoint::ZyreEndpoint(const char *name, const char *deviceClass)
20 {
21  // Create Zyre node
22  _zyre = zyre_new(name);
23  if (_zyre == NULL)
24  {
25  throw Exception("Unable to create node");
26  }
27 
28  // Set class
29  if (deviceClass != nullptr)
30  {
31  zyre_set_header(_zyre, SWARMIO_ZYRE_HEADER_DEVICE_CLASS, "%s", deviceClass);
32  }
33 
34  // Get UUID
35  _uuid = zyre_uuid(_zyre);
36 }
37 
43 static std::map<std::string, std::string> GetInterfaceMap()
44 {
45  std::map<std::string, std::string> map;
46 
47  // Get list of interfaces
48  ziflist_t *ifaces = ziflist_new();
49  if (ifaces != nullptr)
50  {
51  // Store interface names and current addresses
52  for (const char *current = ziflist_first(ifaces); current != nullptr; current = ziflist_next(ifaces))
53  {
54  map[current] = ziflist_address(ifaces);
55  }
56 
57  // Free list of interfaces
58  ziflist_destroy(&ifaces);
59  }
60 
61  return map;
62 }
63 
64 void ZyreEndpoint::SetPort(uint16_t port)
65 {
66  // Check if we are already running
67  if (_worker != nullptr)
68  {
69  throw Exception("Node is already running");
70  }
71 
72  // Set port
73  zyre_set_port(_zyre, port);
74 }
75 
76 void ZyreEndpoint::SetInterface(const char *ifname)
77 {
78  // Check if we are already running
79  if (_worker != nullptr)
80  {
81  throw Exception("Node is already running");
82  }
83 
84  // Set interface
85  zyre_set_interface(_zyre, ifname);
86 }
87 
88 void ZyreEndpoint::SetConfig(std::string cfg)
89 {
90  this->configFilePath = cfg;
91 }
92 
94 {
95  // Check if we are already running
96  if (_worker != nullptr)
97  {
98  throw Exception("Node is already running");
99  }
100  #ifdef SWARMROS_CONFIG_PATH
101  std::string configFilePath = SWARMROS_CONFIG_PATH;
102  #endif
103 
104  // Load configuration and establish endpoint
105  libconfig::Config config;
106  std::unique_ptr<swarmio::Endpoint> endpoint;
107  try
108  {
109  config.readFile(configFilePath.c_str());
110  std::string type = (const char *)config.lookup("endpoint.type");
111  if (type == "zyre")
112  {
113  // Create endpoint
114  auto zyreEndpoint = std::make_unique<swarmio::transport::zyre::ZyreEndpoint>(config.lookup("endpoint.name"), config.lookup("endpoint.deviceClass"));
115 
116  // Apply settings
117  if (config.exists("endpoint.parameters.port"))
118  {
119  unsigned port = config.lookup("endpoint.parameters.port");
120  if (port <= UINT16_MAX)
121  {
122  zyreEndpoint->SetPort((uint16_t)port);
123  }
124  else
125  {
126  LOG(FATAL) << "Port is out of range.";
127  }
128  }
129  if (config.exists("endpoint.parameters.ifname"))
130  {
131  // Get interface name
132  const char *name = config.lookup("endpoint.parameters.ifname");
133 
134  // Check that it exists
135  auto map = GetInterfaceMap();
136  if (map.find(name) != map.end())
137  {
138  zyreEndpoint->SetInterface(name);
139  }
140  else
141  {
142  LOG(DBUG) << "Available interfaces:";
143  for (auto &pair : map)
144  {
145  LOG(DBUG) << " - " << pair.first << " (" << pair.second << ")";
146  }
147  LOG(FATAL) << "An invalid interface name has been specified.";
148  }
149  }
150  if (config.exists("endpoint.parameters.security"))
151  {
152  security_enabled = config.lookup("endpoint.parameters.security");
153  {
154  if (config.exists("endpoint.parameters.privateKey"))
155  {
156  std::string decoded = base64_decode(config.lookup("endpoint.parameters.privateKey"));
157  memcpy(my_secretkey, reinterpret_cast<unsigned char *>(const_cast<char *>((decoded.c_str()))), crypto_box_SECRETKEYBYTES);
158  if (crypto_sign_ed25519_sk_to_curve25519(my_secretkey, my_secretkey) != 0)
159  {
160  LOG(WARNING) << "Unable to convert private key";
161  security_enabled = false;
162  }
163  }
164  if (config.exists("endpoint.parameters.publicKey"))
165  {
166  std::string decoded = base64_decode(config.lookup("endpoint.parameters.publicKey"));
167  memcpy(my_publickey, reinterpret_cast<unsigned char *>(const_cast<char *>(decoded.c_str())), crypto_box_PUBLICKEYBYTES);
168  }
169  else
170  {
171  security_enabled = false;
172  }
173  if (config.exists("endpoint.parameters.signature"))
174  {
175  std::string decoded = base64_decode(config.lookup("endpoint.parameters.signature"));
176  memcpy(signature, reinterpret_cast<unsigned char *>(const_cast<char *>(decoded.c_str())), crypto_sign_SECRETKEYBYTES);
177  }
178  else
179  {
180  security_enabled = false;
181  }
182  if (config.exists("endpoint.parameters.ca"))
183  {
184  std::string decoded = base64_decode(config.lookup("endpoint.parameters.ca"));
185  memcpy(server_public, reinterpret_cast<unsigned char *>(const_cast<char *>(decoded.c_str())), crypto_sign_PUBLICKEYBYTES);
186  }
187  else
188  {
189  security_enabled = false;
190  }
191  }
192  }
193  }
194  }
195  catch (const libconfig::SettingTypeException &e)
196  {
197  LOG(FATAL) << "Invalid type for setting at " << e.getPath() << ".";
198  }
199  catch (const libconfig::SettingNotFoundException &e)
200  {
201  LOG(FATAL) << "Missing setting at " << e.getPath() << ".";
202  }
203  catch (const libconfig::FileIOException &e)
204  {
205  LOG(DBUG) << e.what();
206  LOG(DBUG) << "An exception has occurred while trying to read the configuration file.";
207  }
208  catch (const libconfig::ParseException &e)
209  {
210  LOG(DBUG) << e.getError();
211  LOG(FATAL) << "An exception has occurred while trying to parse the configuration file (line " << e.getLine() << ").";
212  }
213  catch (const swarmio::Exception &e)
214  {
215  LOG(DBUG) << e.what();
216  LOG(FATAL) << "An exception has occurred while trying to initialize the endpoint.";
217  }
218 
219  // Start crypto
220  if (security_enabled)
221  {
222  LOG(WARNING) << "Configuring secure mode.";
223  if (sodium_init() < 0)
224  {
225  throw Exception("Unable to init sodium");
226  }
227  std::cout << 'Me: p: ' << my_publickey << std::endl
228  << ' s: ' << my_secretkey << std::endl;
229  // Create broadcast keys
230  crypto_box_seed_keypair(bcast_publickey, bcast_secretkey, server_public);
231  std::cout << 'Broadcast: p: ' << bcast_publickey << std::endl
232  << ' s: ' << bcast_secretkey << std::endl;
233  auto it = _nodes.emplace(
234  std::piecewise_construct,
235  std::forward_as_tuple("0"),
236  std::forward_as_tuple("0", "broadcast", "broadcast", "0"));
237  unsigned char k[crypto_box_BEFORENMBYTES];
238  if (crypto_box_beforenm(k, bcast_publickey, bcast_secretkey) != 0)
239  throw Exception("Cannot create broadcast keys");
240  else
241  {
242  _nodes.at("0").SetKeys(k, bcast_publickey);
243  unsigned char n[crypto_box_NONCEBYTES];
244  randombytes_buf(n, crypto_box_NONCEBYTES);
245  _nodes.at("0").SetCtr(n);
246  _nodes.at("0").SetVerified();
247  }
248  //Test the signed certificate
249  if (crypto_sign_verify_detached(signature, my_publickey, crypto_sign_PUBLICKEYBYTES, server_public) != 0)
250  {
251  throw Exception("Unable to verify own certificate");
252  }
253  else
254  {
255  memcpy(certificate, my_publickey, crypto_sign_PUBLICKEYBYTES);
256  memcpy(&certificate[crypto_sign_PUBLICKEYBYTES], signature, crypto_sign_SECRETKEYBYTES);
257  if (crypto_sign_ed25519_pk_to_curve25519(my_publickey, my_publickey) != 0)
258  {
259  throw Exception("Unable to convert public key");
260  }
261  }
262  }
263 
264  // Start instance
265  if (zyre_start(_zyre) != 0)
266  {
267  throw Exception("Unable to start node");
268  }
269 
270  // Start the thread
271  _worker = new std::thread(&ZyreEndpoint::Process, this);
272 
273  // Call base implementation
275 }
276 
278 {
279  // Call base implementation
281 
282  // Check if we are running
283  if (_worker == nullptr)
284  {
285  throw Exception("Node is not running");
286  }
287 
288  // Create client socket
289  ZyreControlSocket client(&_control);
290 
291  // Send request
292  zsock_send(client, "p", "SHUTDOWN");
293 
294  // Await response
295  if (zsock_wait(client) != 0)
296  {
297  throw Exception("Invalid response");
298  }
299 
300  // Join thread and remove reference
301  _worker->join();
302  delete _worker;
303  _worker = nullptr;
304 }
305 
306 void ZyreEndpoint::Send(const void *data, size_t size, const Node *node)
307 {
308  // Try to convert to a Zyre node
309  const ZyreNode *zyreNode = dynamic_cast<const ZyreNode *>(node);
310  if (node != nullptr && zyreNode == nullptr)
311  {
312  throw Exception("Invalid target node type");
313  }
314 
315  // Allocate message and append data
316  zmsg_t *message = zmsg_new();
317  if (security_enabled && !isJoining)
318  {
319  size_t c_len = crypto_box_MACBYTES + (size_t)size;
320  unsigned char *ciphertext = new unsigned char[c_len + crypto_box_NONCEBYTES];
321  if (node == nullptr)
322  { // Broadcast node should be selected
323  zyreNode = (ZyreNode *)NodeForUUID("0");
324  }
325  dynamic_cast<const ZyreNode *>(NodeForUUID(zyreNode->GetUUID()))->IncrementCtr();
326  if (crypto_box_easy_afternm(ciphertext, (const unsigned char *)data, (size_t)size, zyreNode->GetCtr(), zyreNode->GetKey()) != 0)
327  {
328  throw Exception("Could not encrypt message");
329  }
330  memcpy(&ciphertext[c_len], zyreNode->GetCtr(), crypto_box_NONCEBYTES);
331  zmsg_addmem(message, ciphertext, c_len + crypto_box_NONCEBYTES);
332  delete[] ciphertext;
333  if (node == nullptr)
334  {
335  zyreNode = nullptr;
336  }
337  }
338  else
339  {
340  zmsg_addmem(message, data, (size_t)size);
341  }
342 
343  // Create client socket
344  ZyreControlSocket client(&_control);
345 
346  // Send request
347  if (zsock_send(client, "ppp", "SEND", zyreNode, message) != 0)
348  {
349  throw Exception("Cannot send control message");
350  }
351  if (zsock_wait(client) != 0)
352  {
353  throw Exception("Cannot send message");
354  }
355 }
356 
358 {
359  // Stop thread
360  if (_worker != nullptr)
361  {
362  Stop();
363  }
364 
365  // Destroy Zyre node
366  if (_zyre != NULL)
367  {
368  zyre_destroy(&_zyre);
369  }
370 }
371 
373 {
374  // Set up queue and delivery thread
375  moodycamel::BlockingReaderWriterQueue<zyre_event_t *> deliveryQueue;
376  std::thread deliveryThread(&ZyreEndpoint::Deliver, this, &deliveryQueue);
377 
378  // Join group
380 
381  // Set up poller
382  zsock_t *zyreSocket = zyre_socket(_zyre);
383  zsock_t *controlSocket = _control.GetSocket();
384  zpoller_t *poller = zpoller_new(controlSocket, zyreSocket, nullptr);
385 
386  // Process events
387  while (true)
388  {
389  // Wait for event
390  void *result = zpoller_wait(poller, -1);
391 
392  // Check if we have a read event
393  if (result == zyreSocket)
394  {
395  // Get event
396  zyre_event_t *event = zyre_event_new(_zyre);
397  if (event != NULL)
398  {
399  // Process event
400  deliveryQueue.enqueue(event);
401  }
402  }
403  else if (result == controlSocket)
404  {
405  // Receive command
406  const char *command = NULL;
407  const ZyreNode *target = NULL;
408  zmsg_t *message = NULL;
409  if (zsock_recv(_control, "ppp", &command, &target, &message) == 0)
410  {
411  if (strcmp(command, "SHUTDOWN") == 0)
412  {
413  // Graceful shutdown request
414  break;
415  }
416  else if (strcmp(command, "SEND") == 0 && message != nullptr)
417  {
418  // Send message
419  if (target == nullptr)
420  {
421  zyre_shout(_zyre, SWARMIO_ZYRE_GROUP_MESSAGES, &message);
422  }
423  else
424  {
425  zyre_whisper(_zyre, target->GetUUID().c_str(), &message);
426  }
427 
428  // OK
429  zsock_signal(_control, 0);
430  }
431  else if (command == NULL)
432  {
433  // Malformed message, send error
434  zsock_signal(_control, -1);
435  }
436  }
437  }
438  }
439 
440  // Finish the queue
441  deliveryQueue.enqueue(nullptr);
442  deliveryThread.join();
443 
444  // Leave group
445  zyre_leave(_zyre, SWARMIO_ZYRE_GROUP_MESSAGES);
446 
447  // Stop instance
448  zyre_stop(_zyre);
449 
450  // Signal terminator
451  zsock_signal(_control, 0);
452 }
453 
454 void ZyreEndpoint::Deliver(moodycamel::BlockingReaderWriterQueue<zyre_event_t *> *queue)
455 {
456  zyre_event_t *event = nullptr;
457  while (true)
458  {
459  // Get next event
460  queue->wait_dequeue(event);
461 
462  // Check if we need to exit
463  if (event == nullptr)
464  {
465  // Set all remote nodes as offline and send notifications
466  std::shared_lock<std::shared_timed_mutex> guard(_mutex);
467  for (auto &element : _nodes)
468  {
469  if (element.second.IsOnline())
470  {
471  element.second.SetOnline(false);
472  NodeWillLeave(&element.second);
473  }
474  }
475 
476  // Exit loop
477  break;
478  }
479 
480  // Resolve UUID
481  const char *uuid = zyre_event_peer_uuid(event);
482  if (uuid != nullptr)
483  {
484  // Handle event
485  const char *type = zyre_event_type(event);
486  if (strcmp(type, "ENTER") == 0)
487  {
488  // Lock map
489  std::unique_lock<std::shared_timed_mutex> guard(_mutex);
490 
491  // Try to resolve node
492  auto result = _nodes.find(uuid);
493  if (result == _nodes.end())
494  {
495  // Detect device class
496  const char *deviceClass = zyre_event_header(event, SWARMIO_ZYRE_HEADER_DEVICE_CLASS);
497  if (deviceClass == nullptr)
498  {
499  deviceClass = "unknown";
500  }
501 
502  // Construct node
503  // (It would be nice to use try_emplace, but there is no way to
504  // get it working with older C++ standard libraries.)
505  auto it = _nodes.emplace(
506  std::piecewise_construct,
507  std::forward_as_tuple(uuid),
508  std::forward_as_tuple(uuid, zyre_event_peer_name(event), deviceClass, zyre_event_peer_addr(event)));
509 
510  // Unlock map
511  guard.unlock();
512 
513  // Send discovery message
514  if (it.second)
515  {
516  NodeWasDiscovered(&it.first->second);
517  }
518  }
519  }
520  else
521  {
522  // Lock map
523  std::shared_lock<std::shared_timed_mutex> guard(_mutex);
524 
525  // Resolve node
526  auto result = _nodes.find(uuid);
527  if (result != _nodes.end())
528  {
529  // Unlock map
530  guard.unlock();
531 
532  if (strcmp(type, "JOIN") == 0 && strcmp(zyre_event_group(event), SWARMIO_ZYRE_GROUP_MESSAGES) == 0)
533  {
534  // Mark as online and notify mailboxes
535  if (!result->second.IsOnline())
536  {
537  result->second.SetOnline(true);
538  NodeDidJoin(&result->second);
539  if (security_enabled)
540  {
541  isJoining = true;
542  LOG(WARNING) << "Sending certificate to join";
543  Send(certificate, crypto_box_PUBLICKEYBYTES + crypto_sign_SECRETKEYBYTES, &result->second);
544  isJoining = false;
545  }
546  }
547  }
548  else if (strcmp(type, "LEAVE") == 0 && strcmp(zyre_event_group(event), SWARMIO_ZYRE_GROUP_MESSAGES) == 0)
549  {
550  // Mark as offline and notify mailboxes
551  if (result->second.IsOnline())
552  {
553  result->second.SetOnline(false);
554  NodeWillLeave(&result->second);
555  }
556  }
557  else if (strcmp(type, "EXIT") == 0)
558  {
559  // Mark as offline and notify mailboxes
560  if (result->second.IsOnline())
561  {
562  result->second.SetOnline(false);
563  NodeWillLeave(&result->second);
564  }
565  }
566  else if (strcmp(type, "SHOUT") == 0 ||
567  strcmp(type, "WHISPER") == 0)
568  {
569  // Get a reference to the raw message
570  zmsg_t *raw = zyre_event_msg(event);
571  if (raw != NULL)
572  {
573  // Each frame needs to be processed individually
574  while (zmsg_size(raw) > 0)
575  {
576  // Handle certificate handshake
577  zframe_t *frame = zmsg_pop(raw);
578  if (security_enabled && zframe_size(frame) == 96 && !((ZyreNode *)&result->second)->GetVerified())
579  {
580  // Handle certificate registration
581  if (crypto_sign_verify_detached(&zframe_data(frame)[crypto_sign_PUBLICKEYBYTES], zframe_data(frame), crypto_sign_PUBLICKEYBYTES, server_public) != 0)
582  {
583  LOG(WARNING) << "Unable to verify joining node certificate";
584  }
585  else
586  {
587  // Save shared key
588  unsigned char k[crypto_box_BEFORENMBYTES];
589  unsigned char p2p_publickey[crypto_box_PUBLICKEYBYTES];
590  if (crypto_sign_ed25519_pk_to_curve25519(p2p_publickey, zframe_data(frame)) != 0)
591  {
592  LOG(WARNING) << "Unable to convert public key";
593  }
594  if (crypto_box_beforenm(k, p2p_publickey, my_secretkey) != 0)
595  {
596  LOG(WARNING) << "Cannot create shared p2p keys";
597  }
598  else
599  {
600  ((ZyreNode *)&result->second)->SetKeys(k, p2p_publickey);
601  ((ZyreNode *)&result->second)->SetVerified();
602  LOG(WARNING) << "Adding joining node certificate";
603  // Send back own certificate
604  isJoining = true;
605  LOG(WARNING) << "Sending back own certificate";
606  Send(certificate, crypto_box_PUBLICKEYBYTES + crypto_sign_SECRETKEYBYTES, &result->second);
607  isJoining = false;
608  }
609  }
610  }
611 
612  // Decrypt message
613  else if (security_enabled)
614  {
615  size_t d_size = zframe_size(frame) - crypto_box_MACBYTES - crypto_box_NONCEBYTES;
616  unsigned char *decrypted = new unsigned char[d_size];
617  unsigned char *nonce = &zframe_data(frame)[zframe_size(frame) - crypto_box_NONCEBYTES];
618  const ZyreNode *zyreNode = dynamic_cast<const ZyreNode *>(&(result->second));
619  dynamic_cast<const ZyreNode *>(NodeForUUID(zyreNode->GetUUID()))->IncrementCtr();
620  if (memcmp(nonce, zyreNode->GetCtr(), crypto_box_NONCEBYTES) < 0)
621  {
622  LOG(WARNING) << "Nonce was smaller than expected";
623  }
624  //Synchronizing nonce
625  zyreNode->SetCtr(nonce);
626  // Broadcast
627  if (strcmp(type, "SHOUT") == 0)
628  {
629  if (crypto_box_open_easy(decrypted, zframe_data(frame), d_size + crypto_box_MACBYTES, nonce, bcast_publickey, bcast_secretkey) != 0)
630  {
631  LOG(WARNING) << "Bcast Message cannot be decrypted";
632  }
633  else
634  {
635  LOG(WARNING) << "Bcast Message successfully decrypted";
636  ReceiveMessage(&result->second, decrypted, d_size);
637  }
638  delete[] decrypted;
639  }
640  else
641  {
642  if (crypto_box_open_easy_afternm(decrypted, zframe_data(frame), d_size + crypto_box_MACBYTES, nonce, zyreNode->GetKey()) != 0)
643  {
644  LOG(WARNING) << "Message cannot be decrypted";
645  }
646  else
647  {
648  LOG(WARNING) << "Message successfully decrypted";
649  ReceiveMessage(&result->second, decrypted, d_size);
650  }
651  delete[] decrypted;
652  }
653  }
654  else
655  {
656  // Decode and dispatch, log errors and go on
657  ReceiveMessage(&result->second, zframe_data(frame), zframe_size(frame));
658  }
659 
660  // Destroy frame
661  zframe_destroy(&frame);
662  }
663  }
664  }
665  }
666  }
667  }
668 
669  // Destroy event
670  zyre_event_destroy(&event);
671  }
672 }
673 
674 std::list<const ZyreNode *> ZyreEndpoint::GetNodes()
675 {
676  // Lock map
677  std::shared_lock<std::shared_timed_mutex> guard(_mutex);
678 
679  // Create copy
680  std::list<const ZyreNode *> nodes;
681  transform(_nodes.begin(), _nodes.end(), back_inserter(nodes), [](const std::map<std::string, ZyreNode>::value_type &value) { return &value.second; });
682 
683  // Return copy
684  return nodes;
685 }
686 
687 const Node *ZyreEndpoint::NodeForUUID(const std::string &uuid)
688 {
689  // Lock map
690  std::shared_lock<std::shared_timed_mutex> guard(_mutex);
691 
692  // Find element
693  auto it = _nodes.find(uuid);
694  if (it != _nodes.end())
695  {
696  return &it->second;
697  }
698  else
699  {
700  return nullptr;
701  }
702 }
void SetPort(uint16_t port)
Set the port used by the endpoint.
unsigned char certificate[crypto_box_PUBLICKEYBYTES+crypto_sign_SECRETKEYBYTES]
Definition: ZyreEndpoint.h:85
#define SWARMIO_ZYRE_GROUP_MESSAGES
A Node as discovered by the Zyre protocol.
Definition: ZyreNode.h:20
virtual void Stop() override
Send a termination signal and wait until the endpoint finished processing messages.
virtual void Send(const void *data, size_t size, const Node *node) override
Called by BasicEndpoint to send serialized messages. Called with node set to nullptr to send a messag...
void SetConfig(std::string cfg)
Set the config file path.
unsigned char bcast_publickey[crypto_box_PUBLICKEYBYTES]
Definition: ZyreEndpoint.h:81
std::thread * _worker
Worker thread.
Definition: ZyreEndpoint.h:60
void IncrementCtr() const
Increment the nonce counter the node.
Definition: ZyreNode.h:172
zsock_t * GetSocket()
Get the pointer to the socket.
virtual void NodeWillLeave(const Node *node) noexcept
Called when a Node signals that it will leave.
Exception class thrown by all library classes.
virtual void NodeWasDiscovered(const Node *node) noexcept
Called when a new Node has been discovered.
#define SWARMIO_ZYRE_HEADER_DEVICE_CLASS
void SetCtr(unsigned char *c) const
Set the nonce (counter)
Definition: ZyreNode.h:181
void Deliver(moodycamel::BlockingReaderWriterQueue< zyre_event_t * > *queue)
Entry point for the delivery thread.
ZyreControlSocket _control
Control pipe to shut down event processing.
Definition: ZyreEndpoint.h:42
virtual void Stop() override
Send a termination signal and wait until the endpoint finished processing messages.
void Process()
Entry point for the worker thread.
virtual bool ReceiveMessage(const Node *sender, const data::Message *message) noexcept
Called by implementations to deliver decoded messages.
ROSLIB_DECL std::string command(const std::string &cmd)
std::map< std::string, ZyreNode > _nodes
Node registry.
Definition: ZyreEndpoint.h:48
std::shared_timed_mutex _mutex
Mutex protecting the Nodes registry.
Definition: ZyreEndpoint.h:54
void SetInterface(const char *ifname)
Set the network interface to bind to.
zyre_t * _zyre
Reference to the Zyre structure.
Definition: ZyreEndpoint.h:36
unsigned char my_secretkey[crypto_box_SECRETKEYBYTES]
Definition: ZyreEndpoint.h:80
unsigned char my_publickey[crypto_box_PUBLICKEYBYTES]
Secret key.
Definition: ZyreEndpoint.h:79
unsigned char bcast_secretkey[crypto_box_SECRETKEYBYTES]
Definition: ZyreEndpoint.h:82
virtual void Start() override
Start a background thread and begin processing messages on this endpoint.
const unsigned char * GetKey() const
Get the shared cryptographic key of the node.
Definition: ZyreNode.h:114
virtual ~ZyreEndpoint() override
Destroy the ZyreEndpoint object.
An inproc socket bound to a special name generated from an object pointer.
virtual const std::string & GetUUID() const override
Get the unique identifier of the node.
Definition: BasicNode.h:50
const char * what() const noexceptoverride
Get the error message.
ZyreEndpoint(const char *name, const char *deviceClass)
Construct a new ZyreEndpoint object.
virtual void Start() override
Start the background thread, announce the Zyre node and start processing messages.
unsigned char signature[crypto_sign_SECRETKEYBYTES]
Definition: ZyreEndpoint.h:83
virtual void NodeDidJoin(const Node *node) noexcept
Called when a new Node has joined the group.
Represents a Node the Endpoint knows about and can send messages to.
virtual const Node * NodeForUUID(const std::string &uuid) override
Retreive a node by its UUID.
std::string base64_decode(std::string const &s)
Definition: base64.cpp:87
bool security_enabled
Security enabled bit (if true, communication is secure)
Definition: ZyreEndpoint.h:72
std::list< const ZyreNode * > GetNodes()
Get a list of known Nodes.
unsigned char server_public[crypto_sign_PUBLICKEYBYTES]
Definition: ZyreEndpoint.h:84
const unsigned char * GetCtr() const
Get the nonce counter of the node.
Definition: ZyreNode.h:144
static std::map< std::string, std::string > GetInterfaceMap()
Get a map of interface names and addresses.


swarmros
Author(s):
autogenerated on Fri Apr 3 2020 03:42:48