Skip to content
Snippets Groups Projects
Select Git revision
  • 0ec453e78ae1dd64996ed2c29e0a2d38f97fe479
  • main default protected
  • mg2bt
  • Part1
4 results

abstract_map_loader.h

Blame
  • user avatar
    KingMaZito authored
    5ed8d517
    History
    abstract_map_loader.h 2.16 KiB
    #ifndef ABSTRACT_MAP_LOADER_
    #define ABSTRACT_MAP_LOADER_
    
    #include "ros/ros.h"
    #include <xmlrpcpp/XmlRpc.h>
    #include <tf2/LinearMath/Transform.h>
    
    #include "octomap/octomap.h"
    #include <pcl/point_cloud.h>
    #include <pcl/octree/octree.h>
    
    
    #include <ros/package.h>
    #include <yaml-cpp/yaml.h>
    #include <fstream>
    
    #include "impl/abstract_robot.h"
    #include "impl/abstract_strategy.h"
    
    class Abstract_strategy;
    class Abstract_robot;
    
    
    class Abstract_map_loader{
        protected:
        std::vector<tf2::Transform> inv_map_;
        std::vector<tf2::Transform> map_;
        std::vector<std::vector<tf2::Transform>> task_grasps_;
        std::vector<std::vector<std::vector<tf2::Quaternion>>> target_rot_;
        std::vector<std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>> target_cloud_;
    
        Abstract_strategy *strategy_; 
    
        public:
        Abstract_map_loader() = default;
        ~Abstract_map_loader() = default;
    
        inline void set_strategy(Abstract_strategy* some_stratergy) {strategy_ = some_stratergy;}
        inline Abstract_strategy* strategy() {return strategy_;}
        
        inline std::vector<tf2::Transform>& inv_map() {return inv_map_;}
        inline std::vector<tf2::Transform>& map() {return map_;}
        inline void set_inv_map(std::vector<tf2::Transform>& list) {inv_map_ = list;}
        inline void set_map(std::vector<tf2::Transform>& list) {map_ = list;}
        inline void set_task_grasps(std::vector<std::vector<tf2::Transform>>& lists_in_list) {task_grasps_ = lists_in_list;}
        inline std::vector<std::vector<tf2::Transform>>& task_grasps() {return task_grasps_;}
        inline std::vector<std::vector<std::vector<tf2::Quaternion>>>& target_rot() {return target_rot_;}
        inline void set_target_rot (std::vector<std::vector<std::vector<tf2::Quaternion>>>& rots) {target_rot_ = rots;}
        inline void set_target_cloud(std::vector<std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& cloud) {target_cloud_ = cloud;}
        inline std::vector<std::vector<pcl::PointCloud< pcl::PointXYZ >::Ptr>>& target_cloud () { return target_cloud_;}
        static std::vector<pcl::PointXYZ> create_pcl_box();
    
        virtual void write_task(Abstract_robot* robot)=0;
        virtual std::vector<std::vector<pcl::PointXYZ>> base_calculation()=0;
    };
    #endif