From 50417051b05b761eb3fe196af7112eba24cfe31a Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 25 Jan 2019 16:14:54 -0600 Subject: [PATCH] Refactor based on reviewer comments: * Remove ERROR status, as disconnecting and stale are sufficient. * Refactor Connect/Disconnect logic into constructor/destructor. --- src/msgs/peer_info.proto | 7 +- src/network/PeerInfo.cc | 4 +- src/network/PeerInfo.hh | 3 +- src/network/PeerTracker.cc | 133 +++++++------------ src/network/PeerTracker.hh | 62 +++++---- src/network/PeerTracker_TEST.cc | 223 ++++++++++++-------------------- 6 files changed, 161 insertions(+), 271 deletions(-) diff --git a/src/msgs/peer_info.proto b/src/msgs/peer_info.proto index db22bb2a77..cb03d7cf8f 100644 --- a/src/msgs/peer_info.proto +++ b/src/msgs/peer_info.proto @@ -62,14 +62,11 @@ message PeerAnnounce /// \brief Possible states announced by a peer enum PeerState { - /// \brief An error occurred - ERROR = 0; - /// \brief Peer is connecting right now - CONNECTING = 1; + CONNECTING = 0; /// \brief Peer is disconnecting right now - DISCONNECTING = 2; + DISCONNECTING = 1; }; /// \brief State which the peer is announcing diff --git a/src/network/PeerInfo.cc b/src/network/PeerInfo.cc index 7baff5ec9d..6eda0e62a0 100644 --- a/src/network/PeerInfo.cc +++ b/src/network/PeerInfo.cc @@ -22,9 +22,9 @@ using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -PeerInfo::PeerInfo(): +PeerInfo::PeerInfo(const NetworkRole &_role): id(ignition::common::Uuid().String()), - role(NetworkRole::None) + role(_role) { } diff --git a/src/network/PeerInfo.hh b/src/network/PeerInfo.hh index 87848d51f6..796d4ebc71 100644 --- a/src/network/PeerInfo.hh +++ b/src/network/PeerInfo.hh @@ -32,9 +32,8 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { class IGNITION_GAZEBO_VISIBLE PeerInfo { - // /// \brief Constructor - public: PeerInfo(); + public: PeerInfo(const NetworkRole &_role = NetworkRole::None); /// \brief Unique peer ID in the network public: std::string id; diff --git a/src/network/PeerTracker.cc b/src/network/PeerTracker.cc index 33a187310f..0b87f95eae 100644 --- a/src/network/PeerTracker.cc +++ b/src/network/PeerTracker.cc @@ -21,17 +21,47 @@ using namespace gazebo; ///////////////////////////////////////////////// PeerTracker::PeerTracker( + const PeerInfo &_info, EventManager *_eventMgr, const ignition::transport::NodeOptions &_options): - node(_options), - eventMgr(_eventMgr) + info(_info), + eventMgr(_eventMgr), + node(_options) { + this->heartbeatPub = this->node.Advertise("heartbeat"); + this->announcePub = this->node.Advertise("announce"); + this->node.Subscribe("heartbeat", &PeerTracker::OnPeerHeartbeat, this); + this->node.Subscribe("announce", &PeerTracker::OnPeerAnnounce, this); + + msgs::PeerAnnounce msg; + *msg.mutable_info() = toProto(this->info); + msg.set_state(msgs::PeerAnnounce::CONNECTING); + this->announcePub.Publish(msg); + + this->heartbeatRunning = true; + this->heartbeatThread = std::thread([this]() + { + this->HeartbeatLoop(); + }); } ///////////////////////////////////////////////// PeerTracker::~PeerTracker() { - this->Disconnect(); + this->node.Unsubscribe("heartbeat"); + this->node.Unsubscribe("announce"); + + this->heartbeatRunning = false; + if (this->heartbeatThread.joinable()) + { + this->heartbeatThread.join(); + } + + msgs::PeerAnnounce msg; + *msg.mutable_info() = toProto(this->info); + msg.set_state(msgs::PeerAnnounce::DISCONNECTING); + + this->announcePub.Publish(msg); } ///////////////////////////////////////////////// @@ -58,51 +88,6 @@ size_t PeerTracker::StaleMultiplier() const return this->staleMultiplier; } -///////////////////////////////////////////////// -void PeerTracker::Connect(std::shared_ptr _info) -{ - this->info = _info; - - this->heartbeatPub = this->node.Advertise("heartbeat"); - this->announcePub = this->node.Advertise("announce"); - this->node.Subscribe("heartbeat", &PeerTracker::OnPeerHeartbeat, this); - this->node.Subscribe("announce", &PeerTracker::OnPeerAnnounce, this); - - msgs::PeerAnnounce msg; - *msg.mutable_info() = toProto(*this->info); - msg.set_state(msgs::PeerAnnounce::CONNECTING); - this->announcePub.Publish(msg); - - this->heartbeatRunning = true; - this->heartbeatThread = std::thread([this]() - { - this->HeartbeatLoop(); - }); -} - -///////////////////////////////////////////////// -void PeerTracker::Disconnect() -{ - this->node.Unsubscribe("heartbeat"); - this->node.Unsubscribe("announce"); - - this->heartbeatRunning = false; - if (this->heartbeatThread.joinable()) - { - this->heartbeatThread.join(); - } - - if (this->info) - { - msgs::PeerAnnounce msg; - *msg.mutable_info() = toProto(*this->info); - msg.set_state(msgs::PeerAnnounce::DISCONNECTING); - - this->announcePub.Publish(msg); - this->info.reset(); - } -} - ///////////////////////////////////////////////// size_t PeerTracker::NumPeers() const { @@ -135,7 +120,7 @@ void PeerTracker::HeartbeatLoop() while (this->heartbeatRunning) { lastUpdateTime = Clock::now(); - this->heartbeatPub.Publish(toProto(*this->info)); + this->heartbeatPub.Publish(toProto(this->info)); std::vector toRemove; for (auto peer : this->peers) @@ -165,33 +150,16 @@ void PeerTracker::HeartbeatLoop() } } -///////////////////////////////////////////////// -void PeerTracker::AddPeer(const PeerInfo &_info) -{ - auto lock = PeerLock(this->peersMutex); - - auto peerState = PeerState(); - peerState.info = _info; - peerState.lastSeen = std::chrono::steady_clock::now(); - this->peers[_info.id] = peerState; -} - ///////////////////////////////////////////////// bool PeerTracker::RemovePeer(const PeerInfo &_info) { - if (!this->info) - { - ignerr << "Internal error: peer missing info." << std::endl; - return false; - } - auto lock = PeerLock(this->peersMutex); auto iter = this->peers.find(_info.id); if (iter == this->peers.end()) { igndbg << "Attempting to remove peer [" << _info.id << "] from [" - << this->info->id << "] but it wasn't connected" << std::endl; + << this->info.id << "] but it wasn't connected" << std::endl; return false; } @@ -205,7 +173,7 @@ void PeerTracker::OnPeerAnnounce(const msgs::PeerAnnounce &_announce) auto peer = fromProto(_announce.info()); // Skip announcements from self. - if (this->info && peer.id == this->info->id) + if (peer.id == this->info.id) return; switch (_announce.state()) @@ -216,9 +184,6 @@ void PeerTracker::OnPeerAnnounce(const msgs::PeerAnnounce &_announce) case msgs::PeerAnnounce::DISCONNECTING: this->OnPeerRemoved(peer); break; - case msgs::PeerAnnounce::ERROR: - this->OnPeerError(peer); - break; default: break; } @@ -229,20 +194,16 @@ void PeerTracker::OnPeerHeartbeat(const msgs::PeerInfo &_info) { auto peer = fromProto(_info); - if (!this->info) - { - return; - } - // Skip hearbeats from self. - if (peer.id == this->info->id) + if (peer.id == this->info.id) { return; } auto lock = PeerLock(this->peersMutex); - // We may have missed a peer announce, add it on heartbeat. + // If it doesn't exist, we may have missed a peer announce, + // so add it here on the heartbeat. if (this->peers.find(peer.id) == this->peers.end()) { this->OnPeerAdded(peer); @@ -256,20 +217,14 @@ void PeerTracker::OnPeerHeartbeat(const msgs::PeerInfo &_info) std::chrono::nanoseconds(_info.header().stamp().nsec())); } -///////////////////////////////////////////////// -void PeerTracker::OnPeerError(const PeerInfo &_info) -{ - auto success = this->RemovePeer(_info); - - // Emit event for any consumers - if (success && eventMgr) - eventMgr->Emit(_info); -} - ///////////////////////////////////////////////// void PeerTracker::OnPeerAdded(const PeerInfo &_info) { - this->AddPeer(_info); + auto lock = PeerLock(this->peersMutex); + auto peerState = PeerState(); + peerState.info = _info; + peerState.lastSeen = std::chrono::steady_clock::now(); + this->peers[_info.id] = peerState; // Emit event for any consumers if (eventMgr) diff --git a/src/network/PeerTracker.hh b/src/network/PeerTracker.hh index 10ad7766d5..16a466b74d 100644 --- a/src/network/PeerTracker.hh +++ b/src/network/PeerTracker.hh @@ -37,9 +37,6 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { // Network Events - /// \brief PeerError fired when there is an unexpected error in a peer - using PeerError = common::EventT; - /// \brief PeerAdded fired when a peer announces itself or detected via /// heartbeat using PeerAdded = common::EventT; @@ -61,9 +58,15 @@ namespace ignition public: using Duration = std::chrono::steady_clock::duration; /// \brief Constructor + /// + /// Announce the existence of a peer with given information _info, + /// and start executing heartbeats and peer tracking. + /// /// \param[in] _eventMgr Event Manager to emit network events on. /// \param[in] _options Advanced options for underlying ign-transport + /// \param[in] _info Peer information to announce public: explicit PeerTracker( + const PeerInfo &_info, EventManager *_eventMgr = nullptr, const NodeOptions &_options = NodeOptions()); @@ -93,33 +96,28 @@ namespace ignition /// \return Number of hearbeats before a peer is marked stale. public: size_t StaleMultiplier() const; + /// \brief Retrieve total number of detected peers in the network. + public: size_t NumPeers() const; + + /// \brief Retrieve number of detected peers in the network by role. + /// \param[in] _role Role of peers to enumerate + /// \return Number of peers with the given role. + public: size_t NumPeers(const NetworkRole &_role) const; + /// \brief Connect to the network graph. /// /// Announce the existence of a peer with given information _info, /// and start executing heartbeats and peer tracking. - /// \param[in] _info Peer information to announce - public: void Connect(std::shared_ptr _info); + private: void Connect(); /// \brief Disconnect from the network graph. /// /// Also announce that this peer is leaving the network. - public: void Disconnect(); - - /// \brief Retrieve number of detected peers in the network. - public: size_t NumPeers() const; - - /// \brief Retrieve number of detected peers in the network by role. - /// \param[in] _role Role of peers to enumerate - /// \return Number of peers with the given role. - public: size_t NumPeers(const NetworkRole &_role) const; + private: void Disconnect(); /// \brief Internal loop to announce and check stale peers. private: void HeartbeatLoop(); - /// \brief Helper function for adding a peer - /// \param[in] _info Peer to add - private: void AddPeer(const PeerInfo &_info); - /// \brief Helper function for removing a peer /// \param[in] _info Peer to remove /// \return True if successfully removed. @@ -133,10 +131,6 @@ namespace ignition /// \param[in] _info Heartbeat from another peer. private: void OnPeerHeartbeat(const msgs::PeerInfo &_info); - /// \brief Callback for when peer errors are detected. - /// \param[in] _info Info from peer which had an error. - private: void OnPeerError(const PeerInfo &_info); - /// \brief Callback for when a peer is added. /// \param[in] _info Info from peer which was added. private: void OnPeerAdded(const PeerInfo &_info); @@ -149,15 +143,6 @@ namespace ignition /// \param[in] _info Info from peer which is stale. private: void OnPeerStale(const PeerInfo &_info); - /// \brief Transport node - private: ignition::transport::Node node; - - /// \brief Heartbeat publisher - private: ignition::transport::Node::Publisher heartbeatPub; - - /// \brief Announcement publisher - private: ignition::transport::Node::Publisher announcePub; - /// \brief Information about discovered peers struct PeerState { @@ -196,11 +181,22 @@ namespace ignition /// \brief Timeout to mark a peer as stale. private: size_t staleMultiplier {5}; + /// \brief Peer information that this tracker announces. + private: PeerInfo info; + /// \brief Event manager instance to be used to emit network events. private: EventManager *eventMgr; - /// \brief Peer information that this tracker announces. - private: std::shared_ptr info; + /// \brief Transport node + private: ignition::transport::Node node; + + /// \brief Heartbeat publisher + private: ignition::transport::Node::Publisher heartbeatPub; + + /// \brief Announcement publisher + private: ignition::transport::Node::Publisher announcePub; + + }; } } // namespace gazebo diff --git a/src/network/PeerTracker_TEST.cc b/src/network/PeerTracker_TEST.cc index 62bb3f0c8d..d52170e7ec 100644 --- a/src/network/PeerTracker_TEST.cc +++ b/src/network/PeerTracker_TEST.cc @@ -44,51 +44,32 @@ TEST(PeerTracker, PeerTracker) peers--; }); - auto tracker1 = PeerTracker(&eventMgr); - auto tracker2 = PeerTracker(); - auto tracker3 = PeerTracker(); - auto tracker4 = PeerTracker(); - auto tracker5 = PeerTracker(); - auto tracker6 = PeerTracker(); - - auto info1 = std::make_shared(); - info1->role = NetworkRole::SimulationPrimary; - - auto info2 = std::make_shared(); - info2->role = NetworkRole::SimulationSecondary; - - auto info3 = std::make_shared(); - info3->role = NetworkRole::SimulationSecondary; - - auto info4 = std::make_shared(); - info4->role = NetworkRole::ReadOnly; - - auto info5 = std::make_shared(); - info5->role = NetworkRole::ReadOnly; - - auto info6 = std::make_shared(); - info6->role = NetworkRole::None; - - tracker1.Connect(info1); + auto tracker1 = std::make_shared( + PeerInfo(NetworkRole::SimulationPrimary), &eventMgr); EXPECT_EQ(0, peers); - tracker2.Connect(info2); + auto tracker2 = std::make_shared( + PeerInfo(NetworkRole::SimulationSecondary)); std::this_thread::sleep_for(std::chrono::milliseconds(10)); EXPECT_EQ(1, peers); - tracker3.Connect(info3); + auto tracker3 = std::make_shared( + PeerInfo(NetworkRole::SimulationSecondary)); std::this_thread::sleep_for(std::chrono::milliseconds(10)); EXPECT_EQ(2, peers); - tracker4.Connect(info4); + auto tracker4 = std::make_shared( + PeerInfo(NetworkRole::ReadOnly)); std::this_thread::sleep_for(std::chrono::milliseconds(10)); EXPECT_EQ(3, peers); - tracker5.Connect(info5); + auto tracker5 = std::make_shared( + PeerInfo(NetworkRole::ReadOnly)); std::this_thread::sleep_for(std::chrono::milliseconds(10)); EXPECT_EQ(4, peers); - tracker6.Connect(info6); + auto tracker6 = std::make_shared( + PeerInfo(NetworkRole::None)); std::this_thread::sleep_for(std::chrono::milliseconds(10)); EXPECT_EQ(5, peers); @@ -96,58 +77,58 @@ TEST(PeerTracker, PeerTracker) std::this_thread::sleep_for(std::chrono::milliseconds(100)); // All counts exclude self. - EXPECT_EQ(5u, tracker1.NumPeers()); - EXPECT_EQ(5u, tracker2.NumPeers()); - EXPECT_EQ(5u, tracker3.NumPeers()); - EXPECT_EQ(5u, tracker4.NumPeers()); - EXPECT_EQ(5u, tracker5.NumPeers()); - - EXPECT_EQ(0u, tracker1.NumPeers(NetworkRole::SimulationPrimary)); - EXPECT_EQ(2u, tracker1.NumPeers(NetworkRole::SimulationSecondary)); - EXPECT_EQ(2u, tracker1.NumPeers(NetworkRole::ReadOnly)); - EXPECT_EQ(1u, tracker1.NumPeers(NetworkRole::None)); - - EXPECT_EQ(1u, tracker2.NumPeers(NetworkRole::SimulationPrimary)); - EXPECT_EQ(1u, tracker2.NumPeers(NetworkRole::SimulationSecondary)); - EXPECT_EQ(2u, tracker2.NumPeers(NetworkRole::ReadOnly)); - EXPECT_EQ(1u, tracker2.NumPeers(NetworkRole::None)); - - EXPECT_EQ(1u, tracker3.NumPeers(NetworkRole::SimulationPrimary)); - EXPECT_EQ(1u, tracker3.NumPeers(NetworkRole::SimulationSecondary)); - EXPECT_EQ(2u, tracker3.NumPeers(NetworkRole::ReadOnly)); - EXPECT_EQ(1u, tracker3.NumPeers(NetworkRole::None)); - - EXPECT_EQ(1u, tracker4.NumPeers(NetworkRole::SimulationPrimary)); - EXPECT_EQ(2u, tracker4.NumPeers(NetworkRole::SimulationSecondary)); - EXPECT_EQ(1u, tracker4.NumPeers(NetworkRole::ReadOnly)); - EXPECT_EQ(1u, tracker4.NumPeers(NetworkRole::None)); - - EXPECT_EQ(1u, tracker5.NumPeers(NetworkRole::SimulationPrimary)); - EXPECT_EQ(2u, tracker5.NumPeers(NetworkRole::SimulationSecondary)); - EXPECT_EQ(1u, tracker5.NumPeers(NetworkRole::ReadOnly)); - EXPECT_EQ(1u, tracker5.NumPeers(NetworkRole::None)); - - tracker6.Disconnect(); + EXPECT_EQ(5u, tracker1->NumPeers()); + EXPECT_EQ(5u, tracker2->NumPeers()); + EXPECT_EQ(5u, tracker3->NumPeers()); + EXPECT_EQ(5u, tracker4->NumPeers()); + EXPECT_EQ(5u, tracker5->NumPeers()); + + EXPECT_EQ(0u, tracker1->NumPeers(NetworkRole::SimulationPrimary)); + EXPECT_EQ(2u, tracker1->NumPeers(NetworkRole::SimulationSecondary)); + EXPECT_EQ(2u, tracker1->NumPeers(NetworkRole::ReadOnly)); + EXPECT_EQ(1u, tracker1->NumPeers(NetworkRole::None)); + + EXPECT_EQ(1u, tracker2->NumPeers(NetworkRole::SimulationPrimary)); + EXPECT_EQ(1u, tracker2->NumPeers(NetworkRole::SimulationSecondary)); + EXPECT_EQ(2u, tracker2->NumPeers(NetworkRole::ReadOnly)); + EXPECT_EQ(1u, tracker2->NumPeers(NetworkRole::None)); + + EXPECT_EQ(1u, tracker3->NumPeers(NetworkRole::SimulationPrimary)); + EXPECT_EQ(1u, tracker3->NumPeers(NetworkRole::SimulationSecondary)); + EXPECT_EQ(2u, tracker3->NumPeers(NetworkRole::ReadOnly)); + EXPECT_EQ(1u, tracker3->NumPeers(NetworkRole::None)); + + EXPECT_EQ(1u, tracker4->NumPeers(NetworkRole::SimulationPrimary)); + EXPECT_EQ(2u, tracker4->NumPeers(NetworkRole::SimulationSecondary)); + EXPECT_EQ(1u, tracker4->NumPeers(NetworkRole::ReadOnly)); + EXPECT_EQ(1u, tracker4->NumPeers(NetworkRole::None)); + + EXPECT_EQ(1u, tracker5->NumPeers(NetworkRole::SimulationPrimary)); + EXPECT_EQ(2u, tracker5->NumPeers(NetworkRole::SimulationSecondary)); + EXPECT_EQ(1u, tracker5->NumPeers(NetworkRole::ReadOnly)); + EXPECT_EQ(1u, tracker5->NumPeers(NetworkRole::None)); + + tracker6.reset(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(4, peers); - tracker5.Disconnect(); + tracker5.reset(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(3, peers); - tracker4.Disconnect(); + tracker4.reset(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(2, peers); - tracker3.Disconnect(); + tracker3.reset(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(1, peers); - tracker2.Disconnect(); + tracker2.reset(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(0, peers); - tracker1.Disconnect(); + tracker1.reset(); } ////////////////////////////////////////////////// @@ -157,36 +138,30 @@ TEST(PeerTracker, PeerTrackerStale) EventManager eventMgr; // Tracker with artificially short timeout. - auto tracker1 = PeerTracker(&eventMgr); - tracker1.SetHeartbeatPeriod(std::chrono::milliseconds(10)); - tracker1.SetStaleMultiplier(1); - - auto tracker2 = PeerTracker(&eventMgr); - tracker2.SetHeartbeatPeriod(std::chrono::milliseconds(100)); + auto tracker1 = std::make_shared( + PeerInfo(NetworkRole::SimulationPrimary), &eventMgr); + tracker1->SetHeartbeatPeriod(std::chrono::milliseconds(10)); + tracker1->SetStaleMultiplier(1); - auto info1 = std::make_shared(); - info1->role = NetworkRole::SimulationPrimary; - - auto info2 = std::make_shared(); - info2->role = NetworkRole::SimulationSecondary; + auto info2 = PeerInfo(NetworkRole::SimulationSecondary); std::atomic stalePeers = 0; auto stale = eventMgr.Connect([&](PeerInfo _peer) { - EXPECT_EQ(_peer.id, info2->id); + EXPECT_EQ(_peer.id, info2.id); stalePeers++; }); - tracker1.Connect(info1); - tracker2.Connect(info2); + auto tracker2 = std::make_shared(info2); + tracker2->SetHeartbeatPeriod(std::chrono::milliseconds(100)); std::this_thread::sleep_for(std::chrono::milliseconds(100)); EXPECT_EQ(1, stalePeers); // Expect while tracker1 can see tracker2, the opposite is // not true. - EXPECT_EQ(0u, tracker1.NumPeers()); - EXPECT_EQ(1u, tracker2.NumPeers()); + EXPECT_EQ(0u, tracker1->NumPeers()); + EXPECT_EQ(1u, tracker2->NumPeers()); // PeerTracker will print a debug message when DISCONNECTING message is // received from stale peer @@ -200,19 +175,13 @@ TEST(PeerTracker, Partitioned) auto options1 = ignition::transport::NodeOptions(); options1.SetPartition("p1"); - auto tracker1 = PeerTracker(&eventMgr, options1); - - auto info1 = std::make_shared(); - info1->role = NetworkRole::SimulationPrimary; - tracker1.Connect(info1); + auto tracker1 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr, options1); auto options2 = ignition::transport::NodeOptions(); options2.SetPartition("p2"); - auto tracker2 = PeerTracker(&eventMgr, options2); - - auto info2 = std::make_shared(); - info2->role = NetworkRole::SimulationPrimary; - tracker2.Connect(info2); + auto tracker2 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr, options2); // Allow all the heartbeats to propagate std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -221,17 +190,11 @@ TEST(PeerTracker, Partitioned) EXPECT_EQ(0u, tracker1.NumPeers()); EXPECT_EQ(0u, tracker2.NumPeers()); - auto tracker3 = PeerTracker(&eventMgr, options1); - - auto info3 = std::make_shared(); - info3->role = NetworkRole::SimulationSecondary; - tracker3.Connect(info3); - - auto tracker4 = PeerTracker(&eventMgr, options2); + auto tracker3 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr, options1); - auto info4 = std::make_shared(); - info4->role = NetworkRole::SimulationSecondary; - tracker4.Connect(info4); + auto tracker4 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr, options2); // Allow some time for heartbeats to propagate // TODO(mjcarroll): Send heartbeats on announce @@ -252,19 +215,13 @@ TEST(PeerTracker, Namespaced) auto options1 = ignition::transport::NodeOptions(); options1.SetNameSpace("ns1"); - auto tracker1 = PeerTracker(&eventMgr, options1); - - auto info1 = std::make_shared(); - info1->role = NetworkRole::SimulationPrimary; - tracker1.Connect(info1); + auto tracker1 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr, options1); auto options2 = ignition::transport::NodeOptions(); options2.SetNameSpace("ns2"); - auto tracker2 = PeerTracker(&eventMgr, options2); - - auto info2 = std::make_shared(); - info2->role = NetworkRole::SimulationPrimary; - tracker2.Connect(info2); + auto tracker2 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr, options2); // Allow some time for heartbeats to propagate std::this_thread::sleep_for(std::chrono::milliseconds(110)); @@ -273,17 +230,11 @@ TEST(PeerTracker, Namespaced) EXPECT_EQ(0u, tracker1.NumPeers()); EXPECT_EQ(0u, tracker2.NumPeers()); - auto tracker3 = PeerTracker(&eventMgr, options1); - - auto info3 = std::make_shared(); - info3->role = NetworkRole::SimulationSecondary; - tracker3.Connect(info3); - - auto tracker4 = PeerTracker(&eventMgr, options2); + auto tracker3 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr, options1); - auto info4 = std::make_shared(); - info4->role = NetworkRole::SimulationSecondary; - tracker4.Connect(info4); + auto tracker4 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr, options2); // Allow some time for heartbeats to propagate // TODO(mjcarroll): Send heartbeats on announce @@ -305,16 +256,12 @@ TEST(PeerTracker, PartitionedEnv) EventManager eventMgr; setenv("IGN_PARTITION", "p1", 1); - auto tracker1 = PeerTracker(&eventMgr); - auto info1 = std::make_shared(); - info1->role = NetworkRole::SimulationPrimary; - tracker1.Connect(info1); + auto tracker1 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr); setenv("IGN_PARTITION", "p2", 1); - auto tracker2 = PeerTracker(&eventMgr); - auto info2 = std::make_shared(); - info2->role = NetworkRole::SimulationPrimary; - tracker2.Connect(info2); + auto tracker2 = PeerTracker( + {NetworkRole::SimulationPrimary}, &eventMgr); // Allow some time for heartbeats to propagate std::this_thread::sleep_for(std::chrono::milliseconds(110)); @@ -324,16 +271,12 @@ TEST(PeerTracker, PartitionedEnv) EXPECT_EQ(0u, tracker2.NumPeers()); setenv("IGN_PARTITION", "p1", 1); - auto tracker3 = PeerTracker(&eventMgr); - auto info3 = std::make_shared(); - info3->role = NetworkRole::SimulationSecondary; - tracker3.Connect(info3); + auto tracker3 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr); setenv("IGN_PARTITION", "p2", 1); - auto tracker4 = PeerTracker(&eventMgr); - auto info4 = std::make_shared(); - info4->role = NetworkRole::SimulationSecondary; - tracker4.Connect(info4); + auto tracker4 = PeerTracker( + {NetworkRole::SimulationSecondary}, &eventMgr); // Allow some time for heartbeats to propagate // TODO(mjcarroll): Send heartbeats on announce