$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: PlanePolygon.cpp 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: 02/04/2012 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 #include <srs_interaction_primitives/plane_polygon.h> 00029 00030 using namespace std; 00031 using namespace interactive_markers; 00032 using namespace visualization_msgs; 00033 using namespace geometry_msgs; 00034 using namespace std_msgs; 00035 00036 00037 namespace srs_interaction_primitives 00038 { 00039 00040 PlanePolygon::PlanePolygon(InteractiveMarkerServerPtr server, string frame_id, string name) : 00041 Plane(server, frame_id, name) 00042 { 00043 setPrimitiveType(srs_interaction_primitives::PrimitiveType::PLANE_POLYGON); 00044 } 00045 00046 void PlanePolygon::create() 00047 { 00048 if (polygon_.points.size() == 0) 00049 { 00050 ROS_WARN("Empty polygon!"); 00051 return; 00052 } 00053 00054 clearObject(); 00055 00056 Point p, max, min; 00057 max.x = max.y = max.z = -9999999.0; 00058 min.x = min.y = min.z = 9999999.0; 00059 00060 object_.header.frame_id = frame_id_; 00061 object_.name = name_; 00062 // object_.description = name_ + " plane"; 00063 00064 polygon_mesh_.type = Marker::LINE_STRIP; 00065 polygon_mesh_.color = color_; 00066 polygon_mesh_.color.a = 1; 00067 polygon_mesh_.header.frame_id = frame_id_; 00068 polygon_mesh_.scale.x = LINE_WIDTH; 00069 00070 Point center; 00071 center.x = 0.0; 00072 center.y = 0.0; 00073 center.z = 0.0; 00074 00075 for (unsigned int i = 0; i < polygon_.points.size(); i++) 00076 { 00077 p.x = polygon_.points[i].x; 00078 p.y = polygon_.points[i].y; 00079 p.z = polygon_.points[i].z; 00080 polygon_mesh_.points.push_back(p); 00081 if (p.x > max.x) 00082 max.x = p.x; 00083 else if (p.x < min.x) 00084 min.x = p.x; 00085 if (p.y > max.y) 00086 max.y = p.y; 00087 else if (p.y < min.y) 00088 min.y = p.y; 00089 if (p.z > max.z) 00090 max.z = p.z; 00091 else if (p.z < min.z) 00092 min.z = p.z; 00093 center.x += polygon_.points[i].x; 00094 center.y += polygon_.points[i].y; 00095 center.z += polygon_.points[i].z; 00096 } 00097 p.x = polygon_.points[0].x; 00098 p.y = polygon_.points[0].y; 00099 p.z = polygon_.points[0].z; 00100 polygon_mesh_.points.push_back(p); 00101 00102 center.x /= polygon_.points.size(); 00103 center.y /= polygon_.points.size(); 00104 center.z /= polygon_.points.size(); 00105 00106 scale_.x = max.x - min.x; 00107 scale_.y = max.y - min.y; 00108 scale_.z = 0.001; 00109 00110 if (polygon_.points.size() >= 3 || normal_ != Ogre::Vector3(0, 0, 0)) 00111 { 00112 object_.pose.position = center; 00113 00114 mesh_.type = Marker::CUBE; 00115 mesh_.header.frame_id = frame_id_; 00116 mesh_.color = color_; 00117 mesh_.color.a = 0.2; 00118 mesh_.pose.position = center; 00119 mesh_.scale = scale_; 00120 00121 if (normal_ == Ogre::Vector3(0, 0, 0)) 00122 { 00123 Ogre::Vector3 u = Ogre::Vector3(polygon_.points[1].x - polygon_.points[0].x, polygon_.points[1].y 00124 - polygon_.points[0].y, polygon_.points[1].z - polygon_.points[0].z); 00125 Ogre::Vector3 v = Ogre::Vector3(polygon_.points[2].x - polygon_.points[0].x, polygon_.points[2].y 00126 - polygon_.points[0].y, polygon_.points[2].z - polygon_.points[0].z); 00127 normal_ = u.crossProduct(v); 00128 } 00129 normal_.normalise(); 00130 00131 float nx = normal_.y * 1 - normal_.z * 0; 00132 float ny = normal_.z * 0 - normal_.x * 1; 00133 float nz = normal_.x * 0 - normal_.z * 0; 00134 00135 float length = sqrt(nx * nx + ny * ny + nz * nz); 00136 nx /= length; 00137 ny /= length; 00138 nz /= length; 00139 00140 float sign = ((nx * 1 + ny * 0 + nz * 0) < 0) ? -1 : 1; 00141 float angle = acos(normal_.x * 0 + normal_.y * 0 + normal_.z * 1) * sign; 00142 00143 Eigen::Quaternion<float> q; 00144 q = Eigen::AngleAxisf(-angle, Eigen::Matrix<float, 3, 1>(nx, ny, nz)); 00145 mesh_.pose.orientation.x = q.x(); 00146 mesh_.pose.orientation.y = q.y(); 00147 mesh_.pose.orientation.z = q.z(); 00148 mesh_.pose.orientation.w = q.w(); 00149 00150 control_.markers.push_back(mesh_); 00151 } 00152 00153 control_.always_visible = true; 00154 control_.interaction_mode = InteractiveMarkerControl::BUTTON; 00155 control_.markers.push_back(polygon_mesh_); 00156 object_.controls.push_back(control_); 00157 00158 createMenu(); 00159 } 00160 00161 }