00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "object_recognition_gui/object_recognition_rviz_ui.h"
00031
00032 #include "rviz_interaction_tools/image_tools.h"
00033
00034 #include "rviz_interaction_tools/mesh_object_switcher.h"
00035 #include "rviz_interaction_tools/mesh_object.h"
00036 #include "rviz_interaction_tools/camera_tools.h"
00037
00038 #include <OGRE/OgreManualObject.h>
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include <OGRE/OgreRenderWindow.h>
00041 #include <OGRE/OgreSceneNode.h>
00042 #include <OGRE/OgreSceneManager.h>
00043 #include <OGRE/OgreRoot.h>
00044
00045 #include <rviz/render_panel.h>
00046 #include <rviz/window_manager_interface.h>
00047 #include <rviz/visualization_manager.h>
00048
00049 #include "rviz_interaction_tools/image_overlay.h"
00050 #include "rviz_interaction_tools/camera_tools.h"
00051 #include "rviz_interaction_tools/unique_string_manager.h"
00052
00053 #include "ui_object_recognition_frame.h"
00054
00055 using namespace rviz_interaction_tools;
00056
00057 namespace object_recognition_gui
00058 {
00059
00060
00061 static const std::string VALID_MAT_NAME = "object_recognition_valid";
00062 static const std::string VALID_SEL_MAT_NAME = "object_recognition_valid_selected";
00063 static const std::string INVALID_MAT_NAME = "object_recognition_invalid";
00064 static const std::string INVALID_SEL_MAT_NAME = "object_recognition_invalid_selected";
00065
00066
00067 ObjectRecognitionRvizUI::ObjectRecognitionRvizUI(rviz::VisualizationManager *visualization_manager) :
00068 QWidget(),
00069 object_recognition_server_(0),
00070 ui_( new Ui::ObjectRecognitionFrame )
00071 {
00072 ui_->setupUi( this );
00073 render_panel_ = ui_->render_panel_;
00074 connect( render_panel_, SIGNAL( mouseEvent( QMouseEvent* )),
00075 this, SLOT( onRenderWindowMouseEvent( QMouseEvent* )));
00076 connect( ui_->cancel, SIGNAL( clicked() ), this, SLOT( cancelButtonClicked() ));
00077 connect( ui_->ok, SIGNAL( clicked() ), this, SLOT( acceptButtonClicked() ));
00078
00079 UniqueStringManager usm;
00080
00081
00082 scene_manager_ = Ogre::Root::getSingleton().createSceneManager( Ogre::ST_GENERIC, usm.unique("ObjectRecognitionRvizUI") );
00083
00084 scene_root_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00085
00086 image_overlay_ = new rviz_interaction_tools::ImageOverlay( scene_root_, Ogre::RENDER_QUEUE_BACKGROUND );
00087
00088 setupRenderPanel( visualization_manager );
00089
00090 createMaterials();
00091
00092 ray_scene_query_ = scene_manager_->createRayQuery(Ogre::Ray());
00093 }
00094
00095 void ObjectRecognitionRvizUI::showBoundingBoxes( bool show )
00096 {
00097 scene_manager_->showBoundingBoxes(show);
00098 }
00099
00100 bool ObjectRecognitionRvizUI::getShowBoundingBoxes()
00101 {
00102 return scene_manager_->getShowBoundingBoxes();
00103 }
00104
00105 ObjectRecognitionRvizUI::~ObjectRecognitionRvizUI()
00106 {
00107 if ( object_recognition_server_ )
00108 {
00109 stopActionServer();
00110 }
00111
00112 cleanupAndHide();
00113
00114 scene_manager_->destroyQuery( ray_scene_query_ );
00115
00116 render_panel_->getRenderWindow()->setActive(false);
00117
00118 delete render_panel_;
00119 delete image_overlay_;
00120 delete ui_;
00121 }
00122
00123
00124 void ObjectRecognitionRvizUI::cleanupAndHide()
00125 {
00126 for ( size_t m=0; m<mesh_switchers_.size(); ++m )
00127 {
00128 delete mesh_switchers_[m];
00129 }
00130 mesh_switchers_.clear();
00131 hide();
00132 }
00133
00134
00135 void ObjectRecognitionRvizUI::setupRenderPanel( rviz::VisualizationManager *visualization_manager )
00136 {
00137 render_panel_->initialize(scene_manager_, visualization_manager);
00138
00139 render_panel_->setAutoRender(false);
00140 render_panel_->getViewport()->setOverlaysEnabled(false);
00141 render_panel_->getViewport()->setClearEveryFrame(true);
00142 render_panel_->getRenderWindow()->setAutoUpdated(false);
00143 render_panel_->getRenderWindow()->setActive(true);
00144
00145
00146 render_panel_->getCamera()->setPosition(0.0, 0.0, 0.0);
00147 render_panel_->getCamera()->lookAt(Ogre::Vector3(0, 0, 1));
00148 render_panel_->getCamera()->roll(Ogre::Radian(3.141592653));
00149 render_panel_->getCamera()->setFOVy(Ogre::Radian(0.518));
00150 render_panel_->getCamera()->setAspectRatio(640.0 / 480.0);
00151 render_panel_->getCamera()->setNearClipDistance( 0.01f );
00152 }
00153
00154
00155 void ObjectRecognitionRvizUI::createMaterials()
00156 {
00157 Ogre::MaterialPtr white = Ogre::MaterialManager::getSingleton().getByName("BaseWhiteNoLighting");
00158
00159 Ogre::Pass *pass;
00160
00161
00162
00163
00164 Ogre::MaterialPtr valid_mat = white->clone( VALID_MAT_NAME );
00165 pass = valid_mat->getTechnique(0)->getPass(0);
00166
00167 pass->setPolygonMode( Ogre::PM_WIREFRAME );
00168 pass->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00169 pass->setDepthWriteEnabled(false);
00170 pass->setDepthCheckEnabled(false);
00171 pass->setLightingEnabled(true);
00172 pass->setCullingMode( Ogre::CULL_NONE );
00173 pass->setAmbient(0.0, 0.0, 0.0);
00174 pass->setDiffuse(0.0, 0.0, 0.0, 0.3);
00175 pass->setSpecular(0.0, 0.0, 0.0, 0.3);
00176
00177 pass->setSelfIllumination( 0.0, 0.9, 0.0 );
00178
00179
00180 pass = valid_mat->clone( VALID_SEL_MAT_NAME )->getTechnique(0)->getPass(0);
00181 pass->setSelfIllumination( 0.4, 1.0, 0.4 );
00182
00183
00184 pass = valid_mat->clone( INVALID_MAT_NAME )->getTechnique(0)->getPass(0);
00185 pass->setSelfIllumination( 0.9, 0.0, 0.0 );
00186
00187
00188 pass = valid_mat->clone( INVALID_SEL_MAT_NAME )->getTechnique(0)->getPass(0);
00189 pass->setSelfIllumination( 1.0, 0.4, 0.4 );
00190 }
00191
00192
00193 void ObjectRecognitionRvizUI::parseMeshes(const std::vector<object_recognition_gui::ModelHypothesisList> &model_hyp_list)
00194 {
00195 ROS_ASSERT( mesh_switchers_.size() == 0 );
00196
00197
00198 int num_models = model_hyp_list.size();
00199 mesh_switchers_.resize(num_models);
00200 for ( int m=0; m<num_models; ++m )
00201 {
00202 const std::vector<object_recognition_gui::ModelHypothesis> &hyp_list =
00203 model_hyp_list[m].hypotheses;
00204
00205 int num_hyp = hyp_list.size();
00206 mesh_switchers_[m] = new MeshObjectSwitcher( VALID_MAT_NAME, VALID_SEL_MAT_NAME, INVALID_MAT_NAME, INVALID_SEL_MAT_NAME );
00207
00208 if ( hyp_list.size() == 0 || hyp_list[0].mesh.triangles.size() == 0 )
00209 {
00210 continue;
00211 }
00212
00213 for ( int h=0; h<num_hyp; ++h )
00214 {
00215 const arm_navigation_msgs::Shape& mesh = hyp_list[h].mesh;
00216 const geometry_msgs::Pose pose = hyp_list[h].pose.pose;
00217 #if 0
00218 ROS_INFO_STREAM( "Model " << m << ", hypothesis " << h
00219 << ") has " << mesh.triangles.size()/3 << " triangles and "
00220 << mesh.vertices.size() << " vertices." );
00221 ROS_INFO_STREAM( " Position:" << pose.position.x << " "
00222 << pose.position.y << " " << pose.position.z <<
00223 ". Orientation: " << pose.orientation.w << " " << pose.orientation.x
00224 << " " << pose.orientation.y << " " << pose.orientation.z );
00225 #endif
00226 MeshObject* mesh_object = new MeshObject( scene_manager_, scene_root_ );
00227
00228 std::ostringstream s;
00229 s << "obj_rec model " << m << " hypothesis " << h;
00230 std::string name = s.str();
00231
00232 mesh_object->loadMesh( name, mesh );
00233 mesh_object->setPose( pose );
00234
00235 Ogre::Entity* entity = mesh_object->getEntity();
00236 entity->getUserObjectBindings().setUserAny( "model", Ogre::Any(m) );
00237 entity->setRenderQueueGroup(Ogre::RENDER_QUEUE_MAIN);
00238
00239 mesh_switchers_[m]->addObject( mesh_object );
00240 }
00241
00242 mesh_switchers_[m]->setValid( model_hyp_list[m].accept );
00243 mesh_switchers_[m]->setVisible( 0 );
00244 }
00245 }
00246
00247
00248 void ObjectRecognitionRvizUI::update(float wall_dt, float ros_dt)
00249 {
00250 render_panel_->getRenderWindow()->update();
00251 }
00252
00253
00254 void ObjectRecognitionRvizUI::onRenderWindowMouseEvent( QMouseEvent* event )
00255 {
00256 ROS_ASSERT( object_recognition_server_->isActive() );
00257
00258 int x = event->x();
00259 int y = event->y();
00260
00261 QSize size = render_panel_->size();
00262
00263
00264 Ogre::Ray mouse_ray = render_panel_->getCamera()->getCameraToViewportRay(x/float(size.width()), y/float(size.height()));
00265 ray_scene_query_->setRay( mouse_ray );
00266
00267 for ( size_t m=0; m<mesh_switchers_.size(); ++m )
00268 {
00269 mesh_switchers_[m]->setSelected(false);
00270 }
00271
00272
00273 ray_scene_query_->setSortByDistance(true);
00274 Ogre::RaySceneQueryResult& result = ray_scene_query_->execute();
00275 Ogre::RaySceneQueryResult::iterator iter = result.begin();
00276
00277 int i=0;
00278 while( iter != result.end() )
00279 {
00280 Ogre::MovableObject* movable_object = iter->movable;
00281 if ( movable_object )
00282 {
00283 Ogre::Any model_any = movable_object->getUserObjectBindings().getUserAny( "model" );
00284
00285 if ( !model_any.isEmpty() )
00286 {
00287 int model = Ogre::any_cast<int>(model_any);
00288
00289
00290 if ( model >=0 && model < (int)mesh_switchers_.size() )
00291 {
00292 mesh_switchers_[model]->setSelected(true);
00293
00294 if ( mesh_switchers_[model]->isValid() )
00295 {
00296 if (event->type() == QEvent::MouseButtonPress && event->button() == Qt::LeftButton)
00297 {
00298 mesh_switchers_[model]->next();
00299 }
00300 else if (event->type() == QEvent::MouseButtonPress && event->button() == Qt::RightButton)
00301 {
00302 mesh_switchers_[model]->setValid( false );
00303 }
00304 }
00305 else
00306 {
00307 if ( event->type() == QEvent::MouseButtonPress )
00308 {
00309 mesh_switchers_[model]->setValid( true );
00310 }
00311 }
00312 }
00313 break;
00314 }
00315 }
00316
00317 i++;
00318 iter++;
00319 }
00320 }
00321
00322
00323 void ObjectRecognitionRvizUI::acceptButtonClicked()
00324 {
00325 ObjectRecognitionGuiResult result;
00326
00327 result.selected_hypothesis_indices.resize( mesh_switchers_.size() );
00328 for ( unsigned i=0; i<mesh_switchers_.size(); ++i )
00329 {
00330 result.selected_hypothesis_indices[i] =
00331 mesh_switchers_[i]->isValid() ? mesh_switchers_[i]->getVisible() : -1;
00332 }
00333
00334 object_recognition_server_->setSucceeded(result);
00335 cleanupAndHide();
00336 }
00337
00338
00339 void ObjectRecognitionRvizUI::cancelButtonClicked()
00340 {
00341 object_recognition_server_->setAborted();
00342 cleanupAndHide();
00343 }
00344
00345
00346 void ObjectRecognitionRvizUI::startActionServer( ros::NodeHandle &node_handle )
00347 {
00348 if ( object_recognition_server_ )
00349 {
00350 ROS_ERROR( "ObjectRecognitionGuiAction server already started!" );
00351 return;
00352 }
00353
00354
00355 object_recognition_server_ =
00356 new actionlib::SimpleActionServer<ObjectRecognitionGuiAction>( node_handle, "object_recognition_popup", false );
00357
00358 object_recognition_server_->registerGoalCallback( boost::bind(&ObjectRecognitionRvizUI::acceptNewGoal, this) );
00359 object_recognition_server_->registerPreemptCallback( boost::bind(&ObjectRecognitionRvizUI::preempt, this) );
00360
00361 object_recognition_server_->start();
00362 }
00363
00364
00365 void ObjectRecognitionRvizUI::stopActionServer()
00366 {
00367 if ( !object_recognition_server_ )
00368 {
00369 ROS_ERROR("ObjectRecognitionGuiAction server cannot be stopped because it is not running.");
00370 return;
00371 }
00372
00373
00374 if ( object_recognition_server_->isActive() )
00375 {
00376 ROS_WARN("Aborting ObjectRecognitionGuiAction goal.");
00377 object_recognition_server_->setAborted();
00378 cleanupAndHide();
00379 }
00380
00381 delete object_recognition_server_;
00382 object_recognition_server_ = 0;
00383 }
00384
00385 void ObjectRecognitionRvizUI::acceptNewGoal()
00386 {
00387 const ObjectRecognitionGuiGoal::ConstPtr &goal = object_recognition_server_->acceptNewGoal();
00388
00389 rviz_interaction_tools::updateCamera( render_panel_->getCamera(), goal->camera_info );
00390
00391 image_overlay_->setImage( goal->image );
00392 image_overlay_->update();
00393
00394 parseMeshes( goal->model_hypotheses );
00395
00396 show();
00397 }
00398
00399 void ObjectRecognitionRvizUI::preempt()
00400 {
00401 object_recognition_server_->setPreempted();
00402 cleanupAndHide();
00403 }
00404
00405
00406
00407
00408 }