abstract_base.h
Go to the documentation of this file.
1 #ifndef ABSTRACT_BASE_
2 #define ABSTRACT_BASE_
3 
4 #include "ros/ros.h"
5 #include <xmlrpcpp/XmlRpc.h>
6 #include <tf2/LinearMath/Transform.h>
7 
8 #include "octomap/octomap.h"
9 #include <pcl/point_cloud.h>
10 #include <pcl/octree/octree.h>
11 
12 
13 #include <ros/package.h>
14 #include <yaml-cpp/yaml.h>
15 #include <fstream>
17 
18 #include "robot/abstract_robot.h"
20 
22 class Abstract_robot;
23 
24 
26 
30  protected:
31  std::shared_ptr<ros::NodeHandle> nh_;
32 
33  std::vector<tf2::Transform> map_;
34  std::vector<tf2::Transform> inv_map_;
35  std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>> task_space_;
36  std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>> target_cloud_;
37 
38  std::shared_ptr<Abstract_base_implementation> implementation_;
39 
40  public:
42 
45  Abstract_base(std::shared_ptr<ros::NodeHandle> const& d) : nh_(d){};
46 
48 
52 
54 
57  inline void set_implementation(std::shared_ptr<Abstract_base_implementation> some_implememntation) {implementation_ = some_implememntation;}
58 
60 
63  inline std::vector<tf2::Transform>& inv_map() {return inv_map_;}
64 
66 
69  inline void set_inv_map(std::vector<tf2::Transform>& list) {inv_map_ = list;}
70 
72 
75  inline std::vector<tf2::Transform>& map() {return map_;}
76 
78 
81  inline void set_map(std::vector<tf2::Transform>& list) {map_ = list;}
82 
84 
87  inline std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& task_space() {return task_space_;}
88 
90 
93  inline void set_task_space(std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& s_trans) {task_space_ = s_trans;}
94 
95 
97 
100  inline std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& target_cloud () { return target_cloud_;}
101 
103 
106  inline void set_target_cloud(std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& cloud) {target_cloud_ = cloud;}
107 
109 
113  static std::vector<pcl::PointXYZ> create_pcl_box();
114 
116 
119  virtual void write_task(Abstract_robot* robot)=0;
120 
122 
126  virtual std::map<const std::string, std::vector<pcl::PointXYZ>> base_calculation()=0;
127 };
128 #endif
Abstract_base::base_calculation
virtual std::map< const std::string, std::vector< pcl::PointXYZ > > base_calculation()=0
pure virtual template methode
Abstract_base::nh_
std::shared_ptr< ros::NodeHandle > nh_
Ros nodehandle object.
Definition: abstract_base.h:31
Abstract_base::set_inv_map
void set_inv_map(std::vector< tf2::Transform > &list)
Set inverse map structure.
Definition: abstract_base.h:69
Abstract_base::target_cloud
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > & target_cloud()
Get task cloud.
Definition: abstract_base.h:100
Abstract_base::implementation
Abstract_base_implementation * implementation()
Get used implementation.
Definition: abstract_base.h:51
Abstract_base::task_space_
std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion > > > > task_space_
Drop-off locations with their grasp orientations, mapped to a robot.
Definition: abstract_base.h:35
Abstract_base::map_
std::vector< tf2::Transform > map_
Reachability map structure of a robot.
Definition: abstract_base.h:33
abstract_param_reader.h
Abstract_base::task_space
std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion > > > > & task_space()
Get task space.
Definition: abstract_base.h:87
Abstract_base::inv_map
std::vector< tf2::Transform > & inv_map()
Get inverse map structure.
Definition: abstract_base.h:63
abstract_robot.h
Abstract_base
Abstract base class.
Definition: abstract_base.h:29
Abstract_base::write_task
virtual void write_task(Abstract_robot *robot)=0
write trask
Abstract_base::create_pcl_box
static std::vector< pcl::PointXYZ > create_pcl_box()
box discretization
Abstract_base::target_cloud_
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > target_cloud_
Pointcloud structure, mapped to robot.
Definition: abstract_base.h:36
object_data
Definition: abstract_param_reader.h:13
Abstract_base::set_map
void set_map(std::vector< tf2::Transform > &list)
Set map structure.
Definition: abstract_base.h:81
Abstract_base::set_implementation
void set_implementation(std::shared_ptr< Abstract_base_implementation > some_implememntation)
Set used implementation.
Definition: abstract_base.h:57
Abstract_base_implementation
abstract base implementation
Definition: abstract_base_implementation.h:11
Abstract_base::map
std::vector< tf2::Transform > & map()
Get map structure.
Definition: abstract_base.h:75
Abstract_base::set_task_space
void set_task_space(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &s_trans)
Set task space.
Definition: abstract_base.h:93
Abstract_base::implementation_
std::shared_ptr< Abstract_base_implementation > implementation_
refined implementation
Definition: abstract_base.h:38
Abstract_base::inv_map_
std::vector< tf2::Transform > inv_map_
Inversion of reachability map structure.
Definition: abstract_base.h:34
Abstract_base::set_target_cloud
void set_target_cloud(std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr >> &cloud)
Set task cloud.
Definition: abstract_base.h:106
Abstract_robot
Definition: impl/abstract_robot.h:25
Abstract_base::Abstract_base
Abstract_base(std::shared_ptr< ros::NodeHandle > const &d)
Abstract base constructor.
Definition: abstract_base.h:45
abstract_base_implementation.h


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