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>
25 std::unique_ptr<ros::Publisher>
pub_;
26 std::map<const std::string, std::vector<pcl::PointXYZ>>
grounds_;
27 std::vector<std::vector<std::unique_ptr<AbstractRobotElement>>>
wings_;
28 std::vector<std::vector<std::vector<protobuf_entry>>>
protobuf_;
47 void generateGrounds(
const tf2::Vector3 origin,
const float diameter,
float resolution);
54 void approximation(std::map<
const std::string, std::vector<tf2::Transform>>& workcell, std::vector<protobuf_entry>& wc_solution);
62 void writeFile(std::vector<protobuf_entry>& wc_solution);
79 void calculate(std::map<
const std::string, std::vector<tf2::Transform>>& workcell);
92 bool checkCollision(
const std::string& robot, std::bitset<3>& panel_mask,
bool& workload, std::vector<object_data>& ts);
105 void connectRobots(std::unique_ptr<AbstractRobotDecorator> robot)
override;