impl/abstract_mediator.h
Go to the documentation of this file.
1 #ifndef ABSTRACT_MEDIATOR_
2 #define ABSTRACT_MEDIATOR_
3 
4 #include <ros/ros.h>
5 #include "impl/abstract_robot.h"
7 #include "impl/robot.h"
8 #include "reader/wing_reader.h"
9 
10 
11 #include <ros/package.h>
12 #include <yaml-cpp/yaml.h>
13 #include <fstream>
14 
15 #include <octomap/octomap.h>
16 #include <pcl/point_cloud.h>
17 #include <pcl/octree/octree.h>
18 
19 
20 
21 #define box_size tf2::Vector3(0.0318f, 0.0636f, 0.091f)
22 #define R_POS tf2::Vector3(0,0.6525f,0.4425f -0.005f)
23 #define L_POS tf2::Vector3(0,-0.6525f,0.4425f -0.005f)
24 #define M_POS tf2::Vector3(0.6525f,0,0.4425f-0.005f)
25 
26 struct wing_BP {
27  std::string name_;
28  tf2::Transform pos_;
29  tf2::Vector3 size_;
30 };
31 
32 
34  protected:
35  std::vector<Abstract_robot*> robots_;
36  std::vector<std::vector<tf2::Transform>> objects_;
37  std::vector<std::vector<std::vector<tf2::Transform>>> relative_bounds_;
38  ros::Publisher* pub_;
39  std::vector<std::vector<pcl::PointXYZ>> result_vector_;
40  std::vector<std::vector<Abstract_robot_element*>> wings_;
41  std::string dirname_;
42 
43 
44 
45 
46 
47  public:
48  Abstract_mediator(std::vector<std::vector<tf2::Transform>> objects, ros::Publisher* pub) : objects_(objects), pub_(pub){
49  }
50 
51  inline void set_result_vector(std::vector<std::vector<pcl::PointXYZ>>& res) {result_vector_ = res;}
52  inline std::vector<std::vector<Abstract_robot_element*>> wings() {return wings_;}
53  inline std::vector<std::vector<pcl::PointXYZ>>& result_vector() {return result_vector_;}
54  inline std::vector<Abstract_robot*> robots(){return robots_;}
55 
56 
57  inline void set_dirname(std::string& dirn) {dirname_ = dirn;}
58  inline std::string& dirname() {return dirname_;}
59 
60 
61 
62  pcl::PointCloud< pcl::PointXYZ >::Ptr vector_to_cloud(std::vector<pcl::PointXYZ>& vector);
63  std::vector<pcl::PointXYZ> generate_Ground(const tf2::Vector3 origin, const float diameter, float resolution);
64 
65  virtual void connect_robots(Abstract_robot* robot)=0;
66  virtual void set_wings(std::vector<std::pair<std::vector<object_data>, int>>& wbp)=0;
67  virtual bool check_collision( const int& robot)=0;
68  virtual void mediate()=0;
69  virtual void build_wings(std::bitset<3>& wing, int& robot)=0;
70 
71 
72 };
73 
74 
75 #endif
wing_BP::pos_
tf2::Transform pos_
Definition: impl/abstract_mediator.h:28
Abstract_mediator::Abstract_mediator
Abstract_mediator(std::vector< std::vector< tf2::Transform >> objects, ros::Publisher *pub)
Definition: impl/abstract_mediator.h:48
Abstract_mediator::relative_bounds_
std::vector< std::vector< std::vector< tf2::Transform > > > relative_bounds_
total bound a workspace
Definition: impl/abstract_mediator.h:37
robot.h
Abstract_mediator::robots
std::vector< Abstract_robot * > robots()
Definition: impl/abstract_mediator.h:54
abstract_robot_element.h
Abstract_mediator::pub_
ros::Publisher * pub_
Definition: impl/abstract_mediator.h:38
Abstract_mediator
Abstract mediator.
Definition: impl/abstract_mediator.h:33
wing_BP
Definition: impl/abstract_mediator.h:26
Abstract_mediator::check_collision
virtual bool check_collision(const int &robot)=0
Abstract_mediator::set_dirname
void set_dirname(std::string &dirn)
Definition: impl/abstract_mediator.h:57
wing_BP::name_
std::string name_
Definition: impl/abstract_mediator.h:27
Abstract_mediator::wings_
std::vector< std::vector< Abstract_robot_element * > > wings_
Definition: impl/abstract_mediator.h:40
Abstract_mediator::vector_to_cloud
pcl::PointCloud< pcl::PointXYZ >::Ptr vector_to_cloud(std::vector< pcl::PointXYZ > &vector)
Definition: impl/abstract_mediator.cpp:16
wing_BP::size_
tf2::Vector3 size_
Definition: impl/abstract_mediator.h:29
Abstract_mediator::result_vector_
std::vector< std::vector< pcl::PointXYZ > > result_vector_
Definition: impl/abstract_mediator.h:39
Abstract_mediator::dirname_
std::string dirname_
Dirname of the reference protobuff.
Definition: impl/abstract_mediator.h:41
abstract_robot.h
Abstract_mediator::result_vector
std::vector< std::vector< pcl::PointXYZ > > & result_vector()
Definition: impl/abstract_mediator.h:53
Abstract_mediator::mediate
virtual void mediate()=0
Abstract_mediator::connect_robots
virtual void connect_robots(Abstract_robot *robot)=0
Abstract_mediator::wings
std::vector< std::vector< Abstract_robot_element * > > wings()
Definition: impl/abstract_mediator.h:52
wing_reader.h
Abstract_mediator::generate_Ground
std::vector< pcl::PointXYZ > generate_Ground(const tf2::Vector3 origin, const float diameter, float resolution)
Definition: impl/abstract_mediator.cpp:4
Abstract_mediator::set_wings
virtual void set_wings(std::vector< std::pair< std::vector< object_data >, int >> &wbp)=0
Abstract_mediator::objects_
std::vector< std::vector< tf2::Transform > > objects_
Definition: impl/abstract_mediator.h:36
Abstract_mediator::set_result_vector
void set_result_vector(std::vector< std::vector< pcl::PointXYZ >> &res)
Definition: impl/abstract_mediator.h:51
Abstract_mediator::build_wings
virtual void build_wings(std::bitset< 3 > &wing, int &robot)=0
Abstract_mediator::dirname
std::string & dirname()
Definition: impl/abstract_mediator.h:58
Abstract_mediator::robots_
std::vector< Abstract_robot * > robots_
Definition: impl/abstract_mediator.h:35
Abstract_robot
Definition: impl/abstract_robot.h:25


multi_cell_builder
Author(s): MA
autogenerated on Thu Jan 12 2023 23:45:43