Go to the documentation of this file. 1 #ifndef ABSTRACT_MEDIATOR_
2 #define ABSTRACT_MEDIATOR_
5 #include <ros/package.h>
6 #include <yaml-cpp/yaml.h>
7 #include <octomap/octomap.h>
8 #include <pcl/point_cloud.h>
9 #include <pcl/octree/octree.h>
45 std::shared_ptr<ros::NodeHandle>
nh_;
47 std::map<std::string, std::unique_ptr<AbstractRobotDecorator>>
robots_;
51 std::map<const std::string, std::vector<std::unique_ptr<AbstractRobotElement>>>
wings_;
77 inline std::map<const std::string, std::vector<std::unique_ptr<AbstractRobotElement>>>&
wings() {
return wings_;}
89 inline std::map<std::string, std::unique_ptr<AbstractRobotDecorator>>&
robots(){
return robots_;}
110 pcl::PointCloud< pcl::PointXYZ >::Ptr
vector2cloud(std::vector<pcl::PointXYZ>& vector);
116 virtual void connectRobots(std::unique_ptr<AbstractRobotDecorator> robot)=0;