Swarm-SLAM  1.0.0
C-SLAM Framework
simulated_rendezvous.h
Go to the documentation of this file.
1 #ifndef _CSLAM_SIMULATED_RENDEZVOUS_H_
2 #define _CSLAM_SIMULATED_RENDEZVOUS_H_
3 
4 #include <vector>
5 #include <string>
6 #include <iostream>
7 #include <fstream>
8 
9 #include <rclcpp/rclcpp.hpp>
10 
11 #include <ctime>
12 #include <chrono>
13 #include <iomanip>
14 
15 namespace cslam
16 {
17 
19  {
25  public:
26  SimulatedRendezVous(std::shared_ptr<rclcpp::Node> &node, const std::string& schedule_file, const unsigned int &robot_id);
27 
33  bool is_alive();
34 
35  private:
36  std::shared_ptr<rclcpp::Node> node_;
37  unsigned int robot_id_;
38  std::vector<std::pair<uint64_t, uint64_t>> rendezvous_ranges_;
39  bool enabled_;
40  };
41 
42 } // namespace cslam
43 
44 #endif // _CSLAM_SIMULATED_RENDEZVOUS_H_
bool is_alive()
Check if the robot is alive (aka in the rendez-vous schedule)
SimulatedRendezVous(std::shared_ptr< rclcpp::Node > &node, const std::string &schedule_file, const unsigned int &robot_id)
Rendez-vous simulation. Reads a config file indicating when the robot should be considered alive.
Definition: __init__.py:1