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