simple_base_implementation.h
Go to the documentation of this file.
1 #ifndef SIMPLE_BASE_IMPLEMENTATION_
2 #define SIMPLE_BASE_IMPLEMENTATION_
3 
4 #include <ros/ros.h>
5 
7 #include "bridge/abstract_base.h"
8 
10 
14  public:
15  SimpleBaseImplementation()= default;
16  ~SimpleBaseImplementation()= default;
17 
19 
23  void setGraspOrientations(std::map<const std::string, std::vector<std::pair<object_data, std::vector<tf2::Quaternion>>>>& var) override;
24 
26 
32  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) override;
33 
35 
38  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) override;
39 
40 
41 };
42 
43 #endif
SimpleBaseImplementation
SimpleBaseImplementation as refinement of AbstractBaseImplementation.
Definition: simple_base_implementation.h:13
abstract_base.h
SimpleBaseImplementation::SimpleBaseImplementation
SimpleBaseImplementation()=default
object_data
Object data.
Definition: abstract_param_reader.h:14
SimpleBaseImplementation::cloudCalculation
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) override
PCL Cloud calculation for every Object.
Definition: simple_base_implementation.cpp:35
SimpleBaseImplementation::setGraspOrientations
void setGraspOrientations(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &var) override
Store grasp orientations as endeffector transforms.
Definition: simple_base_implementation.cpp:3
SimpleBaseImplementation::invMapCreation
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) override
Create inversed reachability map.
Definition: simple_base_implementation.cpp:16
AbstractBaseImplementation
Abstract base implementation.
Definition: abstract_base_implementation.h:12
SimpleBaseImplementation::~SimpleBaseImplementation
~SimpleBaseImplementation()=default
abstract_base_implementation.h


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