abstract_base_implementation.h
Go to the documentation of this file.
1 #ifndef ABSTRACT_BASE_IMPLEMENTATION_
2 #define ABSTRACT_BASE_IMPLEMENTATION_
3 
4 #include <ros/ros.h>
5 
6 #include "bridge/abstract_base.h"
7 
9 
13  public:
14  AbstractBaseImplementation()= default;
15  ~AbstractBaseImplementation()= default;
16 
18 
22  virtual void setGraspOrientations(std::map<const std::string, std::vector<std::pair<object_data, std::vector<tf2::Quaternion>>>>& var)=0;
23 
25 
31  virtual void invMapCreation(std::vector<tf2::Transform>& map, std::vector<tf2::Transform>& inv_map, std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& task_space)=0;
32 
34 
40  virtual void cloudCalculation(std::vector<tf2::Transform>& inv_map, std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>& task_space, std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& target_cloud)=0;
41 
42 
43 };
44 
45 #endif
AbstractBaseImplementation::~AbstractBaseImplementation
~AbstractBaseImplementation()=default
AbstractBaseImplementation::AbstractBaseImplementation
AbstractBaseImplementation()=default
AbstractBaseImplementation::setGraspOrientations
virtual void setGraspOrientations(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &var)=0
pure virtual methode to set grasp orientations
abstract_base.h
object_data
Object data.
Definition: abstract_param_reader.h:14
AbstractBaseImplementation
Abstract base implementation.
Definition: abstract_base_implementation.h:12
AbstractBaseImplementation::cloudCalculation
virtual void cloudCalculation(std::vector< tf2::Transform > &inv_map, std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &task_space, std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr >> &target_cloud)=0
pure virtual methode to calculate pcl clouds
AbstractBaseImplementation::invMapCreation
virtual void invMapCreation(std::vector< tf2::Transform > &map, std::vector< tf2::Transform > &inv_map, std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &task_space)=0
pure virtual methode to calculate the inverse map


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