Go to the documentation of this file.
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>
29 std::shared_ptr<ros::NodeHandle>
nh_;
30 std::vector<tf2::Transform>
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_;
49 inline std::map<const std::string, std::vector<pcl::PointXYZ>>&
result() {
return result_;}
53 inline std::vector<tf2::Transform>&
map() {
return map_;}
55 inline std::map<const std::string, std::vector<std::pair<object_data,std::vector<tf2::Quaternion>>>>&
taskSpace() {
return task_space_;}
57 inline std::map<const std::string, std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>&
targetCloud () {
return target_cloud_;}
AbstractBaseImplementation * implementation()
void setImplementation(std::shared_ptr< AbstractBaseImplementation > implementation)
std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion > > > > & taskSpace()
std::map< const std::string, std::vector< pcl::PointXYZ > > & result()
std::shared_ptr< AbstractBaseImplementation > implementation_
refined implementation
void setResult(std::map< const std::string, std::vector< pcl::PointXYZ >> &result)
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.
Abstract Robot implementation.
std::vector< tf2::Transform > inv_map_
InverseReachabilityMap structure (Zacharias)
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > target_cloud_
Pointcloud structure, mapped to robot.
std::shared_ptr< ros::NodeHandle > nh_
Nodehandle for access to the Rosparam server.
void setTaskSpace(std::map< const std::string, std::vector< std::pair< object_data, std::vector< tf2::Quaternion >>>> &s_trans)
Abstract base implementation.
AbstractBase(std::shared_ptr< ros::NodeHandle > const &nh)
constructor
static std::vector< pcl::PointXYZ > createPCLBox()
createPCLBox box
void setTargetCloud(std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr >> &cloud)
void setMap(std::vector< tf2::Transform > &map)
std::vector< tf2::Transform > & invMap()
void setInvMap(std::vector< tf2::Transform > &inv_map)
std::map< const std::string, std::vector< pcl::PointCloud< pcl::PointXYZ >::Ptr > > & targetCloud()
std::vector< tf2::Transform > & map()
std::map< const std::string, std::vector< pcl::PointXYZ > > result_
Result basepositions, mapped to robot.
std::vector< tf2::Transform > map_
ReachabilityMap structure (Zacharias)
virtual void baseCalculation()=0
pure virtual template methode