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