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 #include <octomap/octomap.h>
8 #include <pcl/point_cloud.h>
9 #include <pcl/octree/octree.h>
10 #include <ros/package.h>
11 #include <yaml-cpp/yaml.h>
12 
13 #include <fstream>
14 
16 #include "robot/abstract_robot.h"
18 
20 class AbstractRobot;
21 
22 
24 
28  protected:
29  std::shared_ptr<ros::NodeHandle> nh_;
30  std::vector<tf2::Transform> map_;
31  std::vector<tf2::Transform> inv_map_;
32  std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>> task_space_;
33  std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>> target_cloud_;
34  std::map<const std::string, std::vector<pcl::PointXYZ>> result_;
35 
36 
37  std::shared_ptr<AbstractBaseImplementation> implementation_;
38 
39  public:
41 
44  AbstractBase(std::shared_ptr<ros::NodeHandle> const& nh) : nh_(nh){};
45 
46 
48  inline void setImplementation(std::shared_ptr<AbstractBaseImplementation> implementation) {implementation_ = implementation;}
49  inline std::map<const std::string, std::vector<pcl::PointXYZ>>& result() { return result_;}
50  inline void setResult(std::map<const std::string, std::vector<pcl::PointXYZ>>& result) { result_ = result;}
51  inline std::vector<tf2::Transform>& invMap() {return inv_map_;}
52  inline void setInvMap(std::vector<tf2::Transform>& inv_map) {inv_map_ = inv_map;}
53  inline std::vector<tf2::Transform>& map() {return map_;}
54  inline void setMap(std::vector<tf2::Transform>& map) {map_ = map;}
55  inline std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& taskSpace() {return task_space_;}
56  inline void setTaskSpace(std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& s_trans) {task_space_ = s_trans;}
57  inline std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& targetCloud () { return target_cloud_;}
58  inline void setTargetCloud(std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& cloud) {target_cloud_ = cloud;}
59 
61 
65  static std::vector<pcl::PointXYZ> createPCLBox();
66 
68 
71  virtual void baseCalculation()=0;
72 };
73 #endif
AbstractBase::implementation
AbstractBaseImplementation * implementation()
Definition: abstract_base.h:47
AbstractBase::setImplementation
void setImplementation(std::shared_ptr< AbstractBaseImplementation > implementation)
Definition: abstract_base.h:48
AbstractBase::taskSpace
std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion > > > > & taskSpace()
Definition: abstract_base.h:55
AbstractBase::result
std::map< const std::string, std::vector< pcl::PointXYZ > > & result()
Definition: abstract_base.h:49
abstract_param_reader.h
AbstractBase::implementation_
std::shared_ptr< AbstractBaseImplementation > implementation_
refined implementation
Definition: abstract_base.h:37
AbstractBase::setResult
void setResult(std::map< const std::string, std::vector< pcl::PointXYZ >> &result)
Definition: abstract_base.h:50
abstract_robot.h
AbstractBase::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:32
AbstractBase
AbstractBaseClass.
Definition: abstract_base.h:27
AbstractRobot
Abstract Robot implementation.
Definition: abstract_robot.h:25
AbstractBase::inv_map_
std::vector< tf2::Transform > inv_map_
InverseReachabilityMap structure (Zacharias)
Definition: abstract_base.h:31
object_data
Object data.
Definition: abstract_param_reader.h:14
AbstractBase::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:33
AbstractBase::nh_
std::shared_ptr< ros::NodeHandle > nh_
Nodehandle for access to the Rosparam server.
Definition: abstract_base.h:29
AbstractBase::setTaskSpace
void setTaskSpace(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &s_trans)
Definition: abstract_base.h:56
AbstractBaseImplementation
Abstract base implementation.
Definition: abstract_base_implementation.h:12
AbstractBase::AbstractBase
AbstractBase(std::shared_ptr< ros::NodeHandle > const &nh)
constructor
Definition: abstract_base.h:44
AbstractBase::createPCLBox
static std::vector< pcl::PointXYZ > createPCLBox()
createPCLBox box
Definition: simple_base.cpp:78
AbstractBase::setTargetCloud
void setTargetCloud(std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr >> &cloud)
Definition: abstract_base.h:58
AbstractBase::setMap
void setMap(std::vector< tf2::Transform > &map)
Definition: abstract_base.h:54
AbstractBase::invMap
std::vector< tf2::Transform > & invMap()
Definition: abstract_base.h:51
AbstractBase::setInvMap
void setInvMap(std::vector< tf2::Transform > &inv_map)
Definition: abstract_base.h:52
AbstractBase::targetCloud
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > & targetCloud()
Definition: abstract_base.h:57
AbstractBase::map
std::vector< tf2::Transform > & map()
Definition: abstract_base.h:53
AbstractBase::result_
std::map< const std::string, std::vector< pcl::PointXYZ > > result_
Result basepositions, mapped to robot.
Definition: abstract_base.h:34
AbstractBase::map_
std::vector< tf2::Transform > map_
ReachabilityMap structure (Zacharias)
Definition: abstract_base.h:30
AbstractBase::baseCalculation
virtual void baseCalculation()=0
pure virtual template methode
abstract_base_implementation.h


multi_cell_builder
Author(s): Matteo Anedda
autogenerated on Sun Apr 9 2023 23:59:51