-
Notifications
You must be signed in to change notification settings - Fork 6
Expand file tree
/
Copy pathdsr_api.cpp
More file actions
1961 lines (1724 loc) · 81 KB
/
dsr_api.cpp
File metadata and controls
1961 lines (1724 loc) · 81 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
//
// Created by crivac on 5/02/19.
//
#include "dsr/api/dsr_graph_settings.h"
#include "dsr/core/topics/IDLGraph.hpp"
#include "dsr/core/types/translator.h"
#include "include/dsr/api/dsr_signal_emitter.h"
#include <chrono>
#include <ctime>
#include <dsr/api/dsr_api.h>
#include <dsr/core/types/crdt_types.h>
#include <iostream>
#include <optional>
#include <qglobal.h>
#include <unistd.h>
#include <algorithm>
#include <utility>
#include <cmath>
#include <dsr/api/dsr_logging.h>
#include <fastdds/rtps/RTPSDomain.hpp>
#include <QtCore/qlogging.h>
#include <QtCore/qdebug.h>
using namespace DSR;
using namespace std::literals;
/////////////////////////////////////////////////
///// PUBLIC METHODS
/////////////////////////////////////////////////
DSRGraph::DSRGraph(GraphSettings settings) :
agent_id(settings.agent_id),
agent_name(std::move(settings.graph_name)),
copy(false),
tp(settings.theradpool_threads),
tp_delta_attr(settings.attribute_threadpool_threads),
same_host(settings.same_host),
generator(settings.agent_id),
log_level(settings.log_level)
{
qDebug() << "Agent name: " << QString::fromStdString(agent_name);
utils = std::make_unique<Utilities>(this);
if (settings.signal_mode == SignalMode::QT) {
set_qt_signals();
} else {
set_queued_signals();
}
// RTPS Create participant
auto[suc, participant_handle] = dsrparticipant.init(agent_id, agent_name, settings.same_host,
ParticipantChangeFunctor(this, [&](DSR::DSRGraph *graph,
eprosima::fastdds::rtps::ParticipantDiscoveryStatus status,
const eprosima::fastdds::rtps::ParticipantBuiltinTopicData& info)
{
if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DISCOVERED_PARTICIPANT)
{
std::unique_lock<std::mutex> lck(participant_set_mutex);
std::cout << "Participant matched [" << info.participant_name.to_string() << "]" << std::endl;
graph->participant_set.emplace(info.participant_name.to_string(), false);
}
else if (status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::REMOVED_PARTICIPANT ||
status == eprosima::fastdds::rtps::ParticipantDiscoveryStatus::DROPPED_PARTICIPANT)
{
std::unique_lock<std::mutex> lck(participant_set_mutex);
graph->participant_set.erase(info.participant_name.to_string());
std::cout << "Participant unmatched [" << info.participant_name.to_string() << "]" << std::endl;
graph->delete_node(info.participant_name.to_string());
}
}), settings.domain_id);
// RTPS Initialize publisher with general topic
auto [res, pub, writer] = dsrpub_node.init(participant_handle, dsrparticipant.getNodeTopic());
auto [res2, pub2, writer2] = dsrpub_node_attrs.init(participant_handle, dsrparticipant.getAttNodeTopic());
auto [res3, pub3, writer3] = dsrpub_edge.init(participant_handle, dsrparticipant.getEdgeTopic());
auto [res4, pub4, writer4] = dsrpub_edge_attrs.init(participant_handle, dsrparticipant.getAttEdgeTopic());
auto [res5, pub5, writer5] = dsrpub_graph_request.init(participant_handle, dsrparticipant.getGraphRequestTopic());
auto [res6, pub6, writer6] = dsrpub_request_answer.init(participant_handle, dsrparticipant.getGraphTopic());
dsrparticipant.add_publisher(dsrparticipant.getNodeTopic()->get_name(), {pub, writer});
dsrparticipant.add_publisher(dsrparticipant.getAttNodeTopic()->get_name(), {pub2, writer2});
dsrparticipant.add_publisher(dsrparticipant.getEdgeTopic()->get_name(), {pub3, writer3});
dsrparticipant.add_publisher(dsrparticipant.getAttEdgeTopic()->get_name(), {pub4, writer4});
dsrparticipant.add_publisher(dsrparticipant.getGraphRequestTopic()->get_name(), {pub5, writer5});
dsrparticipant.add_publisher(dsrparticipant.getGraphTopic()->get_name(), {pub6, writer6});
// RTPS Initialize comms threads
if (!settings.input_file.empty())
{
try
{
read_from_json_file(settings.input_file);
qDebug() << __FUNCTION__ << "Warning, graph read from file " << QString::fromStdString(settings.input_file);
}
catch(const DSR::DSRException& e)
{
std::cout << e.what() << '\n';
qFatal("Aborting program. Cannot continue without intial file");
}
start_fullgraph_server_thread();
start_subscription_threads();
}
else
{
start_subscription_threads(); // regular subscription to deltas
auto [response, repeated] = start_fullgraph_request_thread(); // for agents that want to request the graph for other agent
if(!response)
{
dsrparticipant.remove_participant_and_entities(); // Remove a Participant and all associated publishers and subscribers.
if (repeated)
{
qFatal("%s", (std::string("There is already an agent connected with the id: ") + std::to_string(agent_id)).c_str());
}
else {
qFatal("DSRGraph aborting: could not get DSR from the network after timeout");
}
}
}
qDebug() << __FUNCTION__ << "Constructor finished OK";
}
DSRGraph::DSRGraph(std::string name, uint32_t id, const std::string &dsr_input_file, bool all_same_host, int8_t domain_id, SignalMode mode)
: DSR::DSRGraph(GraphSettings {id, 5, 1, name, dsr_input_file, "", all_same_host, GraphSettings::LOGLEVEL::INFOL, domain_id, mode})
{}
DSRGraph::~DSRGraph()
{
qDebug() << "Removing DSRGraph";
dsrparticipant.remove_participant_and_entities();
if (!copy) {
qDebug() << "Removing rtps participant";
}
}
//////////////////////////////////////
/// NODE METHODS
/////////////////////////////////////
std::optional<DSR::Node> DSRGraph::get_node(const std::string &name)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
if (name.empty()) return {};
std::optional<uint64_t> id = get_id_from_name(name);
if (id.has_value())
{
std::optional<CRDTNode> n = get_(id.value());
if (n.has_value()) return Node(std::move(n.value()));
}
return {};
}
std::optional<DSR::Node> DSRGraph::get_node(uint64_t id)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::optional<CRDTNode> n = get_(id);
if (n.has_value()) return Node(std::move(n.value()));
return {};
}
std::tuple<bool, std::optional<IDL::MvregNode>> DSRGraph::insert_node_(CRDTNode &&node)
{
if (!deleted.contains(node.id()))
{
if (auto it = nodes.find(node.id()); it != nodes.end() and not it->second.empty() and it->second.read_reg() == node)
{
return {true, {}};
}
uint64_t id = node.id();
update_maps_node_insert(id, node);
mvreg<CRDTNode> delta = nodes[id].write(std::move(node));
return {true, CRDTNode_to_IDL(agent_id, id, delta)};
}
return {false, {}};
}
template<typename No>
std::optional<uint64_t> DSRGraph::insert_node(No &&node)
requires (std::is_same_v<std::remove_reference_t<No>, DSR::Node>)
{
std::optional<IDL::MvregNode> delta;
bool inserted = false;
{
std::unique_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lck_cache(_mutex_cache_maps);
uint64_t new_node_id = generator.generate();
node.id(new_node_id);
if (node.name().empty() or name_map.contains(node.name()))
node.name(node.type() + "_" + id_generator::hex_string(new_node_id));
lck_cache.unlock();
std::tie(inserted, delta) = insert_node_(user_node_to_crdt(std::forward<No>(node)));
}
if (inserted)
{
if (!copy)
{
if (delta.has_value())
{
dsrpub_node.write(&delta.value());
DSR_LOG_DEBUG("[INSERT_NODE] emitting update_node_signal", node.id(), node.type());
emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id});
for (const auto &[k, v]: node.fano())
{
emitter.update_edge_signal(node.id(), k.first, k.second, SignalInfo{agent_id});
}
}
}
return node.id();
}
return {};
}
template std::optional<uint64_t> DSRGraph::insert_node<DSR::Node &&>(DSR::Node&&);
template std::optional<uint64_t> DSRGraph::insert_node<DSR::Node&>(DSR::Node&);
std::tuple<bool, std::optional<std::vector<IDL::MvregNodeAttr>>> DSRGraph::update_node_(CRDTNode &&node)
{
if (!deleted.contains(node.id()))
{
if (nodes.contains(node.id()) and !nodes.at(node.id()).empty())
{
std::vector<IDL::MvregNodeAttr> atts_deltas;
auto &iter = nodes.at(node.id()).read_reg().attrs();
//New attributes and updates.
for (auto &[k, att]: node.attrs()) {
if (!iter.contains(k)) {
iter.emplace(k, mvreg<CRDTAttribute>());
}
if (iter.at(k).empty() or att.read_reg() != iter.at(k).read_reg()) {
auto delta = iter.at(k).write(std::move(att.read_reg()));
atts_deltas.emplace_back(
CRDTNodeAttr_to_IDL(agent_id, node.id(), node.id(), k, delta));
}
}
//Remove old attributes.
auto it_a = iter.begin();
while (it_a != iter.end()) {
const std::string &k = it_a->first;
if (ignored_attributes.contains(k)) {
it_a = iter.erase(it_a);
} else if (!node.attrs().contains(k)) {
auto delta = iter.at(k).reset();
atts_deltas.emplace_back(
CRDTNodeAttr_to_IDL(node.agent_id(), node.id(), node.id(), k, delta));
it_a = iter.erase(it_a);
} else {
++it_a;
}
}
return {true, std::move(atts_deltas)};
}
}
return {false, {}};
}
template<typename No>
bool DSRGraph::update_node(No &&node)
requires (std::is_same_v<std::remove_cvref_t<No>, DSR::Node>)
{
bool updated = false;
std::optional<std::vector<IDL::MvregNodeAttr>> vec_node_attr;
{
std::unique_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lck_cache(_mutex_cache_maps);
if (deleted.contains(node.id()))
throw std::runtime_error(
(std::string("Cannot update node in G, " + std::to_string(node.id()) + " is deleted") + __FILE__ +
" " + __FUNCTION__ + " " + std::to_string(__LINE__)).data());
else if (( id_map.contains(node.id()) and id_map.at(node.id()) != node.name()) or
( name_map.contains(node.name()) and name_map.at(node.name()) != node.id()))
throw std::runtime_error(
(std::string("Cannot update node in G, id and name must be unique") + __FILE__ + " " +
__FUNCTION__ + " " + std::to_string(__LINE__)).data());
else if (nodes.contains(node.id())) {
lck_cache.unlock();
std::tie(updated, vec_node_attr) = update_node_(user_node_to_crdt(std::forward<No>(node)));
}
}
if (updated) {
if (!copy) {
if (vec_node_attr.has_value()) {
dsrpub_node_attrs.write(&vec_node_attr.value());
DSR_LOG_DEBUG("[UPDATE_NODE] emitting update_node_signal", node.id(), node.type());
emitter.update_node_signal(node.id(), node.type(), SignalInfo{agent_id});
std::vector<std::string> atts_names(vec_node_attr->size());
std::transform(std::make_move_iterator(vec_node_attr->begin()),
std::make_move_iterator(vec_node_attr->end()),
atts_names.begin(),
[](auto &&x) { return x.attr_name(); });
emitter.update_node_attr_signal(node.id(), atts_names, SignalInfo{agent_id});
}
}
}
return updated;
}
template bool DSRGraph::update_node<DSR::Node &&>(DSR::Node&&);
template bool DSRGraph::update_node<DSR::Node&>(DSR::Node&);
template bool DSRGraph::update_node<const DSR::Node&>(const DSR::Node&);
template bool DSRGraph::update_node<DSR::Node>(DSR::Node&&);
std::tuple<bool, std::vector<Edge>, std::optional<IDL::MvregNode>, std::vector<IDL::MvregEdge>>
DSRGraph::delete_node_(uint64_t id) {
std::vector<Edge> deleted_edges;
std::vector<IDL::MvregEdge> delta_vec;
//Get and remove node.
auto node = get_(id);
if (!node.has_value()) return make_tuple(false, deleted_edges, std::nullopt, delta_vec);
// Delete all edges from this node.
for (const auto &v : node.value().fano()) {
deleted_edges.emplace_back(v.second.read_reg());
}
// Get remove delta.
auto delta = nodes[id].reset();
IDL::MvregNode delta_remove = CRDTNode_to_IDL(agent_id, id, delta);
//search and remove edges.
//For each node check if there is an edge to remove.
//TODO: use to_edges.
for (auto &[k, v] : nodes)
{
std::shared_lock<std::shared_mutex> lck_cache(_mutex_cache_maps);
if (!edges.contains({k, id})) continue;
// Remove all edges between them
auto &visited_node = v.read_reg();
auto keys = deleted_edges.size();
for (const auto &key : edges.at({k, id}))
{
deleted_edges.emplace_back(visited_node.fano().at({id, key}).read_reg());
auto delta_fano = visited_node.fano().at({id, key}).reset();
delta_vec.emplace_back(CRDTEdge_to_IDL(agent_id, k, id, key, delta_fano));
visited_node.fano().erase({id, key});
}
lck_cache.unlock();
//Remove all from cache
for (auto i = keys; i < deleted_edges.size(); i++) {
update_maps_edge_delete(k, id, deleted_edges[i].type());
}
}
update_maps_node_delete(id, node.value());
return make_tuple(true, std::move(deleted_edges), std::move(delta_remove), std::move(delta_vec));
}
bool DSRGraph::delete_node(const DSR::Node &node)
{
return delete_node(node.id());
}
bool DSRGraph::delete_node(const std::string &name)
{
bool result = false;
std::vector<Edge> deleted_edges;
std::optional<IDL::MvregNode> deleted_node;
std::vector<IDL::MvregEdge> delta_vec;
std::optional<Node> node_signal;
std::optional<uint64_t> id = {};
{
id = get_id_from_name(name);
if (id.has_value()) {
node_signal = get_(*id);
std::unique_lock<std::shared_mutex> lock(_mutex);
std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id.value());
} else {
return false;
}
}
if (result) {
if (!copy) {
DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id.value());
emitter.del_node_signal(id.value(), SignalInfo{agent_id});
if (node_signal) emitter.deleted_node_signal(*node_signal, SignalInfo{agent_id});
dsrpub_node.write(&deleted_node.value());
for (auto &a : delta_vec) {
dsrpub_edge.write(&a);
}
for (auto &edge : deleted_edges) {
emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id });
emitter.deleted_edge_signal(edge, SignalInfo{ agent_id });
}
}
return true;
}
return false;
}
bool DSRGraph::delete_node(uint64_t id)
{
bool result = false;
std::vector<Edge> deleted_edges;
std::optional<IDL::MvregNode> deleted_node;
std::optional<Node> node_signal;
std::vector<IDL::MvregEdge> delta_vec;
{
node_signal = get_(id);
std::unique_lock<std::shared_mutex> lock(_mutex);
std::tie(result, deleted_edges, deleted_node, delta_vec) = delete_node_(id);
}
if (result) {
if (!copy) {
DSR_LOG_DEBUG("[DELETE_NODE] emitting del_node_signal", id);
emitter.del_node_signal(id, SignalInfo{ agent_id });
if (node_signal) emitter.deleted_node_signal(*node_signal, SignalInfo{agent_id});
dsrpub_node.write(&deleted_node.value());
for (auto &a : delta_vec) {
dsrpub_edge.write(&a);
}
for (auto &edge : deleted_edges) {
emitter.del_edge_signal(edge.from(), edge.to(), edge.type(), SignalInfo{ agent_id });
emitter.deleted_edge_signal(edge, SignalInfo{ agent_id });
}
}
return true;
}
return false;
}
std::vector<DSR::Node> DSRGraph::get_nodes_by_type(const std::string &type)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lck(_mutex_cache_maps);
std::vector<Node> nodes_;
if (nodeType.contains(type))
{
for (auto &id: nodeType.at(type))
{
std::optional<CRDTNode> n = get_(id);
if (n.has_value())
nodes_.emplace_back(std::move(n.value()));
}
}
return nodes_;
}
std::vector<Node> DSRGraph::get_nodes()
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::vector<Node> nodes_;
nodes_.reserve(nodes.size());
for (auto &[id, N]: nodes)
{
nodes_.emplace_back(N.read_reg());
}
return nodes_;
}
std::vector<DSR::Node> DSRGraph::get_nodes_by_types(const std::vector<std::string> &types)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lck(_mutex_cache_maps);
std::vector<Node> nodes_;
for (auto &type : types)
{
if (nodeType.contains(type))
{
for (auto &id: nodeType.at(type))
{
std::optional<CRDTNode> n = get_(id);
if (n.has_value())
nodes_.emplace_back(std::move(n.value()));
}
}
}
return nodes_;
}
//////////////////////////////////////////////////////////////////////////////////
// EDGE METHODS
//////////////////////////////////////////////////////////////////////////////////
std::optional<CRDTEdge> DSRGraph::get_edge_(uint64_t from, uint64_t to, const std::string &key)
{
//std::shared_lock<std::shared_mutex> lock(_mutex);
if (nodes.contains(from) && nodes.contains(to))
{
auto n = get_(from);
if (n.has_value()) {
auto edge = n.value().fano().find({to, key});
if (edge != n.value().fano().end()) {
return edge->second.read_reg();
}
}
}
return {};
}
std::optional<DSR::Edge> DSRGraph::get_edge(const std::string &from, const std::string &to, const std::string &key)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::optional<uint64_t> id_from = get_id_from_name(from);
std::optional<uint64_t> id_to = get_id_from_name(to);
if (id_from.has_value() and id_to.has_value())
{
auto edge_opt = get_edge_(id_from.value(), id_to.value(), key);
if (edge_opt.has_value()) return Edge(edge_opt.value());
}
return {};
}
std::optional<DSR::Edge> DSRGraph::get_edge(uint64_t from, uint64_t to, const std::string &key)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
auto edge_opt = get_edge_(from, to, key);
if (edge_opt.has_value()) return Edge(std::move(edge_opt.value()));
return {};
}
std::optional<Edge> DSRGraph::get_edge(const Node &n, const std::string &to, const std::string &key)
{
std::optional<uint64_t> id_to = get_id_from_name(to);
if (id_to.has_value())
{
return (n.fano().contains({id_to.value(), key})) ?
std::make_optional(n.fano().find({id_to.value(), key})->second) :
std::nullopt;
}
return {};
}
std::optional<Edge> DSRGraph::get_edge(const Node &n, uint64_t to, const std::string &key)
{
return (n.fano().contains({to, key})) ?
std::make_optional(n.fano().find({to, key})->second) :
std::nullopt;
}
std::tuple<bool, std::optional<IDL::MvregEdge>, std::optional<std::vector<IDL::MvregEdgeAttr>>>
DSRGraph::insert_or_assign_edge_(CRDTEdge &&attrs, uint64_t from, uint64_t to)
{
std::optional<IDL::MvregEdge> delta_edge;
std::optional<std::vector<IDL::MvregEdgeAttr>> delta_attrs;
if (nodes.contains(from))
{
auto &node = nodes.at(from).read_reg();
//check if we are creating an edge or we are updating it.
//Update
if (node.fano().contains({to, attrs.type()}))
{
auto iter = nodes.at(from).read_reg().fano().find({attrs.to(), attrs.type()});
auto end = nodes.at(from).read_reg().fano().end();
if (iter != end) {
std::vector<IDL::MvregEdgeAttr> atts_deltas;
auto &iter_edge = iter->second.read_reg().attrs();
for (auto &[k, att]: attrs.attrs()) {
//comparar igualdad o inexistencia
if (!iter_edge.contains(k)) {
iter_edge.emplace(k, mvreg<CRDTAttribute>());
}
if (iter_edge.at(k).empty() or
att.read_reg() !=
iter_edge.at(k).read_reg()) {
auto delta = iter_edge.at(k).write(std::move(att.read_reg()));
atts_deltas.emplace_back(
CRDTEdgeAttr_to_IDL(agent_id, from, from, to, attrs.type(), k, delta));
}
}
auto it = iter_edge.begin();
while (it != iter_edge.end()) {
if (!attrs.attrs().contains(it->first)) {
std::string att = it->first;
auto delta = iter_edge.at(it->first).reset();
it = iter_edge.erase(it);
atts_deltas.emplace_back(
CRDTEdgeAttr_to_IDL(agent_id, from, from, to, attrs.type(), att, delta));
} else {
++it;
}
}
return {true, {}, std::move(atts_deltas)};
}
} else
{ // Insert
//node.fano().insert({{to, attrs.type()}, mvreg<CRDTEdge>()});
std::string att_type = attrs.type();
auto delta = node.fano()[{to, attrs.type()}].write(std::move(attrs));
update_maps_edge_insert(from, to, att_type);
return {true, CRDTEdge_to_IDL(agent_id, from, to, att_type, delta), {}};
}
}
return {false, {}, {}};
}
template<typename Ed>
bool DSRGraph::insert_or_assign_edge(Ed &&attrs)
requires (std::is_same_v<std::remove_cvref_t<Ed>, DSR::Edge>)
{
bool result = false;
std::optional<IDL::MvregEdge> delta_edge;
std::optional<std::vector<IDL::MvregEdgeAttr>> delta_attrs;
{
std::unique_lock<std::shared_mutex> lock(_mutex);
uint64_t from = attrs.from();
uint64_t to = attrs.to();
if (nodes.contains(from) && nodes.contains(to)) {
std::tie(result, delta_edge, delta_attrs) = insert_or_assign_edge_(user_edge_to_crdt(std::forward<Ed>(attrs)), from, to);
} else {
std::cout << __FUNCTION__ << ":" << __LINE__ << " Error. ID:" << from << " or " << to
<< " not found. Cant update. " << std::endl;
return false;
}
}
if (result) {
if (!copy) {
DSR_LOG_DEBUG("[INSERT_OR_ASSIGN_EDGE] emitting update_edge_signal", attrs.from(), attrs.to(), attrs.type());
emitter.update_edge_signal(attrs.from(), attrs.to(), attrs.type(), SignalInfo{ agent_id });
if (delta_edge.has_value()) { //Insert
dsrpub_edge.write(&delta_edge.value());
}
if (delta_attrs.has_value()) { //Update
dsrpub_edge_attrs.write(&delta_attrs.value());
std::vector<std::string> atts_names(delta_attrs->size());
std::transform(std::make_move_iterator(delta_attrs->begin()),
std::make_move_iterator(delta_attrs->end()),
atts_names.begin(),
[](auto &&x) { return x.attr_name(); });
emitter.update_edge_attr_signal(attrs.from(), attrs.to(), attrs.type(), atts_names, SignalInfo{ agent_id });
}
}
}
return true;
}
template bool DSRGraph::insert_or_assign_edge<DSR::Edge>(DSR::Edge&&);
template bool DSRGraph::insert_or_assign_edge<DSR::Edge &&>(DSR::Edge&&);
template bool DSRGraph::insert_or_assign_edge<DSR::Edge&>(DSR::Edge&);
template bool DSRGraph::insert_or_assign_edge<const DSR::Edge&>(const DSR::Edge&);
std::optional<IDL::MvregEdge> DSRGraph::delete_edge_(uint64_t from, uint64_t to, const std::string &key)
{
if (nodes.contains(from)) {
auto &node = nodes.at(from).read_reg();
if (node.fano().contains({to, key})) {
auto delta = node.fano().at({to, key}).reset();
node.fano().erase({to, key});
update_maps_edge_delete(from, to, key);
return CRDTEdge_to_IDL(agent_id, from, to, key, delta);
}
}
return {};
}
bool DSRGraph::delete_edge(uint64_t from, uint64_t to, const std::string &key)
{
std::optional<IDL::MvregEdge> delta;
std::optional<Edge> deleted_edge;
{
std::unique_lock<std::shared_mutex> lock(_mutex);
deleted_edge = get_edge_(from, to, key);
delta = delete_edge_(from, to, key);
}
if (delta.has_value())
{
if (!copy) {
DSR_LOG_DEBUG("[DELETE_EDGE] emitting del_edge_signal", from, to, key);
emitter.del_edge_signal(from, to, key, SignalInfo{ agent_id });
if (deleted_edge.has_value()) {
emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id });
}
dsrpub_edge.write(&delta.value());
}
return true;
}
return false;
}
bool DSRGraph::delete_edge(const std::string &from, const std::string &to, const std::string &key)
{
std::optional<uint64_t> id_from = {};
std::optional<uint64_t> id_to = {};
std::optional<IDL::MvregEdge> delta;
std::optional<Edge> deleted_edge;
{
id_from = get_id_from_name(from);
id_to = get_id_from_name(to);
std::unique_lock<std::shared_mutex> lock(_mutex);
deleted_edge = get_edge_(id_from.value(), id_to.value(), key);
if (id_from.has_value() && id_to.has_value())
{
delta = delete_edge_(id_from.value(), id_to.value(), key);
}
}
if (delta.has_value())
{
if (!copy) {
emitter.del_edge_signal(id_from.value(), id_to.value(), key, SignalInfo{ agent_id });
if (deleted_edge.has_value()) {
emitter.deleted_edge_signal(*deleted_edge, SignalInfo{ agent_id });
}
dsrpub_edge.write(&delta.value());
}
return true;
}
return false;
}
std::vector<DSR::Edge> DSRGraph::get_node_edges_by_type(const Node &node, const std::string &type)
{
std::vector<Edge> edges_;
for (auto &[key, edge] : node.fano())
if (key.second == type)
edges_.emplace_back(edge);
return edges_;
}
std::vector<DSR::Edge> DSRGraph::get_edges_by_type(const std::string &type)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lock_cache(_mutex_cache_maps);
std::vector<Edge> edges_;
if (edgeType.contains(type)) {
for (auto &[from, to] : edgeType.at(type)) {
auto n = get_edge_(from, to, type);
if (n.has_value())
edges_.emplace_back(std::move(n.value()));
}
}
return edges_;
}
std::vector<DSR::Edge> DSRGraph::get_edges_to_id(uint64_t id)
{
std::shared_lock<std::shared_mutex> lock(_mutex);
std::shared_lock<std::shared_mutex> lock_cache(_mutex_cache_maps);
std::vector<Edge> edges_;
if (to_edges.contains(id)) {
for (const auto &[k, v] : to_edges.at(id)) {
auto n = get_edge_(k, id, v);
if (n.has_value())
edges_.emplace_back(std::move(n.value()));
}
}
return edges_;
}
std::optional<std::map<std::pair<uint64_t, std::string>, DSR::Edge>> DSRGraph::get_edges(uint64_t id) {
std::shared_lock<std::shared_mutex> lock(_mutex);
std::optional<Node> n = get_node(id);
if (n.has_value())
{
return n->fano();
}
return std::nullopt;
}
/////////////////////////////////////////////////
///// Utils
/////////////////////////////////////////////////
std::map<uint64_t, DSR::Node> DSRGraph::getCopy() const
{
std::map<uint64_t, Node> mymap;
std::shared_lock<std::shared_mutex> lock(_mutex);
for (auto &[key, val] : nodes)
mymap.emplace(key, Node(val.read_reg()));
return mymap;
}
//////////////////////////////////////////////////////////////////////////////
///// CORE
//////////////////////////////////////////////////////////////////////////////
std::optional<CRDTNode> DSRGraph::get_(uint64_t id)
{
auto it = nodes.find(id);
if (it != nodes.end() and !it->second.empty())
{
return std::make_optional(it->second.read_reg());
}
return {};
}
std::optional<std::int32_t> DSRGraph::get_node_level(const Node &n)
{
return get_attrib_by_name<level_att>(n);
}
std::optional<uint64_t> DSRGraph::get_parent_id(const Node &n)
{
return get_attrib_by_name<parent_att>(n);
}
std::optional<DSR::Node> DSRGraph::get_parent_node(const Node &n)
{
auto p = get_attrib_by_name<parent_att>(n);
if (p.has_value())
{
std::shared_lock<std::shared_mutex> lock(_mutex);
auto tmp = get_(p.value());
if (tmp.has_value()) return Node(tmp.value());
}
return {};
}
std::string DSRGraph::get_node_type(Node &n)
{
return n.type();
}
//////////////////////////////////////////////////////////////////////////////////////////////
inline void DSRGraph::update_maps_node_delete(uint64_t id, const std::optional<CRDTNode> &n)
{
nodes.erase(id);
std::unique_lock<std::shared_mutex> lck(_mutex_cache_maps);
if (id_map.contains(id))
{
name_map.erase(id_map.at(id));
id_map.erase(id);
}
deleted.insert(id);
to_edges.erase(id);
if (n.has_value())
{
if (nodeType.contains(n->type())) {
nodeType.at(n->type()).erase(id);
if (nodeType.at(n->type()).empty()) nodeType.erase(n->type());
}
for (const auto &[k, v] : n->fano()) {
if (auto tuple = std::pair{id, v.read_reg().to()}; edges.contains(tuple)) {
edges.at(tuple).erase(k.second);
if (edges.at(tuple).empty()) edges.erase(tuple);
}
if (auto tuple = std::pair{id, k.first}; edgeType.contains(k.second)) {
edgeType.at(k.second).erase(tuple);
if (edgeType.at(k.second).empty())edgeType.erase(k.second);
}
if (auto tuple = std::pair{id, k.second}; to_edges.contains(k.first)) {
to_edges.at(k.first).erase(tuple);
if (to_edges.at(k.first).empty()) to_edges.erase(k.first);
}
}
}
}
inline void DSRGraph::update_maps_node_insert(uint64_t id, const CRDTNode &n)
{
std::unique_lock<std::shared_mutex> lck(_mutex_cache_maps);
name_map[n.name()] = id;
id_map[id] = n.name();
nodeType[n.type()].emplace(id);
for (const auto &[k, v] : n.fano())
{
edges[{id, k.first}].insert(k.second);
edgeType[k.second].insert({id, k.first});
to_edges[k.first].insert({id, k.second});
}
}
inline void DSRGraph::update_maps_edge_delete(uint64_t from, uint64_t to, const std::string &key)
{
std::unique_lock<std::shared_mutex> lck(_mutex_cache_maps);
if (const auto tuple = std::pair{from, to}; edges.contains(tuple)) {
edges.at(tuple).erase(key);
edges.erase({from, to});
}
if (to_edges.contains(to)) {
to_edges.at(to).erase({from, key});
if (to_edges.at(to).empty()) to_edges.erase(to);
}
if (edgeType.contains(key)) {
edgeType.at(key).erase({from, to});
if (edgeType.at(key).empty()) edgeType.erase(key);
}
}
inline void DSRGraph::update_maps_edge_insert(uint64_t from, uint64_t to, const std::string &key)
{
std::unique_lock<std::shared_mutex> lck(_mutex_cache_maps);
edges[{from, to}].insert(key);
to_edges[to].insert({from, key});
edgeType[key].insert({from, to});
}
std::optional<uint64_t> DSRGraph::get_id_from_name(const std::string &name)
{
std::shared_lock<std::shared_mutex> lck(_mutex_cache_maps);
auto v = name_map.find(name);
if (v != name_map.end()) return v->second;
return {};
}
std::optional<std::string> DSRGraph::get_name_from_id(uint64_t id)
{
std::shared_lock<std::shared_mutex> lck(_mutex_cache_maps);
auto v = id_map.find(id);
if (v != id_map.end()) return v->second;
return {};
}
size_t DSRGraph::size() const {
std::shared_lock<std::shared_mutex> lock(_mutex);
return nodes.size();
}
bool DSRGraph::empty(const uint64_t &id)
{
auto it = nodes.find(id);
if (it != nodes.end()) {
return it->second.empty();
} else
return false;
}
void DSRGraph::join_delta_node(IDL::MvregNode &&mvreg)
{
std::optional<CRDTNode> maybe_deleted_node = {};
try {
bool signal = false, joined = false;
auto id = mvreg.id();
uint64_t timestamp = mvreg.timestamp();
DSR_LOG_DEBUG("[JOIN_NODE] id:", id, "timestamp:", timestamp, "agent:", mvreg.agent_id());
auto crdt_delta = IDLNode_to_CRDT(std::move(mvreg));
bool d_empty = crdt_delta.empty();
auto delete_unprocessed_deltas = [&](){
unprocessed_delta_node_att.erase(id);
decltype(unprocessed_delta_edge_from)::node_type node_handle = unprocessed_delta_edge_from.extract(id);
while (!node_handle.empty())
{
node_handle = unprocessed_delta_edge_from.extract(id);
}
std::erase_if(unprocessed_delta_edge_to,
[&](auto &it){ return std::get<0>(it.second) == id;});
std::erase_if(unprocessed_delta_edge_att,
[&](auto &it){ return std::get<0>(it.first) == id or std::get<1>(it.first) == id;});
};
std::unordered_set<std::pair<uint64_t, std::string>,hash_tuple> map_new_to_edges = {};
std::unordered_set<std::tuple<uint64_t, uint64_t, std::string>,hash_tuple> map_new_from_edges = {};