00001 /****************************************************************************** 00002 * \file 00003 * 00004 * Copyright (C) Brno University of Technology 00005 * 00006 * This file is part of software developed by Robo@FIT group. 00007 * 00008 * Author: Tomas Lokaj (xlokaj03@stud.fit.vutbr.cz) 00009 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00010 * Date: 12/09/2012 00011 * 00012 * This file is free software: you can redistribute it and/or modify 00013 * it under the terms of the GNU Lesser General Public License as published by 00014 * the Free Software Foundation, either version 3 of the License, or 00015 * (at your option) any later version. 00016 * 00017 * This file is distributed in the hope that it will be useful, 00018 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00019 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00020 * GNU Lesser General Public License for more details. 00021 * 00022 * You should have received a copy of the GNU Lesser General Public License 00023 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00024 */ 00025 00026 #ifndef CLICKABLE_POSITIONS_H_ 00027 #define CLICKABLE_POSITIONS_H_ 00028 00029 #include <ros/ros.h> 00030 #include <ros/subscriber.h> 00031 #include <visualization_msgs/InteractiveMarker.h> 00032 #include <visualization_msgs/InteractiveMarkerControl.h> 00033 #include <visualization_msgs/InteractiveMarkerFeedback.h> 00034 #include <interactive_markers/interactive_marker_server.h> 00035 #include <srs_interaction_primitives/topics_list.h> 00036 00037 namespace srs_interaction_primitives 00038 { 00039 typedef boost::shared_ptr<interactive_markers::InteractiveMarkerServer> InteractiveMarkerServerPtr; 00040 00047 class ClickablePositionsMarker 00048 { 00049 public: 00059 ClickablePositionsMarker(InteractiveMarkerServerPtr imServer,std::string frame_id, std::string topic, float radius, std_msgs::ColorRGBA color, 00060 std::vector<geometry_msgs::Point> positions); 00064 virtual ~ClickablePositionsMarker(); 00065 00070 visualization_msgs::InteractiveMarker getMarker() 00071 { 00072 return interactive_marker_; 00073 } 00074 00078 void markerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); 00079 00080 private: 00081 void create(); 00082 00083 private: 00084 // Interactive Marker server 00085 InteractiveMarkerServerPtr imServer_; 00086 00087 std::string frame_id_; 00088 std::string topic_suffix_; 00089 float radius_; 00090 std_msgs::ColorRGBA color_; 00091 std::vector<geometry_msgs::Point> positions_; 00092 00093 ros::NodeHandle nh_; 00094 visualization_msgs::InteractiveMarker interactive_marker_; 00095 std::stringstream marker_name_; 00096 std::map<std::string, geometry_msgs::Point> controls_; 00097 00098 ros::Publisher click_publisher_; 00099 }; 00100 00101 } /* namespace srs_interaction_primitives */ 00102 #endif /* CLICKABLE_POSITIONS_H_ */