world_landmark.h
Go to the documentation of this file.
00001 #ifndef PBD_WORLD_LANDMARK
00002 #define PBD_WORLD_LANDMARK
00003 
00004 
00005 // System includes
00006 #include <sstream>
00007 
00008 // ROS builtins
00009 #include "ros/ros.h"
00010 #include <interactive_markers/menu_handler.h>
00011 #include <geometry_msgs/Pose.h>
00012 #include "visualization_msgs/InteractiveMarkerFeedback.h"
00013 #include "visualization_msgs/InteractiveMarker.h"
00014 
00015 // Local
00016 #include "fetch_pbd_interaction/Landmark.h"
00017 
00018 namespace fetch_pbd_interaction {
00019 
00020 class World;
00021 
00022 class WorldLandmark {
00023 
00024 private:
00025         //void (World::*_removeObjectCallback)(std::string name);
00026         //void (World::*_generateGraspsCallback)(std::string name);
00027         sensor_msgs::PointCloud2 point_cloud;
00028         int index;
00029         std::string assigned_name;
00030     bool is_removed;
00031     fetch_pbd_interaction::World *world;
00032 
00033 public:
00034         WorldLandmark(geometry_msgs::Pose pose, int ind, geometry_msgs::Vector3 dims,
00035                  sensor_msgs::PointCloud2 pc); // World *world, void (World::*removeObject)(std::string name), void (World::*generateGrasps)(std::string name));
00036         ~WorldLandmark();
00037         std::string getName();
00038         void remove(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00039         void getGrasps(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback);
00040     visualization_msgs::InteractiveMarker int_marker;
00041         interactive_markers::MenuHandler menu_handler;
00042 
00043         fetch_pbd_interaction::Landmark object;
00044 
00045 
00046 };
00047 
00048 };
00049 
00050 #endif


fetch_pbd_interaction
Author(s): Sarah Elliott
autogenerated on Thu Jun 6 2019 18:27:21