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