$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: UnknownObject.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: 21/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 #include <srs_interaction_primitives/unknown_object.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 namespace srs_interaction_primitives 00037 { 00038 00039 UnknownObject::UnknownObject(InteractiveMarkerServerPtr server, string frame_id, string name) 00040 : Primitive(server, frame_id, name, srs_interaction_primitives::PrimitiveType::UNKNOWN_OBJECT) 00041 { 00042 description_ = ""; 00043 00044 // color_.r = 0.3; 00045 // color_.g = 0.5; 00046 // color_.b = 0.6; 00047 // color_.a = 1.0; 00048 color_.r = 0.8; 00049 color_.g = 0.85; 00050 color_.b = 0.9; 00051 color_.a = 0.5; 00052 00053 show_movement_control_ = show_scale_control_ = show_rotation_control_ = show_measure_control_ = show_description_control_ = false; 00054 use_material_ = true; 00055 allow_object_interaction_ = false; 00056 } 00057 00058 00059 void UnknownObject::setAllowObjectInteraction(bool allow) 00060 { 00061 ROS_INFO("Interaction allowed"); 00062 00063 allow_object_interaction_ = allow; 00064 if (allow_object_interaction_) 00065 { 00066 addMovementControls(); 00067 addRotationControls(); 00068 addScaleControls(); 00069 00070 menu_handler_.setCheckState(menu_handler_interaction_movement_, MenuHandler::CHECKED); 00071 menu_handler_.setCheckState(menu_handler_interaction_rotation_, MenuHandler::CHECKED); 00072 menu_handler_.setCheckState(menu_handler_interaction_scale_, MenuHandler::CHECKED); 00073 } 00074 else 00075 { 00076 removeMovementControls(); 00077 removeRotationControls(); 00078 removeScaleControls(); 00079 00080 menu_handler_.setCheckState(menu_handler_interaction_movement_, MenuHandler::UNCHECKED); 00081 menu_handler_.setCheckState(menu_handler_interaction_rotation_, MenuHandler::UNCHECKED); 00082 menu_handler_.setCheckState(menu_handler_interaction_scale_, MenuHandler::UNCHECKED); 00083 } 00084 00085 server_->insert(object_); 00086 menu_handler_.reApply(*server_); 00087 server_->applyChanges(); 00088 } 00089 00090 00091 void UnknownObject::uboxCallback(const InteractiveMarkerFeedbackConstPtr &feedback) 00092 { 00093 defaultCallback(feedback); 00094 00095 if (show_scale_control_) 00096 { 00097 updateScaleControls(); 00098 server_->applyChanges(); 00099 } 00100 } 00101 00102 00103 void UnknownObject::menuCallback(const InteractiveMarkerFeedbackConstPtr &feedback) 00104 { 00105 MenuHandler::EntryHandle handle = feedback->menu_entry_id; 00106 MenuHandler::CheckState state; 00107 string title; 00108 menu_handler_.getCheckState(handle, state); 00109 menu_handler_.getTitle(handle, title); 00110 00111 updatePublisher_->publishMenuClicked(title, state); 00112 00113 switch (feedback->menu_entry_id) 00114 { 00115 case 1: 00119 if (state == MenuHandler::CHECKED) 00120 { 00121 removeDescriptionControl(); 00122 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00123 } 00124 else 00125 { 00126 addDescriptionControl(); 00127 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00128 } 00129 break; 00130 case 2: 00134 if (state == MenuHandler::CHECKED) 00135 { 00136 removeMeasureControl(); 00137 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00138 } 00139 else 00140 { 00141 addMeasureControl(); 00142 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00143 } 00144 break; 00145 00146 case 4: 00147 /* 00148 * Enable all interaction controls 00149 */ 00150 addMovementControls(); 00151 addRotationControls(); 00152 addScaleControls(); 00153 menu_handler_.setCheckState(menu_handler_interaction_movement_, MenuHandler::CHECKED); 00154 menu_handler_.setCheckState(menu_handler_interaction_rotation_, MenuHandler::CHECKED); 00155 menu_handler_.setCheckState(menu_handler_interaction_scale_, MenuHandler::CHECKED); 00156 break; 00157 case 5: 00158 /* 00159 * Disable all interaction controls 00160 */ 00161 removeMovementControls(); 00162 removeRotationControls(); 00163 removeScaleControls(); 00164 menu_handler_.setCheckState(menu_handler_interaction_movement_, MenuHandler::UNCHECKED); 00165 menu_handler_.setCheckState(menu_handler_interaction_rotation_, MenuHandler::UNCHECKED); 00166 menu_handler_.setCheckState(menu_handler_interaction_scale_, MenuHandler::UNCHECKED); 00167 break; 00168 00169 case 6: 00170 /* 00171 * Movement controls 00172 */ 00173 if (state == MenuHandler::CHECKED) 00174 { 00175 removeMovementControls(); 00176 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00177 } 00178 else 00179 { 00180 addMovementControls(); 00181 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00182 } 00183 break; 00184 case 7: 00185 /* 00186 * Rotation controls 00187 */ 00188 if (state == MenuHandler::CHECKED) 00189 { 00190 removeRotationControls(); 00191 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00192 } 00193 else 00194 { 00195 addRotationControls(); 00196 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00197 } 00198 break; 00199 case 8: 00200 /* 00201 * Scale controls 00202 */ 00203 if (state == MenuHandler::CHECKED) 00204 { 00205 removeScaleControls(); 00206 menu_handler_.setCheckState(handle, MenuHandler::UNCHECKED); 00207 } 00208 else 00209 { 00210 addScaleControls(); 00211 menu_handler_.setCheckState(handle, MenuHandler::CHECKED); 00212 } 00213 break; 00214 } 00215 00216 server_->insert(object_); 00217 menu_handler_.reApply(*server_); 00218 server_->applyChanges(); 00219 } 00220 00221 void UnknownObject::createMenu() 00222 { 00223 if (!menu_created_) 00224 { 00225 menu_created_ = true; 00226 menu_handler_.setCheckState( 00227 menu_handler_.insert("Show Description", boost::bind(&UnknownObject::menuCallback, this, _1)), 00228 MenuHandler::UNCHECKED); 00229 menu_handler_.setCheckState( 00230 menu_handler_.insert("Show Measure", boost::bind(&UnknownObject::menuCallback, this, _1)), 00231 MenuHandler::UNCHECKED); 00232 00233 menu_handler_interaction_ = menu_handler_.insert("Interaction"); 00234 menu_handler_.setCheckState( 00235 menu_handler_.insert(menu_handler_interaction_, "Enable All", boost::bind(&UnknownObject::menuCallback, this, _1)), 00236 MenuHandler::NO_CHECKBOX); 00237 menu_handler_.setCheckState( 00238 menu_handler_.insert(menu_handler_interaction_, "Disable All", boost::bind(&UnknownObject::menuCallback, this, _1)), 00239 MenuHandler::NO_CHECKBOX); 00240 00241 menu_handler_interaction_movement_ = menu_handler_.insert(menu_handler_interaction_, "Movement", 00242 boost::bind(&UnknownObject::menuCallback, this, _1)); 00243 menu_handler_interaction_rotation_ = menu_handler_.insert(menu_handler_interaction_, "Rotation", 00244 boost::bind(&UnknownObject::menuCallback, this, _1)); 00245 menu_handler_interaction_scale_ = menu_handler_.insert(menu_handler_interaction_, "Scale", 00246 boost::bind(&UnknownObject::menuCallback, this, _1)); 00247 00248 menu_handler_.setCheckState(menu_handler_interaction_movement_, MenuHandler::UNCHECKED); 00249 menu_handler_.setCheckState(menu_handler_interaction_rotation_, MenuHandler::UNCHECKED); 00250 menu_handler_.setCheckState(menu_handler_interaction_scale_, MenuHandler::UNCHECKED); 00251 } 00252 } 00253 00254 00255 void UnknownObject::createBox() 00256 { 00257 box_.type = Marker::MESH_RESOURCE; 00258 box_.mesh_use_embedded_materials = true; 00259 box_.scale = scale_; 00260 box_.mesh_resource = "package://srs_interaction_primitives/meshes/unknown_object.dae"; 00261 } 00262 00263 00264 void UnknownObject::createColorBox() 00265 { 00266 // Transparent box 00267 box_.type = Marker::CUBE; 00268 box_.pose.position.x = 0; 00269 box_.pose.position.y = 0; 00270 box_.pose.position.z = 0; 00271 box_.scale = scale_; 00272 box_.color = color_; 00273 box_.color.a = 0.5; 00274 00275 // Wireframe model - disabled for now, it doesn't scale properly... 00276 wire_.points.clear(); 00277 00278 Point p1, p2; 00279 double sx = scale_.x / 2; 00280 double sy = scale_.y / 2; 00281 double sz = scale_.z / 2; 00282 double trans_x = 0; 00283 double trans_y = 0; 00284 double trans_z = 0; 00285 00286 wire_.type = Marker::LINE_LIST; 00287 wire_.pose.position.x = 0; 00288 wire_.pose.position.y = 0; 00289 wire_.pose.position.z = 0; 00290 wire_.scale = scale_; 00291 wire_.color = color_; 00292 wire_.color.a = 1.0; 00293 // wire_.scale.x = 0.002; 00294 wire_.scale.x = 0.004; 00295 00296 p1.x = -sx + trans_x; 00297 p1.y = -sy + trans_y; 00298 p1.z = -sz + trans_z; 00299 p2.x = -sx + trans_x; 00300 p2.y = sy + trans_y; 00301 p2.z = -sz + trans_z; 00302 wire_.points.push_back(p1); 00303 wire_.points.push_back(p2); 00304 p2.x = -sx + trans_x; 00305 p2.y = -sy + trans_y; 00306 p2.z = sz + trans_z; 00307 wire_.points.push_back(p1); 00308 wire_.points.push_back(p2); 00309 p1.x = -sx + trans_x; 00310 p1.y = sy + trans_y; 00311 p1.z = sz + trans_z; 00312 p2.x = -sx + trans_x; 00313 p2.y = sy + trans_y; 00314 p2.z = -sz + trans_z; 00315 wire_.points.push_back(p1); 00316 wire_.points.push_back(p2); 00317 p2.x = -sx + trans_x; 00318 p2.y = -sy + trans_y; 00319 p2.z = sz + trans_z; 00320 wire_.points.push_back(p1); 00321 wire_.points.push_back(p2); 00322 00323 p1.x = sx + trans_x; 00324 p1.y = -sy + trans_y; 00325 p1.z = -sz + trans_z; 00326 p2.x = sx + trans_x; 00327 p2.y = sy + trans_y; 00328 p2.z = -sz + trans_z; 00329 wire_.points.push_back(p1); 00330 wire_.points.push_back(p2); 00331 p2.x = sx + trans_x; 00332 p2.y = -sy + trans_y; 00333 p2.z = sz + trans_z; 00334 wire_.points.push_back(p1); 00335 wire_.points.push_back(p2); 00336 p1.x = sx + trans_x; 00337 p1.y = sy + trans_y; 00338 p1.z = sz + trans_z; 00339 p2.x = sx + trans_x; 00340 p2.y = sy + trans_y; 00341 p2.z = -sz + trans_z; 00342 wire_.points.push_back(p1); 00343 wire_.points.push_back(p2); 00344 p2.x = sx + trans_x; 00345 p2.y = -sy + trans_y; 00346 p2.z = sz + trans_z; 00347 wire_.points.push_back(p1); 00348 wire_.points.push_back(p2); 00349 00350 p1.x = sx + trans_x; 00351 p1.y = sy + trans_y; 00352 p1.z = sz + trans_z; 00353 p2.x = -sx + trans_x; 00354 p2.y = sy + trans_y; 00355 p2.z = sz + trans_z; 00356 wire_.points.push_back(p1); 00357 wire_.points.push_back(p2); 00358 00359 p1.x = sx + trans_x; 00360 p1.y = -sy + trans_y; 00361 p1.z = sz + trans_z; 00362 p2.x = -sx + trans_x; 00363 p2.y = -sy + trans_y; 00364 p2.z = sz + trans_z; 00365 wire_.points.push_back(p1); 00366 wire_.points.push_back(p2); 00367 00368 p1.x = sx + trans_x; 00369 p1.y = sy + trans_y; 00370 p1.z = -sz + trans_z; 00371 p2.x = -sx + trans_x; 00372 p2.y = sy + trans_y; 00373 p2.z = -sz + trans_z; 00374 wire_.points.push_back(p1); 00375 wire_.points.push_back(p2); 00376 00377 p1.x = sx + trans_x; 00378 p1.y = -sy + trans_y; 00379 p1.z = -sz + trans_z; 00380 p2.x = -sx + trans_x; 00381 p2.y = -sy + trans_y; 00382 p2.z = -sz + trans_z; 00383 wire_.points.push_back(p1); 00384 wire_.points.push_back(p2); 00385 } 00386 00387 00388 void UnknownObject::createUnknownBox() 00389 { 00390 object_.header.frame_id = frame_id_; 00391 object_.name = name_; 00392 // object_.description = name_; 00393 object_.pose = pose_; 00394 object_.scale = srs_interaction_primitives::maxScale(scale_); 00395 } 00396 00397 00398 void UnknownObject::create() 00399 { 00400 clearObject(); 00401 00402 createUnknownBox(); 00403 00404 control_.name = "box_control"; 00405 if( use_material_ ) 00406 { 00407 createBox(); 00408 control_.markers.push_back(box_); 00409 } 00410 else 00411 { 00412 createColorBox(); 00413 control_.markers.push_back(box_); 00414 control_.markers.push_back(wire_); 00415 } 00416 control_.interaction_mode = InteractiveMarkerControl::MENU; 00417 control_.always_visible = true; 00418 object_.controls.push_back(control_); 00419 00420 createMenu(); 00421 } 00422 00423 void UnknownObject::insert() 00424 { 00425 create(); 00426 00427 server_->insert(object_, boost::bind(&UnknownObject::uboxCallback, this, _1)); 00428 menu_handler_.apply(*server_, name_); 00429 } 00430 00431 }