Go to the documentation of this file. 1 #ifndef ABSTRACT_MEDIATOR_
2 #define ABSTRACT_MEDIATOR_
15 #include <ros/package.h>
16 #include <yaml-cpp/yaml.h>
19 #include <octomap/octomap.h>
20 #include <pcl/point_cloud.h>
21 #include <pcl/octree/octree.h>
35 std::shared_ptr<ros::NodeHandle>
nh_;
37 std::vector<std::unique_ptr<Abstract_robot_decorator>>
robots_;
41 std::map<const std::string, std::vector<std::unique_ptr<Abstract_robot_element>>>
wings_;
62 inline std::map<const std::string, std::vector<std::unique_ptr<Abstract_robot_element>>>&
wings() {
return wings_;}
74 inline std::vector<std::unique_ptr<Abstract_robot_decorator>>&
robots(){
return robots_;}
95 pcl::PointCloud< pcl::PointXYZ >::Ptr
vector_to_cloud(std::vector<pcl::PointXYZ>& vector);
101 virtual void connect_robots(std::unique_ptr<Abstract_robot_decorator> robot)=0;
118 virtual void build_wings(std::bitset<3>& wing,
int& robot)=0;