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 "camera_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/render_panel.h"
00033 #include "rviz/properties/property.h"
00034 #include "rviz/properties/property_manager.h"
00035 #include "rviz/window_manager_interface.h"
00036 #include "rviz/frame_manager.h"
00037 #include "rviz/validate_floats.h"
00038 #include "rviz/panel_dock_widget.h"
00039 #include "rviz/display_wrapper.h"
00040
00041 #include <tf/transform_listener.h>
00042
00043 #include <boost/bind.hpp>
00044
00045 #include <ogre_tools/axes.h>
00046 #include <ogre_tools/render_system.h>
00047
00048 #include <OGRE/OgreSceneNode.h>
00049 #include <OGRE/OgreSceneManager.h>
00050 #include <OGRE/OgreRectangle2D.h>
00051 #include <OGRE/OgreMaterialManager.h>
00052 #include <OGRE/OgreTextureManager.h>
00053 #include <OGRE/OgreViewport.h>
00054 #include <OGRE/OgreRenderWindow.h>
00055 #include <OGRE/OgreManualObject.h>
00056 #include <OGRE/OgreRoot.h>
00057 #include <OGRE/OgreRenderSystem.h>
00058
00059 namespace rviz
00060 {
00061
00062 static const std::string IMAGE_POS_BACKGROUND = "background";
00063 static const std::string IMAGE_POS_OVERLAY = "overlay";
00064 static const std::string IMAGE_POS_BOTH = "background & overlay";
00065
00066 bool validateFloats(const sensor_msgs::CameraInfo& msg)
00067 {
00068 bool valid = true;
00069 valid = valid && validateFloats(msg.D);
00070 valid = valid && validateFloats(msg.K);
00071 valid = valid && validateFloats(msg.R);
00072 valid = valid && validateFloats(msg.P);
00073 return valid;
00074 }
00075
00076 CameraDisplay::RenderListener::RenderListener(CameraDisplay* display)
00077 : display_(display)
00078 {
00079 }
00080
00081 void CameraDisplay::RenderListener::preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00082 {
00083 display_->bg_scene_node_->setVisible( display_->image_position_ == IMAGE_POS_BACKGROUND || display_->image_position_ == IMAGE_POS_BOTH );
00084 display_->fg_scene_node_->setVisible( display_->image_position_ == IMAGE_POS_OVERLAY || display_->image_position_ == IMAGE_POS_BOTH );
00085 }
00086
00087 void CameraDisplay::RenderListener::postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00088 {
00089 display_->bg_scene_node_->setVisible(false);
00090 display_->fg_scene_node_->setVisible(false);
00091 }
00092
00093 CameraDisplay::Panel::Panel( CameraDisplay* display, QWidget* parent )
00094 : RenderPanel( ogre_tools::RenderSystem::get(), display, parent )
00095 , display_( display )
00096 , render_listener_( display )
00097 {
00098 }
00099
00100 void CameraDisplay::Panel::showEvent( QShowEvent* event )
00101 {
00102 RenderPanel::showEvent( event );
00103 render_window_->addListener( &render_listener_ );
00104 render_window_->setAutoUpdated(false);
00105 render_window_->setActive( active_ );
00106 display_->setTopic( display_->getTopic() );
00107 }
00108
00109 void CameraDisplay::Panel::setActive( bool active )
00110 {
00111 active_ = active;
00112 if( render_window_ != 0 )
00113 {
00114 render_window_->setActive( active_ );
00115 }
00116 }
00117
00118 void CameraDisplay::Panel::updateRenderWindow()
00119 {
00120 if( render_window_ != 0 )
00121 {
00122 render_window_->update();
00123 }
00124 }
00125
00126 CameraDisplay::CameraDisplay()
00127 : Display()
00128 , zoom_(1)
00129 , transport_("raw")
00130 , image_position_(IMAGE_POS_BOTH)
00131 , caminfo_tf_filter_( 0 )
00132 , new_caminfo_(false)
00133 , texture_(update_nh_)
00134 , render_panel_( 0 )
00135 , force_render_(false)
00136 , panel_container_( 0 )
00137 {
00138 }
00139
00140 CameraDisplay::~CameraDisplay()
00141 {
00142 unsubscribe();
00143 caminfo_tf_filter_->clear();
00144
00145 if( render_panel_ )
00146 {
00147 if( panel_container_ )
00148 {
00149 delete panel_container_;
00150 }
00151 else
00152 {
00153 delete render_panel_;
00154 }
00155 }
00156
00157 delete bg_screen_rect_;
00158 delete fg_screen_rect_;
00159
00160 bg_scene_node_->getParentSceneNode()->removeAndDestroyChild(bg_scene_node_->getName());
00161 fg_scene_node_->getParentSceneNode()->removeAndDestroyChild(fg_scene_node_->getName());
00162
00163 delete caminfo_tf_filter_;
00164 }
00165
00166 void CameraDisplay::onInitialize()
00167 {
00168 caminfo_tf_filter_ = new tf::MessageFilter<sensor_msgs::CameraInfo>(*vis_manager_->getTFClient(), "", 2, update_nh_);
00169
00170 bg_scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00171 fg_scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00172
00173 {
00174 static int count = 0;
00175 std::stringstream ss;
00176 ss << "CameraDisplayObject" << count++;
00177
00178
00179 bg_screen_rect_ = new Ogre::Rectangle2D(true);
00180 bg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00181
00182 ss << "Material";
00183 bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00184 bg_material_->setDepthWriteEnabled(false);
00185
00186 bg_material_->setReceiveShadows(false);
00187 bg_material_->setDepthCheckEnabled(false);
00188
00189 bg_material_->getTechnique(0)->setLightingEnabled(false);
00190 Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
00191 tu->setTextureName(texture_.getTexture()->getName());
00192 tu->setTextureFiltering( Ogre::TFO_NONE );
00193 tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
00194
00195 bg_material_->setCullingMode(Ogre::CULL_NONE);
00196 bg_material_->setSceneBlending( Ogre::SBT_REPLACE );
00197
00198 Ogre::AxisAlignedBox aabInf;
00199 aabInf.setInfinite();
00200
00201 bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
00202 bg_screen_rect_->setBoundingBox(aabInf);
00203 bg_screen_rect_->setMaterial(bg_material_->getName());
00204
00205 bg_scene_node_->attachObject(bg_screen_rect_);
00206 bg_scene_node_->setVisible(false);
00207
00208
00209 fg_screen_rect_ = new Ogre::Rectangle2D(true);
00210 fg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00211
00212 fg_material_ = bg_material_->clone( ss.str()+"fg" );
00213 fg_screen_rect_->setBoundingBox(aabInf);
00214 fg_screen_rect_->setMaterial(fg_material_->getName());
00215
00216 fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00217 fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00218
00219 fg_scene_node_->attachObject(fg_screen_rect_);
00220 fg_scene_node_->setVisible(false);
00221 }
00222
00223 setAlpha( 0.5f );
00224
00225 QWidget* parent = 0;
00226
00227 WindowManagerInterface* wm = vis_manager_->getWindowManager();
00228 if( wm )
00229 {
00230 parent = wm->getParentWindow();
00231 }
00232
00233 render_panel_ = new Panel( this, parent );
00234 render_panel_->resize( 640, 480 );
00235 render_panel_->initialize(vis_manager_->getSceneManager(), vis_manager_);
00236 if( wm )
00237 {
00238 panel_container_ = wm->addPane(name_, render_panel_);
00239 panel_container_->hide();
00240 }
00241 render_panel_->setAutoRender(false);
00242 render_panel_->setOverlaysEnabled(false);
00243 render_panel_->getCamera()->setNearClipDistance( 0.01f );
00244
00245 caminfo_tf_filter_->connectInput(caminfo_sub_);
00246 caminfo_tf_filter_->registerCallback(boost::bind(&CameraDisplay::caminfoCallback, this, _1));
00247 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
00248
00249 if( panel_container_ )
00250 {
00251
00252 connect( panel_container_, SIGNAL( visibilityChanged( bool ) ), this, SLOT( setWrapperEnabled( bool )));
00253 }
00254 }
00255
00256 void CameraDisplay::setWrapperEnabled( bool enabled )
00257 {
00258
00259
00260 DisplayWrapper* wrapper = vis_manager_->getDisplayWrapper( this );
00261 if( wrapper != NULL )
00262 {
00263 wrapper->setEnabled( enabled );
00264 }
00265 }
00266
00267 void CameraDisplay::onEnable()
00268 {
00269 subscribe();
00270 if( render_panel_->parentWidget() == 0 )
00271 {
00272 render_panel_->show();
00273 }
00274 else
00275 {
00276 panel_container_->show();
00277 }
00278
00279 render_panel_->setActive(true);
00280 }
00281
00282 void CameraDisplay::onDisable()
00283 {
00284 render_panel_->setActive(false);
00285
00286 if( render_panel_->parentWidget() == 0 )
00287 {
00288 if( render_panel_->isVisible() )
00289 {
00290 render_panel_->hide();
00291 }
00292 }
00293 else
00294 {
00295 if( panel_container_->isVisible() )
00296 {
00297 panel_container_->hide();
00298 }
00299 }
00300
00301 unsubscribe();
00302
00303 clear();
00304 }
00305
00306 void CameraDisplay::subscribe()
00307 {
00308 if ( !isEnabled() )
00309 {
00310 return;
00311 }
00312
00313 texture_.setTopic(topic_);
00314
00315
00316 std::string caminfo_topic = "camera_info";
00317 size_t pos = topic_.rfind('/');
00318 if (pos != std::string::npos)
00319 {
00320 std::string ns = topic_;
00321 ns.erase(pos);
00322
00323 caminfo_topic = ns + "/" + caminfo_topic;
00324 }
00325
00326 caminfo_sub_.subscribe(update_nh_, caminfo_topic, 1);
00327 }
00328
00329 void CameraDisplay::unsubscribe()
00330 {
00331 texture_.setTopic("");
00332 caminfo_sub_.unsubscribe();
00333 }
00334
00335 void CameraDisplay::setAlpha( float alpha )
00336 {
00337 alpha_ = alpha;
00338
00339 Ogre::Pass* pass = fg_material_->getTechnique(0)->getPass(0);
00340 if (pass->getNumTextureUnitStates() > 0)
00341 {
00342 Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState(0);
00343 tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha_ );
00344 }
00345 else
00346 {
00347 fg_material_->setAmbient(Ogre::ColourValue(0.0f, 1.0f, 1.0f, alpha_));
00348 fg_material_->setDiffuse(Ogre::ColourValue(0.0f, 1.0f, 1.0f, alpha_));
00349 }
00350
00351 propertyChanged(alpha_property_);
00352 force_render_ = true;
00353 causeRender();
00354 }
00355
00356 void CameraDisplay::setZoom( float zoom )
00357 {
00358 if (fabs(zoom) < .00001 || fabs(zoom) > 100000)
00359 {
00360 return;
00361 }
00362 zoom_ = zoom;
00363
00364 propertyChanged(zoom_property_);
00365
00366 force_render_ = true;
00367 causeRender();
00368 }
00369
00370 void CameraDisplay::setTopic( const std::string& topic )
00371 {
00372 unsubscribe();
00373
00374 topic_ = topic;
00375 clear();
00376
00377 subscribe();
00378
00379 propertyChanged(topic_property_);
00380 }
00381
00382 void CameraDisplay::setTransport(const std::string& transport)
00383 {
00384 transport_ = transport;
00385
00386 texture_.setTransportType(transport);
00387
00388 propertyChanged(transport_property_);
00389 }
00390
00391 void CameraDisplay::setImagePosition(const std::string& image_position)
00392 {
00393 image_position_ = image_position;
00394
00395 propertyChanged(image_position_property_);
00396
00397 force_render_ = true;
00398 causeRender();
00399 }
00400
00401 void CameraDisplay::clear()
00402 {
00403 texture_.clear();
00404 force_render_ = true;
00405 causeRender();
00406
00407 new_caminfo_ = false;
00408 current_caminfo_.reset();
00409
00410 setStatus(status_levels::Warn, "CameraInfo", "No CameraInfo received on [" + caminfo_sub_.getTopic() + "]. Topic may not exist.");
00411 setStatus(status_levels::Warn, "Image", "No Image received");
00412
00413 render_panel_->getCamera()->setPosition(Ogre::Vector3(999999, 999999, 999999));
00414 }
00415
00416 void CameraDisplay::updateStatus()
00417 {
00418 if (texture_.getImageCount() == 0)
00419 {
00420 setStatus(status_levels::Warn, "Image", "No image received");
00421 }
00422 else
00423 {
00424 std::stringstream ss;
00425 ss << texture_.getImageCount() << " images received";
00426 setStatus(status_levels::Ok, "Image", ss.str());
00427 }
00428 }
00429
00430 void CameraDisplay::update(float wall_dt, float ros_dt)
00431 {
00432 updateStatus();
00433
00434 try
00435 {
00436 if (texture_.update() || force_render_)
00437 {
00438 float old_alpha = alpha_;
00439 if (texture_.getImageCount() == 0)
00440 {
00441 alpha_ = 1.0f;
00442 }
00443
00444 updateCamera();
00445 render_panel_->updateRenderWindow();
00446 alpha_ = old_alpha;
00447
00448 force_render_ = false;
00449 }
00450 }
00451 catch (UnsupportedImageEncoding& e)
00452 {
00453 setStatus(status_levels::Error, "Image", e.what());
00454 }
00455 }
00456
00457 void CameraDisplay::updateCamera()
00458 {
00459 sensor_msgs::CameraInfo::ConstPtr info;
00460 sensor_msgs::Image::ConstPtr image;
00461 {
00462 boost::mutex::scoped_lock lock(caminfo_mutex_);
00463
00464 info = current_caminfo_;
00465 image = texture_.getImage();
00466 }
00467
00468 if (!info || !image)
00469 {
00470 return;
00471 }
00472
00473 if (!validateFloats(*info))
00474 {
00475 setStatus(status_levels::Error, "CameraInfo", "Contains invalid floating point values (nans or infs)");
00476 return;
00477 }
00478
00479 Ogre::Vector3 position;
00480 Ogre::Quaternion orientation;
00481 vis_manager_->getFrameManager()->getTransform(image->header, position, orientation);
00482
00483
00484 orientation = orientation * Ogre::Quaternion(Ogre::Degree(180), Ogre::Vector3::UNIT_X);
00485
00486 float img_width = info->width;
00487 float img_height = info->height;
00488
00489
00490 if (img_width == 0)
00491 {
00492 ROS_DEBUG("Malformed CameraInfo on camera [%s], width = 0", getName().c_str());
00493
00494 img_width = texture_.getWidth();
00495 }
00496
00497 if (img_height == 0)
00498 {
00499 ROS_DEBUG("Malformed CameraInfo on camera [%s], height = 0", getName().c_str());
00500
00501 img_height = texture_.getHeight();
00502 }
00503
00504 if (img_height == 0.0 || img_width == 0.0)
00505 {
00506 setStatus(status_levels::Error, "CameraInfo", "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)");
00507 return;
00508 }
00509
00510 double fx = info->P[0];
00511 double fy = info->P[5];
00512
00513 float win_width = render_panel_->width();
00514 float win_height = render_panel_->height();
00515 float zoom_x = zoom_;
00516 float zoom_y = zoom_;
00517
00518
00519 if ( win_width != 0 && win_height != 0 )
00520 {
00521 float img_aspect = (img_width/fx) / (img_height/fy);
00522 float win_aspect = win_width / win_height;
00523
00524 if ( img_aspect > win_aspect )
00525 {
00526 zoom_y = zoom_y / img_aspect * win_aspect;
00527 }
00528 else
00529 {
00530 zoom_x = zoom_x / win_aspect * img_aspect;
00531 }
00532 }
00533
00534
00535 double tx = -1 * (info->P[3] / fx);
00536 Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
00537 position = position + (right * tx);
00538
00539 double ty = -1 * (info->P[7] / fy);
00540 Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
00541 position = position + (down * ty);
00542
00543 if (!validateFloats(position))
00544 {
00545 setStatus(status_levels::Error, "CameraInfo", "CameraInfo/P resulted in an invalid position calculation (nans or infs)");
00546 return;
00547 }
00548
00549 render_panel_->getCamera()->setPosition(position);
00550 render_panel_->getCamera()->setOrientation(orientation);
00551
00552
00553 double cx = info->P[2];
00554 double cy = info->P[6];
00555
00556 double far_plane = 100;
00557 double near_plane = 0.01;
00558
00559 Ogre::Matrix4 proj_matrix;
00560 proj_matrix = Ogre::Matrix4::ZERO;
00561
00562 proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
00563 proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
00564
00565 proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
00566 proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
00567
00568 proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
00569 proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
00570
00571 proj_matrix[3][2]= -1;
00572
00573 render_panel_->getCamera()->setCustomProjectionMatrix( true, proj_matrix );
00574
00575 setStatus(status_levels::Ok, "CameraInfo", "OK");
00576
00577 #if 0
00578 static ogre_tools::Axes* debug_axes = new ogre_tools::Axes(scene_manager_, 0, 0.2, 0.01);
00579 debug_axes->setPosition(position);
00580 debug_axes->setOrientation(orientation);
00581 #endif
00582
00583
00584 bg_screen_rect_->setCorners(-1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y);
00585 fg_screen_rect_->setCorners(-1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y);
00586
00587 Ogre::AxisAlignedBox aabInf;
00588 aabInf.setInfinite();
00589 bg_screen_rect_->setBoundingBox(aabInf);
00590 fg_screen_rect_->setBoundingBox(aabInf);
00591 }
00592
00593 void CameraDisplay::caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg)
00594 {
00595 boost::mutex::scoped_lock lock(caminfo_mutex_);
00596 current_caminfo_ = msg;
00597 new_caminfo_ = true;
00598 }
00599
00600 void CameraDisplay::onTransportEnumOptions(V_string& choices)
00601 {
00602 texture_.getAvailableTransportTypes(choices);
00603 }
00604
00605 void CameraDisplay::onImagePositionEnumOptions(V_string& choices)
00606 {
00607 choices.clear();
00608 choices.push_back(IMAGE_POS_BACKGROUND);
00609 choices.push_back(IMAGE_POS_OVERLAY);
00610 choices.push_back(IMAGE_POS_BOTH);
00611 }
00612
00613 void CameraDisplay::createProperties()
00614 {
00615 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Image Topic", property_prefix_, boost::bind( &CameraDisplay::getTopic, this ),
00616 boost::bind( &CameraDisplay::setTopic, this, _1 ), parent_category_, this );
00617 setPropertyHelpText(topic_property_, "sensor_msgs::Image topic to subscribe to. The topic must be a well-formed <strong>camera</strong> topic, and in order to work properly must have a matching <strong>camera_info<strong> topic.");
00618 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00619 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::Image>());
00620
00621 transport_property_ = property_manager_->createProperty<EditEnumProperty>("Transport Hint", property_prefix_, boost::bind(&CameraDisplay::getTransport, this),
00622 boost::bind(&CameraDisplay::setTransport, this, _1), parent_category_, this);
00623 EditEnumPropertyPtr transport_prop = transport_property_.lock();
00624 transport_prop->setOptionCallback(boost::bind(&CameraDisplay::onTransportEnumOptions, this, _1));
00625
00626 image_position_property_ = property_manager_->createProperty<EditEnumProperty>("Image Rendering", property_prefix_, boost::bind(&CameraDisplay::getImagePosition, this),
00627 boost::bind(&CameraDisplay::setImagePosition, this, _1), parent_category_, this);
00628 setPropertyHelpText(image_position_property_, "Render the image behind all other geometry or overlay it on top.");
00629 EditEnumPropertyPtr ip_prop = image_position_property_.lock();
00630 ip_prop->setOptionCallback(boost::bind(&CameraDisplay::onImagePositionEnumOptions, this, _1));
00631
00632 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Overlay Alpha", property_prefix_, boost::bind( &CameraDisplay::getAlpha, this ),
00633 boost::bind( &CameraDisplay::setAlpha, this, _1 ), parent_category_, this );
00634 setPropertyHelpText(alpha_property_, "The amount of transparency to apply to the camera image when rendered as overlay.");
00635
00636 zoom_property_ = property_manager_->createProperty<FloatProperty>("Zoom Factor", property_prefix_, boost::bind(&CameraDisplay::getZoom, this),
00637 boost::bind( &CameraDisplay::setZoom, this, _1), parent_category_, this);
00638 setPropertyHelpText(image_position_property_, "Set a zoom factor below 1 to see a larger part of the world, a factor above 1 to magnify the image.");
00639 }
00640
00641 void CameraDisplay::fixedFrameChanged()
00642 {
00643 caminfo_tf_filter_->setTargetFrame(fixed_frame_);
00644 texture_.setFrame(fixed_frame_, vis_manager_->getTFClient());
00645 }
00646
00647 void CameraDisplay::targetFrameChanged()
00648 {
00649
00650 }
00651
00652 void CameraDisplay::reset()
00653 {
00654 Display::reset();
00655
00656 clear();
00657 }
00658
00659 }