$search
00001 /* 00002 * table_visualization.h 00003 * 00004 * Created on: Sep 19, 2012 00005 * Author: goa-sn 00006 */ 00007 00008 #ifndef TABLE_VISUALIZATION_H_ 00009 #define TABLE_VISUALIZATION_H_ 00010 00011 //################## 00012 //#### includes #### 00013 // standard includes 00014 #include <stdio.h> 00015 #include <sstream> 00016 00017 // ros includes 00018 #include <ros/ros.h> 00019 #include <cob_3d_mapping_msgs/ShapeArray.h> 00020 #include <cob_3d_mapping_msgs/GetObjectsOfClass.h> 00021 #include <cob_3d_mapping_msgs/GetTables.h> 00022 #include <cob_3d_visualization/table_marker.h> 00023 00024 //#include <cob_3d_mapping_msgs/GetTables.h> 00025 00026 00027 class TableVisualization 00028 { 00029 public: 00030 // Constructor 00031 TableVisualization () 00032 00033 { 00034 ctr_ = 0 ; 00035 // simple_nh_("move_base_linear_simple") ; 00036 00037 table_array_sub_ = nh_.subscribe ("table_array", 1, &TableVisualization::tableVisualizationCallback, this); 00038 table_im_server_.reset (new interactive_markers::InteractiveMarkerServer ("geometry_map/map", "", false)); 00039 // goal_pub_ = nh_.advertise<geometry_msgs::PoseStamped>("/move_base_linear_simple/goal", 1); 00040 00041 00042 } 00043 // Destructor 00044 ~TableVisualization () 00045 { 00046 00047 } 00048 00049 void tableVisualizationCallback (const cob_3d_mapping_msgs::ShapeArrayPtr& ta); 00050 00051 00052 00053 protected: 00054 00055 ros::NodeHandle nh_; 00056 // ros::NodeHandle simple_nh_; 00057 ros::Subscriber table_array_sub_ ; 00058 ros::Publisher goal_pub_ ; 00059 std::vector<boost::shared_ptr<TableMarker> > v_tm_; 00060 boost::shared_ptr<interactive_markers::InteractiveMarkerServer> table_im_server_; 00061 00062 00063 00064 int ctr_; 00065 }; 00066 00067 #endif /* TABLE_VISUALIZATION_H_ */