$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_environment_perception_intern 00012 * ROS package name: cob_3d_mapping_common 00013 * Description: 00014 * 00015 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00016 * 00017 *\author 00018 * Author: Waqas Tanveer, email:Waqas.Tanveer@ipa.fhg.de 00019 * \author 00020 * Supervised by: Georg Arbeiter, email:georg.arbeiter@ipa.fhg.de 00021 * 00022 * Date of creation: 04/2012 00023 * ToDo: 00024 * 00025 * 00026 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00027 * 00028 * Redistribution and use in source and binary forms, with or without 00029 * modification, are permitted provided that the following conditions are met: 00030 * 00031 * * Redistributions of source code must retain the above copyright 00032 * notice, this list of conditions and the following disclaimer. 00033 * * Redistributions in binary form must reproduce the above copyright 00034 * notice, this list of conditions and the following disclaimer in the 00035 * documentation and/or other materials provided with the distribution. 00036 * * Neither the name of the Fraunhofer Institute for Manufacturing 00037 * Engineering and Automation (IPA) nor the names of its 00038 * contributors may be used to endorse or promote products derived from 00039 * this software without specific prior written permission. 00040 * 00041 * This program is free software: you can redistribute it and/or modify 00042 * it under the terms of the GNU Lesser General Public License LGPL as 00043 * published by the Free Software Foundation, either version 3 of the 00044 * License, or (at your option) any later version. 00045 * 00046 * This program is distributed in the hope that it will be useful, 00047 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00048 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00049 * GNU Lesser General Public License LGPL for more details. 00050 * 00051 * You should have received a copy of the GNU Lesser General Public 00052 * License LGPL along with this program. 00053 * If not, see <http://www.gnu.org/licenses/>. 00054 * 00055 ****************************************************************/ 00056 00057 //################## 00058 //#### includes #### 00059 00060 00061 #include <cob_3d_visualization/shape_marker.h> 00062 #include <cob_3d_visualization/table_marker.h> 00063 #include <cob_3d_visualization/shape_visualization.h> 00064 #include <math.h> 00065 #include <stdlib.h> 00066 #include <vector> 00067 //#include <Eigen/Core> 00068 //#include <cob_3d_mapping_geometry_map/geometry_map.h> 00069 #define PI 3.14159265 00070 00071 using namespace cob_3d_mapping; 00072 00073 ShapeVisualization::ShapeVisualization () :ctr_for_shape_indexes (0) 00074 00075 { 00076 shape_array_sub_ = nh_.subscribe ("shape_array", 1, &ShapeVisualization::shapeArrayCallback, this); 00077 feedback_sub_ = nh_.subscribe("geometry_map/map/feedback",1,&ShapeVisualization::setShapePosition,this); 00078 // shape_pub_ = nh_.advertise<cob_3d_mapping_msgs::ShapeArray> ("shape_array", 1); 00079 // get_table_subscriber_ = nh_.subscribe("shape_array", 1, &ShapeVisualization::findTables,this); 00080 im_server_.reset (new interactive_markers::InteractiveMarkerServer ("geometry_map/map", "", false)); 00081 moreOptions() ; 00082 } 00083 00084 void ShapeVisualization::setShapePosition(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)//,const cob_3d_mapping_msgs::Shape& shape) 00085 { 00086 00087 cob_3d_mapping_msgs::ShapeArray map_msg; 00088 map_msg.header.frame_id="/map"; 00089 map_msg.header.stamp = ros::Time::now(); 00090 00091 int shape_id,index; 00092 index=-1; 00093 stringstream name(feedback->marker_name); 00094 00095 Eigen::Quaternionf quat; 00096 00097 Eigen::Matrix3f rotationMat; 00098 Eigen::MatrixXf rotationMatInit; 00099 00100 Eigen::Vector3f normalVec; 00101 Eigen::Vector3f normalVecNew; 00102 Eigen::Vector3f newCentroid; 00103 Eigen::Matrix4f transSecondStep; 00104 00105 00106 if (feedback->marker_name != "Text"){ 00107 name >> shape_id ; 00108 cob_3d_mapping::Polygon p; 00109 00110 for(unsigned int i=0;i<sha.shapes.size();++i) 00111 { 00112 if (sha.shapes[i].id == shape_id) 00113 { 00114 index = i; 00115 } 00116 } 00117 // temporary fix. 00118 //do nothing if index of shape is not found 00119 // this is not supposed to occur , but apparently it does 00120 if(index==-1){ 00121 ROS_WARN("shape not in map array"); 00122 return; 00123 } 00124 00125 cob_3d_mapping::fromROSMsg (sha.shapes.at(index), p); 00126 00127 if (feedback->event_type == 2 && feedback->menu_entry_id == 5){ 00128 quatInit.x() = (float)feedback->pose.orientation.x ; //normalized 00129 quatInit.y() = (float)feedback->pose.orientation.y ; 00130 quatInit.z() = (float)feedback->pose.orientation.z ; 00131 quatInit.w() = (float)feedback->pose.orientation.w ; 00132 00133 oldCentroid (0) = (float)feedback->pose.position.x ; 00134 oldCentroid (1) = (float)feedback->pose.position.y ; 00135 oldCentroid (2) = (float)feedback->pose.position.z ; 00136 00137 quatInit.normalize() ; 00138 00139 rotationMatInit = quatInit.toRotationMatrix() ; 00140 00141 transInit.block(0,0,3,3) << rotationMatInit ; 00142 transInit.col(3).head(3) << oldCentroid(0) , oldCentroid(1), oldCentroid(2) ; 00143 transInit.row(3) << 0,0,0,1 ; 00144 00145 transInitInv = transInit.inverse() ; 00146 Eigen::Affine3f affineInitFinal (transInitInv) ; 00147 affineInit = affineInitFinal ; 00148 00149 std::cout << "transInit : " << "\n" << affineInitFinal.matrix() << "\n" ; 00150 } 00151 00152 if (feedback->event_type == 5){ 00153 /* the name of the marker is arrows_shape_.id, we need to erase the "arrows_" part */ 00154 //string strName(feedback->marker_name); 00155 //strName.erase(strName.begin(),strName.begin()+7); 00156 // stringstream name(strName); 00157 stringstream name(feedback->marker_name); 00158 00159 /* the name of the marker is arrows_shape_.id, we need to erase the "arrows_" part */ 00160 // int test ; 00161 // string strName(feedback->marker_name); 00162 // strName.erase(strName.begin(),strName.begin()+7); 00163 // stringstream nameTest(strName); 00164 // std::cout << "nameTest : " << nameTest.str() << "\n" ; 00165 // nameTest >> test ; 00166 // std::cout << "test : " << test << "\n" ; 00167 00168 // name >> shape_id ; 00169 cob_3d_mapping::Polygon p; 00170 // for(size_t i=0;i<sha.shapes.size();++i) 00171 // { 00172 // if (sha.shapes[i].id == shape_id) 00173 // { 00174 // index = i; 00175 // } 00176 // } 00177 std::cout << "index is : " << index << "\n" ; 00178 cob_3d_mapping::fromROSMsg (sha.shapes.at(index), p); 00179 00180 quat.x() = (float)feedback->pose.orientation.x ; //normalized 00181 quat.y() = (float)feedback->pose.orientation.y ; 00182 quat.z() = (float)feedback->pose.orientation.z ; 00183 quat.w() = (float)feedback->pose.orientation.w ; 00184 00185 quat.normalize() ; 00186 00187 rotationMat = quat.toRotationMatrix() ; 00188 00189 normalVec << sha.shapes.at(index).params[0], //normalized 00190 sha.shapes.at(index).params[1], 00191 sha.shapes.at(index).params[2]; 00192 00193 newCentroid << (float)feedback->pose.position.x , 00194 (float)feedback->pose.position.y , 00195 (float)feedback->pose.position.z ; 00196 00197 00198 transSecondStep.block(0,0,3,3) << rotationMat ; 00199 transSecondStep.col(3).head(3) << newCentroid(0) , newCentroid(1), newCentroid(2) ; 00200 transSecondStep.row(3) << 0,0,0,1 ; 00201 00202 Eigen::Affine3f affineSecondStep(transSecondStep) ; 00203 00204 std::cout << "transfrom : " << "\n" << affineSecondStep.matrix() << "\n" ; 00205 00206 Eigen::Affine3f affineFinal(affineSecondStep*affineInit) ; 00207 Eigen::Matrix4f matFinal = (transSecondStep*transInitInv) ; 00208 00209 normalVecNew = (matFinal.block(0,0,3,3))* normalVec; 00210 // newCentroid = transFinal *OldCentroid ; 00211 00212 00213 sha.shapes.at(index).centroid.x = newCentroid(0) ; 00214 sha.shapes.at(index).centroid.y = newCentroid(1) ; 00215 sha.shapes.at(index).centroid.z = newCentroid(2) ; 00216 00217 00218 sha.shapes.at(index).params[0] = normalVecNew(0) ; 00219 sha.shapes.at(index).params[1] = normalVecNew(1) ; 00220 sha.shapes.at(index).params[2] = normalVecNew(2) ; 00221 00222 00223 std::cout << "transfromFinal : " << "\n" << affineFinal.matrix() << "\n" ; 00224 00225 pcl::PointCloud<pcl::PointXYZ> pc; 00226 pcl::PointXYZ pt; 00227 sensor_msgs::PointCloud2 pc2; 00228 00229 for(unsigned int j=0; j<p.contours.size(); j++) 00230 { 00231 for(unsigned int k=0; k<p.contours[j].size(); k++) 00232 { 00233 p.contours[j][k] = affineFinal * p.contours[j][k]; 00234 pt.x = p.contours[j][k][0] ; 00235 pt.y = p.contours[j][k][1] ; 00236 pt.z = p.contours[j][k][2] ; 00237 pc.push_back(pt) ; 00238 } 00239 } 00240 00241 pcl::toROSMsg (pc, pc2); 00242 sha.shapes.at(index).points.clear() ; 00243 sha.shapes.at(index).points.push_back (pc2); 00244 00245 // uncomment when using test_shape_array 00246 00247 // for(unsigned int i=0;i<sha.shapes.size();i++){ 00248 // map_msg.header = sha.shapes.at(i).header ; 00249 // map_msg.shapes.push_back(sha.shapes.at(i)) ; 00250 // } 00251 // shape_pub_.publish(map_msg); 00252 00253 // end uncomment 00254 00255 modified_shapes_.shapes.push_back(sha.shapes.at(index)); 00256 } 00257 } 00258 } 00259 00260 void ShapeVisualization::applyModifications(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 00261 { 00262 cob_3d_mapping_msgs::ModifyMap::Request req ; 00263 cob_3d_mapping_msgs::ModifyMap::Response res; 00264 visualization_msgs::InteractiveMarker imarker; 00265 stringstream aa; 00266 int index ; 00267 00268 /*****Modify shapes*****/ 00269 if (!modified_shapes_.shapes.empty()){ 00270 // ROS_INFO("modify action..."); 00271 for(unsigned int i=0;i<modified_shapes_.shapes.size();i++){ 00272 req.InMap.shapes.push_back(modified_shapes_.shapes.at(i)) ; 00273 /*erase the second marker created at the original position of the Marker*/ 00274 aa.str(""); 00275 aa.clear(); 00276 aa << "second_marker_" << modified_shapes_.shapes[i].id ; 00277 imarker.name = aa.str() ; 00278 im_server_->erase(imarker.name) ; 00279 im_server_->applyChanges(); 00280 /*end*/ 00281 } 00282 req.action = cob_3d_mapping_msgs::ModifyMapRequest::MODIFY ; 00283 std ::cout << "size of request: " << req.InMap.shapes.size() << "\n" ; 00284 if (ros::service::call("geometry_map/modify_map",req,res)) 00285 { 00286 std::cout << "calling ModifyMap service..." << "\n" ; 00287 } 00288 while (!req.InMap.shapes.empty()){ 00289 req.InMap.shapes.pop_back() ; 00290 modified_shapes_.shapes.pop_back() ; 00291 } 00292 } 00293 00294 /*****Delete shapes*****/ 00295 if (!deleted_markers_indices_.empty()){ 00296 00297 std::cout<< "deleted_markers_indices_ size : " << deleted_markers_indices_.size() << "\n" ; 00298 // ROS_INFO("delete action..."); 00299 req.action = cob_3d_mapping_msgs::ModifyMapRequest::DELETE ; 00300 for(unsigned int i=0;i<deleted_markers_indices_.size();i++){ 00301 /*erase the transparent marker*/ 00302 aa.str(""); 00303 aa.clear(); 00304 aa << "deleted_marker_" << deleted_markers_indices_.at(i) ; 00305 imarker.name = aa.str() ; 00306 im_server_->erase(imarker.name) ; 00307 im_server_->applyChanges(); 00308 /*end*/ 00309 for(unsigned int j=0;j<sha.shapes.size();++j) 00310 { 00311 if (sha.shapes[j].id == deleted_markers_indices_.at(i)) 00312 { 00313 index = j; 00314 } 00315 } 00316 req.InMap.shapes.push_back(sha.shapes.at(index)) ; 00317 } 00318 00319 if (ros::service::call("geometry_map/modify_map",req,res)) 00320 { 00321 std::cout << "calling ModifyMap service..." << "\n" ; 00322 } 00323 00324 while (!req.InMap.shapes.empty()){ 00325 req.InMap.shapes.pop_back() ; 00326 deleted_markers_indices_.pop_back() ; 00327 00328 } 00329 std::cout<< "deleted_markers_indices_ size : " << deleted_markers_indices_.size() << "\n" ; 00330 std::cout << "req size" << req.InMap.shapes.size() << "\n" ; 00331 } 00332 im_server_->applyChanges() ; 00333 } 00334 00335 void ShapeVisualization::resetAll(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 00336 { 00337 stringstream aa; 00338 modified_shapes_.shapes.clear() ; 00339 // std::cout <<"interacted_shapes_.size() = " << interacted_shapes_.size() <<"\n" ; 00340 00341 if(!interacted_shapes_.empty()) { 00342 for (unsigned int i=0; i< interacted_shapes_.size();i++) 00343 { 00344 unsigned int id = interacted_shapes_[i]; 00345 for (unsigned int j=0; j<v_sm_.size(); j++) 00346 { 00347 if(id == v_sm_[j]->getID()) 00348 v_sm_[j]->resetMarker(); 00349 // interacted_shapes_.pop_back(); 00350 } 00351 00352 } 00353 interacted_shapes_.clear(); 00354 } 00355 00356 if(!moved_shapes_indices_.empty()) { 00357 for (unsigned int i=0; i< moved_shapes_indices_.size();i++){ 00358 00359 unsigned int id = moved_shapes_indices_[i]; 00360 for (unsigned int j=0; j<v_sm_.size(); j++) 00361 { 00362 if(id == v_sm_[j]->getID()){ 00363 v_sm_[j]->hideArrows(0); 00364 // im_server_->applyChanges (); 00365 } 00366 } 00367 } 00368 moved_shapes_indices_.clear() ; 00369 } 00370 00371 if(!deleted_markers_indices_.empty()) { 00372 00373 for (unsigned int i=0; i< deleted_markers_indices_.size();i++){ 00374 unsigned int id = deleted_markers_indices_[i]; 00375 for (unsigned int j=0; j<v_sm_.size(); j++) 00376 { 00377 if(id == v_sm_[j]->getID()){ 00378 v_sm_[j]->setDeleted() ; 00379 aa.str(""); 00380 aa.clear() ; 00381 aa << "deleted_marker_"<< id ; 00382 im_server_->erase(aa.str()) ; 00383 //retrieve the deleted Marker 00384 v_sm_[j]->createInteractiveMarker(); 00385 im_server_->applyChanges (); 00386 00387 } 00388 } 00389 } 00390 deleted_markers_indices_.clear() ; 00391 } 00392 // im_server_->applyChanges (); 00393 } 00394 00395 void ShapeVisualization::moreOptions() 00396 { 00397 optionMenu(); 00398 visualization_msgs::Marker Text; 00399 00400 Text.type = visualization_msgs::Marker::TEXT_VIEW_FACING; 00401 Text.action = visualization_msgs::Marker::ADD; 00402 Text.lifetime = ros::Duration (); 00403 Text.header.frame_id = "/map" ; 00404 00405 Text.id = 0; 00406 Text.ns = "text"; 00407 00408 Text.text = "Click here for more options" ; 00409 // Scale 00410 Text.scale.x = 0.3; 00411 Text.scale.y = 0.3; 00412 Text.scale.z = 0.3; 00413 00414 // Pose 00415 Text.pose.position.x = 0; 00416 Text.pose.position.y = 0; 00417 Text.pose.position.z = 0.5; 00418 00419 Text.pose.orientation.x = 0; 00420 Text.pose.orientation.y = 0; 00421 Text.pose.orientation.z = 0; 00422 Text.pose.orientation.w = 1; 00423 00424 00425 00426 Text.color.r = 1; 00427 Text.color.g = 1; 00428 Text.color.b = 1; 00429 Text.color.a = 1; 00430 00431 /*Interactive Marker for the Text*/ 00432 00433 visualization_msgs::InteractiveMarker imarkerText; 00434 visualization_msgs::InteractiveMarkerControl im_ctrl_text_ ; 00435 im_ctrl_text_.always_visible = true ; 00436 im_ctrl_text_.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON; 00437 imarkerText.name = "Text" ; 00438 imarkerText.header = Text.header ; 00439 im_ctrl_text_.markers.push_back(Text); 00440 imarkerText.controls.push_back(im_ctrl_text_); 00441 00442 im_server_->insert (imarkerText); 00443 menu_handler_for_text_.apply (*im_server_,imarkerText.name); 00444 00445 } 00446 00447 void ShapeVisualization::displayAllNormals(const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) { 00448 00449 interactive_markers::MenuHandler::CheckState check_state; 00450 00451 menu_handler_for_text_.getCheckState (feedback->menu_entry_id, check_state); 00452 if (check_state == interactive_markers::MenuHandler::UNCHECKED) 00453 { 00454 ROS_INFO ("Displaying all Normals..."); 00455 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::CHECKED); 00456 00457 for (unsigned int j=0; j<v_sm_.size(); j++) 00458 { 00459 v_sm_[j]->displayNormal(); 00460 } 00461 } 00462 else if (check_state == interactive_markers::MenuHandler::CHECKED) 00463 { 00464 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::UNCHECKED); 00465 ROS_INFO ("Deleting all Normals..."); 00466 for (unsigned int j=0; j<v_sm_.size(); j++) 00467 { 00468 v_sm_[j]->hideNormal(0); 00469 } 00470 } 00471 menu_handler_for_text_.reApply (*im_server_); 00472 im_server_->applyChanges (); 00473 } 00474 00475 void 00476 ShapeVisualization::displayAllCentroids (const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback) 00477 { 00478 00479 interactive_markers::MenuHandler::CheckState check_state; 00480 menu_handler_for_text_.getCheckState (feedback->menu_entry_id, check_state); 00481 00482 if (check_state == interactive_markers::MenuHandler::UNCHECKED) 00483 { 00484 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::CHECKED); 00485 for (unsigned int j=0; j<v_sm_.size(); j++) 00486 { 00487 v_sm_[j]->displayCentroid(); 00488 } 00489 } 00490 else if (check_state == interactive_markers::MenuHandler::CHECKED) 00491 { 00492 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::UNCHECKED); 00493 for (unsigned int i=0; i< sha.shapes.size();i++) 00494 { 00495 00496 for (unsigned int j=0; j<v_sm_.size(); j++) 00497 { 00498 v_sm_[j]->hideCentroid(0); 00499 } 00500 } 00501 } 00502 menu_handler_for_text_.reApply (*im_server_); 00503 im_server_->applyChanges (); 00504 } 00505 00506 void 00507 ShapeVisualization::displayAllContours (const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback){ 00508 00509 interactive_markers::MenuHandler::CheckState check_state; 00510 menu_handler_for_text_.getCheckState (feedback->menu_entry_id, check_state); 00511 00512 if (check_state == interactive_markers::MenuHandler::UNCHECKED) 00513 { 00514 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::CHECKED); 00515 for (unsigned int j=0; j<v_sm_.size(); j++) 00516 { 00517 v_sm_[j]->displayContour(); 00518 } 00519 } 00520 else if (check_state == interactive_markers::MenuHandler::CHECKED) 00521 { 00522 menu_handler_for_text_.setCheckState (feedback->menu_entry_id, interactive_markers::MenuHandler::UNCHECKED); 00523 for (unsigned int i=0; i< sha.shapes.size();i++) 00524 { 00525 00526 for (unsigned int j=0; j<v_sm_.size(); j++) 00527 { 00528 v_sm_[j]->hideContour(0); 00529 } 00530 } 00531 } 00532 menu_handler_for_text_.reApply (*im_server_); 00533 im_server_->applyChanges (); 00534 } 00535 00536 void ShapeVisualization::optionMenu() { 00537 00538 // ROS_INFO("Creating menu for the text...") ; 00539 00540 interactive_markers::MenuHandler::EntryHandle eh_1, eh_2 , eh_3 ,eh_4 ,eh_5, eh_6; 00541 00542 eh_1 = menu_handler_for_text_.insert ("Menu"); 00543 eh_2 = menu_handler_for_text_.insert (eh_1, "All Normals",boost::bind (&ShapeVisualization::displayAllNormals, this, _1)); 00544 eh_3 = menu_handler_for_text_.insert (eh_1, "All Centroids",boost::bind (&ShapeVisualization::displayAllCentroids, this, _1)); 00545 eh_4 = menu_handler_for_text_.insert (eh_1, "All Contours",boost::bind (&ShapeVisualization::displayAllContours, this, _1)); 00546 eh_5 = menu_handler_for_text_.insert (eh_1, "Apply map modifications",boost::bind (&ShapeVisualization::applyModifications, this, _1)); 00547 eh_6 = menu_handler_for_text_.insert (eh_1, "Reset all Controls",boost::bind (&ShapeVisualization::resetAll, this, _1)); 00548 00549 menu_handler_for_text_.setVisible (eh_1, true); 00550 menu_handler_for_text_.setCheckState (eh_1, interactive_markers::MenuHandler::NO_CHECKBOX); 00551 menu_handler_for_text_.setVisible (eh_2, true); 00552 menu_handler_for_text_.setCheckState (eh_2, interactive_markers::MenuHandler::UNCHECKED); 00553 menu_handler_for_text_.setVisible (eh_3, true); 00554 menu_handler_for_text_.setCheckState (eh_3, interactive_markers::MenuHandler::UNCHECKED); 00555 menu_handler_for_text_.setVisible (eh_4, true); 00556 menu_handler_for_text_.setCheckState (eh_4, interactive_markers::MenuHandler::UNCHECKED); 00557 menu_handler_for_text_.setVisible (eh_5, true); 00558 menu_handler_for_text_.setCheckState (eh_5, interactive_markers::MenuHandler::NO_CHECKBOX); 00559 menu_handler_for_text_.setVisible (eh_6, true); 00560 menu_handler_for_text_.setCheckState (eh_6, interactive_markers::MenuHandler::NO_CHECKBOX); 00561 00562 00563 } 00564 00565 void 00566 ShapeVisualization::shapeArrayCallback (const cob_3d_mapping_msgs::ShapeArrayPtr& sa) 00567 { 00568 // ctr_for_shape_indexes = 0 ; 00569 v_sm_.clear(); 00570 sha.shapes.clear() ; 00571 im_server_->applyChanges(); 00572 ROS_INFO("shape array with %d shapes received", sa->shapes.size()); 00573 00574 for (unsigned int i = 0; i < sa->shapes.size (); i++) 00575 { 00576 sha.shapes.push_back(sa->shapes[i]); 00577 sha.shapes[i].id = sa->shapes[i].id; 00578 00579 std::cout << "shape id: " << sa->shapes[i].id << "\n" ; 00580 boost::shared_ptr<ShapeMarker> sm(new ShapeMarker(im_server_, sa->shapes[i],moved_shapes_indices_ 00581 ,interacted_shapes_,deleted_markers_indices_,false,false)) ;//,deleted_)); 00582 v_sm_.push_back(sm); 00583 marker_pub_.publish(sm->getMarker()); 00584 } 00585 // im_server_->applyChanges(); //update changes 00586 } 00587 00588 int 00589 main (int argc, char** argv) 00590 { 00591 ros::init (argc, argv, "shape_visualization"); 00592 ROS_INFO("shape_visualization node started...."); 00593 ShapeVisualization sv; 00594 00595 ros::spin(); 00596 }