Go to the documentation of this file.
5 #include <xmlrpcpp/XmlRpc.h>
6 #include <tf2/LinearMath/Transform.h>
8 #include "octomap/octomap.h"
9 #include <pcl/point_cloud.h>
10 #include <pcl/octree/octree.h>
13 #include <ros/package.h>
14 #include <yaml-cpp/yaml.h>
31 std::shared_ptr<ros::NodeHandle>
nh_;
33 std::vector<tf2::Transform>
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_;
75 inline std::vector<tf2::Transform>&
map() {
return map_;}
81 inline void set_map(std::vector<tf2::Transform>& list) {
map_ = list;}
87 inline std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>&
task_space() {
return task_space_;}
126 virtual std::map<const std::string, std::vector<pcl::PointXYZ>>
base_calculation()=0;
virtual std::map< const std::string, std::vector< pcl::PointXYZ > > base_calculation()=0
pure virtual template methode
std::shared_ptr< ros::NodeHandle > nh_
Ros nodehandle object.
void set_inv_map(std::vector< tf2::Transform > &list)
Set inverse map structure.
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > & target_cloud()
Get task cloud.
Abstract_base_implementation * implementation()
Get used implementation.
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.
std::vector< tf2::Transform > map_
Reachability map structure of a robot.
std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion > > > > & task_space()
Get task space.
std::vector< tf2::Transform > & inv_map()
Get inverse map structure.
virtual void write_task(Abstract_robot *robot)=0
write trask
static std::vector< pcl::PointXYZ > create_pcl_box()
box discretization
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > target_cloud_
Pointcloud structure, mapped to robot.
void set_map(std::vector< tf2::Transform > &list)
Set map structure.
void set_implementation(std::shared_ptr< Abstract_base_implementation > some_implememntation)
Set used implementation.
abstract base implementation
std::vector< tf2::Transform > & map()
Get map structure.
void set_task_space(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &s_trans)
Set task space.
std::shared_ptr< Abstract_base_implementation > implementation_
refined implementation
std::vector< tf2::Transform > inv_map_
Inversion of reachability map structure.
void set_target_cloud(std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr >> &cloud)
Set task cloud.
Abstract_base(std::shared_ptr< ros::NodeHandle > const &d)
Abstract base constructor.