/**
 Constructor
   */
  RvizLogo::RvizLogo(const std::string& name, VisualizationManager* manager/*wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi */)
  : Display( "logo", manager ),
    frame_(0)
  //: wxPanel( parent, wxID_ANY, wxDefaultPosition, wxSize(280, 180), wxTAB_TRAVERSAL, title)
  //, m_wmi( wmi )
  {
    string path = ros::package::getPath("cob_3d_mapping_demonstrator") + "/ros/files/logo_title.jpg";
    // Create controls
    //m_button = new wxButton(this, ID_RESET_BUTTON, wxT("Reset map"));
    wxWindow* parent = 0;

    WindowManagerInterface* wm = vis_manager_->getWindowManager();
    if (wm)
    {
      parent = wm->getParentWindow();
    }
    else
    {
      frame_ = new wxFrame(0, wxID_ANY, wxString::FromAscii(""), wxDefaultPosition, wxDefaultSize, wxMINIMIZE_BOX | wxMAXIMIZE_BOX | wxRESIZE_BORDER | wxCAPTION | wxCLIP_CHILDREN);
      parent = frame_;
    }

    panel_ = new wxImagePanel(parent, wxString::FromAscii(path.c_str()),wxBITMAP_TYPE_JPEG);
    //if (!pic_.LoadFile(wxT("/home/goa/git/cob_environment_perception_intern/cob_3d_mapping_demonstrator/lib/logo.jpg"),wxBITMAP_TYPE_JPEG)) ROS_ERROR("Image file not found!");
    //logo_ = new wxStaticBitmap(panel_, wxID_ANY, pic_);
    //wxSizer *vsizer = new wxBoxSizer(wxVERTICAL);
    //vsizer->Add(logo_, 1, wxALIGN_CENTER);

    //vsizer->SetSizeHints(panel_);
    //panel_->SetSizerAndFit(vsizer);

    if (wm)
    {
      wm->addPane(name, panel_);
    }
  }
CameraDisplaySave::CameraDisplaySave( const std::string& name, VisualizationManager* manager )
: Display( name, manager )
, transport_("raw")
, caminfo_tf_filter_(*manager->getTFClient(), "", 2, update_nh_)
, new_caminfo_(false)
, texture_(update_nh_)
, frame_(0)
, force_render_(false)
, render_listener_(this)
{
  scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();

  {
    static int count = 0;
    std::stringstream ss;
    ss << "CameraDisplaySaveObject" << count++;

    screen_rect_ = new Ogre::Rectangle2D(true);
    screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
    screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);

    ss << "Material";
    material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
    material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
    material_->setDepthWriteEnabled(false);

    material_->setReceiveShadows(false);
    material_->setDepthCheckEnabled(false);


#if 1
    material_->getTechnique(0)->setLightingEnabled(false);
    Ogre::TextureUnitState* tu = material_->getTechnique(0)->getPass(0)->createTextureUnitState();
    tu->setTextureName(texture_.getTexture()->getName());
    tu->setTextureFiltering( Ogre::TFO_NONE );
    tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
#else
    material_->getTechnique(0)->setLightingEnabled(true);
    material_->setAmbient(Ogre::ColourValue(0.0f, 1.0f, 1.0f, 1.0f));
#endif

    material_->setCullingMode(Ogre::CULL_NONE);
    Ogre::AxisAlignedBox aabInf;
    aabInf.setInfinite();
    screen_rect_->setBoundingBox(aabInf);
    screen_rect_->setMaterial(material_->getName());
    scene_node_->attachObject(screen_rect_);

  }

  setAlpha( 0.5f );

  wxWindow* parent = 0;

  WindowManagerInterface* wm = vis_manager_->getWindowManager();
  if (wm)
  {
    parent = wm->getParentWindow();
  }
  else
  {
    frame_ = new wxFrame(0, wxID_ANY, wxString::FromAscii(name.c_str()), wxPoint(100,100), wxDefaultSize, wxMINIMIZE_BOX | wxMAXIMIZE_BOX | wxRESIZE_BORDER | wxCAPTION | wxCLIP_CHILDREN);
    parent = frame_;
  }

  render_panel_ = new RenderPanel(parent, false);
  render_panel_->SetSize(wxSize(640, 480));
  if (wm)
  {
    wm->addPane(name, render_panel_);
  }

  render_panel_->createRenderWindow();
  render_panel_->initialize(vis_manager_->getSceneManager(), vis_manager_);

  render_panel_->setAutoRender(false);
  render_panel_->getRenderWindow()->addListener(&render_listener_);
  render_panel_->getViewport()->setOverlaysEnabled(false);
  render_panel_->getViewport()->setClearEveryFrame(true);
  render_panel_->getRenderWindow()->setActive(false);
  render_panel_->getRenderWindow()->setAutoUpdated(false);
  render_panel_->getCamera()->setNearClipDistance( 0.1f );

  caminfo_tf_filter_.connectInput(caminfo_sub_);
  caminfo_tf_filter_.registerCallback(boost::bind(&CameraDisplaySave::caminfoCallback, this, _1));
  vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
}