$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: interaction_primitives_service_server.h 676 2012-04-19 18:32:07Z xlokaj03 $ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by Robo@FIT group. 00009 * 00010 * Author: Tomas Lokaj (xlokaj03@stud.fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 9/12/2011 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #pragma once 00029 #ifndef INTERACTION_PRIMITIVES_SERVICE_SERVER_H_ 00030 #define INTERACTION_PRIMITIVES_SERVICE_SERVER_H_ 00031 00032 #include <ros/ros.h> 00033 #include <interactive_markers/interactive_marker_server.h> 00034 00035 #include <srs_interaction_primitives/PrimitiveType.h> 00036 #include <std_msgs/UInt8.h> 00037 00038 #include "primitive.h" 00039 #include "bounding_box.h" 00040 #include "billboard.h" 00041 #include "plane.h" 00042 #include "plane_polygon.h" 00043 #include "object.h" 00044 #include "unknown_object.h" 00045 #include "clickable_positions/clickable_positions.h" 00046 #include "services_list.h" 00047 00048 #include <cmath> 00049 #include <map> 00050 #include <string> 00051 00058 namespace srs_interaction_primitives 00059 { 00060 00061 // Container with primitives 00062 extern std::map<std::string, Primitive*> primitives; 00063 00064 // Interactive Marker server 00065 extern InteractiveMarkerServerPtr imServer; 00066 00067 ros::Publisher vis_pub; 00068 00075 bool addPlane(AddPlane::Request &req, AddPlane::Response &res); 00076 00083 bool addPlanePolygon(AddPlanePolygon::Request &req, AddPlanePolygon::Response &res); 00084 00091 bool addBillboard(AddBillboard::Request &req, AddBillboard::Response &res); 00092 00099 bool addBoundingBox(AddBoundingBox::Request &req, AddBoundingBox::Response &res); 00100 00107 bool addObject(AddObject::Request &req, AddObject::Response &res); 00108 00115 bool addUnknownObject(AddUnknownObject::Request &req, AddUnknownObject::Response &res); 00116 00123 bool removePrimitive(RemovePrimitive::Request &req, RemovePrimitive::Response &res); 00124 00131 bool setPreGraspPosition(SetPreGraspPosition::Request &req, SetPreGraspPosition::Response &res); 00132 00139 bool removePreGraspPosition(RemovePreGraspPosition::Request &req, RemovePreGraspPosition::Response &res); 00140 00147 bool changeDescription(ChangeDescription::Request &req, ChangeDescription::Response &res); 00148 00155 bool changePose(ChangePose::Request &req, ChangePose::Response &res); 00156 00163 bool changeScale(ChangeScale::Request &req, ChangeScale::Response &res); 00164 00171 bool changeColor(ChangeColor::Request &req, ChangeColor::Response &res); 00172 00179 bool changeDirection(ChangeDirection::Request &req, ChangeDirection::Response &res); 00180 00187 bool changeVelocity(ChangeVelocity::Request &req, ChangeVelocity::Response &res); 00188 00195 bool getUpdateTopic(GetUpdateTopic::Request &req, GetUpdateTopic::Response &res); 00196 00203 bool setAllowObjectInteraction(SetAllowObjectInteraction::Request &req, SetAllowObjectInteraction::Response &res); 00204 00211 bool getObject(GetObject::Request &req, GetObject::Response &res); 00212 00219 bool clickablePositions(ClickablePositions::Request &req, ClickablePositions::Response &res); 00220 00227 bool robotPosePrediction(RobotPosePrediction::Request &req, RobotPosePrediction::Response &res); 00228 00229 } 00230 00231 #endif /* INTERACTION_PRIMITIVES_SERVICE_SERVER_H_ */