Go to the documentation of this file. 1 #ifndef BASE_CALCULATION_MEDIATOR_
2 #define BASE_CALCULATION_MEDIATOR_
5 #include <ros/package.h>
6 #include <yaml-cpp/yaml.h>
24 std::unique_ptr<ros::Publisher>
pub_;
29 std::map<const std::string, std::vector<pcl::PointXYZ>>
grounds_;
30 std::vector<std::vector<std::unique_ptr<Abstract_robot_element>>>
wings_;
48 std::vector<pcl::PointXYZ>
generate_grounds(
const tf2::Vector3 origin,
const float diameter,
float resolution);
92 void calculate(std::vector<tf2::Transform>& ground_per_robot);
123 void connect_robots(std::unique_ptr<Abstract_robot_decorator> robot)
override;