$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * 00005 * Copyright (C) Brno University of Technology 00006 * 00007 * This file is part of software developed by Robo@FIT group. 00008 * 00009 * Author: Tomas Lokaj (xlokaj03@stud.fit.vutbr.cz) 00010 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00011 * Date: 02/04/2012 00012 * 00013 * This file is free software: you can redistribute it and/or modify 00014 * it under the terms of the GNU Lesser General Public License as published by 00015 * the Free Software Foundation, either version 3 of the License, or 00016 * (at your option) any later version. 00017 * 00018 * This file is distributed in the hope that it will be useful, 00019 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00020 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00021 * GNU Lesser General Public License for more details. 00022 * 00023 * You should have received a copy of the GNU Lesser General Public License 00024 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00025 */ 00026 00027 #pragma once 00028 #ifndef PLANEPOLYGON_H_ 00029 #define PLANEPOLYGON_H_ 00030 00031 #include "plane.h" 00032 #include <Eigen/Geometry> 00033 00034 #define LINE_WIDTH 0.01 00035 00036 namespace srs_interaction_primitives 00037 { 00047 class PlanePolygon : public Plane 00048 { 00049 public: 00057 PlanePolygon(InteractiveMarkerServerPtr server, std::string frame_id, std::string name); 00058 00063 Ogre::Vector3 getNormal() 00064 { 00065 return normal_; 00066 } 00067 00072 void setNormal(Ogre::Vector3 normal) 00073 { 00074 normal_ = normal; 00075 } 00076 00081 void setNormal(geometry_msgs::Vector3 normal) 00082 { 00083 normal_ = Ogre::Vector3(normal.x, normal.y, normal.z); 00084 } 00085 00090 void setPolygon(geometry_msgs::Polygon polygon) 00091 { 00092 polygon_ = polygon; 00093 } 00094 00095 protected: 00096 void create(); 00097 00098 private: 00099 // PlanePolygon's attributes 00100 Ogre::Vector3 normal_; 00101 geometry_msgs::Polygon polygon_; 00102 visualization_msgs::Marker polygon_mesh_; 00103 }; 00104 00105 } 00106 00107 #endif /* PLANEPOLYGON_H_ */