runtime_core.h
Go to the documentation of this file.
00001 
00023 #ifndef RUNTIME_CORE_H_
00024 #define RUNTIME_CORE_H_
00025 
00026 #include <iostream>
00027 #include <unistd.h>
00028 #include <ros/ros.h>
00029 #include <pluginlib/class_loader.h>
00030 
00031 #include "micros_swarm/singleton.h"
00032 #include "micros_swarm/packet_type.h"
00033 #include "micros_swarm/serialize.h"
00034 #include "micros_swarm/runtime_handle.h"
00035 #include "micros_swarm/comm_interface.h"
00036 #include "micros_swarm/msg_queue_manager.h"
00037 #include "micros_swarm/packet_parser.h"
00038 #include "micros_swarm/app_manager.h"
00039 
00040 namespace micros_swarm{
00041 
00042     class RuntimeCore
00043     {
00044     public:
00045         ros::NodeHandle node_handle_;
00046         boost::shared_ptr<RuntimeHandle> rth_;
00047         boost::shared_ptr<CommInterface> communicator_;
00048         std::string comm_type_;
00049         pluginlib::ClassLoader<micros_swarm::CommInterface> ci_loader_;
00050         boost::shared_ptr<micros_swarm::MsgQueueManager> msg_queue_manager_;
00051         boost::shared_ptr<micros_swarm::PacketParser> parser_;
00052         boost::shared_ptr<AppManager> app_manager_;
00053 
00054         ros::Timer publish_robot_base_timer_;
00055         ros::Timer publish_swarm_list_timer_;
00056         ros::Timer barrier_timer_;
00057         ros::Timer spin_timer_;
00058 
00059         double publish_robot_base_duration_;
00060         double publish_swarm_list_duration_;
00061         double default_neighbor_distance_;
00062         int total_robot_numbers_;
00063         int robot_id_;
00064         int worker_num_;
00065 
00066         boost::thread* spin_thread_;
00067 
00068         RuntimeCore();
00069         ~RuntimeCore();
00070         void initialize();
00071         void shutdown();
00072         void setParameters();
00073         void spin_msg_queue();
00074         void publish_robot_base(const ros::TimerEvent&);
00075         void publish_swarm_list(const ros::TimerEvent&);
00076         void barrier_check(const ros::TimerEvent&);
00077     };
00078 };
00079 
00080 #endif


micros_swarm
Author(s):
autogenerated on Thu Jun 6 2019 18:52:14