runtime_core.h
Go to the documentation of this file.
1 
23 #ifndef RUNTIME_CORE_H_
24 #define RUNTIME_CORE_H_
25 
26 #include <iostream>
27 #include <unistd.h>
28 #include <ros/ros.h>
29 #include <pluginlib/class_loader.h>
30 
31 #include "micros_swarm/singleton.h"
33 #include "micros_swarm/serialize.h"
39 
40 namespace micros_swarm{
41 
43  {
44  public:
48  std::string comm_type_;
53 
58 
63  int robot_id_;
65 
66  boost::thread* spin_thread_;
67 
68  RuntimeCore();
69  ~RuntimeCore();
70  void initialize();
71  void shutdown();
72  void setParameters();
73  void spin_msg_queue();
76  void barrier_check(const ros::TimerEvent&);
77  };
78 };
79 
80 #endif
pluginlib::ClassLoader< micros_swarm::CommInterface > ci_loader_
Definition: runtime_core.h:49
void barrier_check(const ros::TimerEvent &)
boost::thread * spin_thread_
Definition: runtime_core.h:66
boost::shared_ptr< RuntimeHandle > rth_
Definition: runtime_core.h:46
ros::Timer publish_swarm_list_timer_
Definition: runtime_core.h:55
ros::NodeHandle node_handle_
Definition: runtime_core.h:45
boost::shared_ptr< CommInterface > communicator_
Definition: runtime_core.h:47
ros::Timer publish_robot_base_timer_
Definition: runtime_core.h:54
boost::shared_ptr< micros_swarm::MsgQueueManager > msg_queue_manager_
Definition: runtime_core.h:50
boost::shared_ptr< micros_swarm::PacketParser > parser_
Definition: runtime_core.h:51
void publish_robot_base(const ros::TimerEvent &)
void publish_swarm_list(const ros::TimerEvent &)
boost::shared_ptr< AppManager > app_manager_
Definition: runtime_core.h:52


micros_swarm
Author(s):
autogenerated on Mon Jun 10 2019 14:02:06