view.hpp
Go to the documentation of this file.
00001 
00063 #ifndef COB_3D_MAPPING_TOOLS_GUIE_VIEW_HPP_
00064 #define COB_3D_MAPPING_TOOLS_GUIE_VIEW_HPP_
00065 
00066 #include "cob_3d_mapping_tools/gui/view.h"
00067 
00068   /* -----------------....-------*/
00069  /* --------- ViewBase ---------*/
00070 /* ----------------------------*/
00071 Gui::ViewBase::~ViewBase()
00072 { r_base_ptr->releaseView(name_); std::cout << "Base View destroyed" << std::endl; }
00073 
00074 
00075   /* ------------------------*/
00076  /* --------- View ---------*/
00077 /* ------------------------*/
00078 template<typename RT, typename VT>
00079 boost::signals::connection Gui::View<RT,VT>::registerMouseCallback(boost::function<void (wxMouseEvent&, Resource<RT>*)> f)
00080 { return mouse_sig_.connect(f); }
00081 
00082 template<typename RT, typename VT>
00083 boost::signals::connection Gui::View<RT,VT>::registerKeyCallback(boost::function<void (wxKeyEvent&, Resource<RT>*)> f)
00084 { return key_sig_.connect(f); }
00085 
00086 template<typename RT, typename VT>
00087 void Gui::View<RT,VT>::show(Gui::ViewTypes::View2D)
00088 { Core::wMan()->create(static_cast<Gui::ImageView<RT,VT>*>(this),std::string(RT::STR + VT::STR)); }
00089 
00090 template<typename RT, typename VT>
00091 void Gui::View<RT,VT>::refresh(Gui::ViewTypes::View2D)
00092 { static_cast<Gui::ImageView<RT,VT>*>(this)->render(); }
00093 
00094 
00095  /* --------- Res: Image -|- View: Color ---------*/
00096 /* ----------------------------------------------*/
00097 template<typename RT, typename VT>
00098 void Gui::View<RT,VT>::reloadData(ResourceTypes::Image, ViewTypes::Color)
00099 {
00100   typedef Gui::ImageView<Gui::ResourceTypes::Image, Gui::ViewTypes::Color> IV;
00101 
00102   int w = this->r_ptr->getData()->cols;
00103   int h = this->r_ptr->getData()->rows;
00104   static_cast<IV*>(this)->bmp_.reset(new wxBitmap(w,h));
00105   wxNativePixelData data(*(static_cast<IV*>(this)->bmp_));
00106   wxNativePixelData::Iterator pwx(data);
00107   for(int row = 0; row < h; ++row)
00108   {
00109     for(int col = 0; col < w; ++col, ++pwx)
00110     {
00111       cv::Vec3b& pcv = (*this->r_ptr->getData())(row,col);
00112       pwx.Blue() = pcv[0];
00113       pwx.Green() = pcv[1];
00114       pwx.Red() = pcv[2];
00115     }
00116   }
00117 }
00118 
00119 
00120  /* --------- Res: Organized PC -|- View: Color ---------*/
00121 /* -----------------------------------------------------*/
00122 template<typename RT, typename VT>
00123 template<typename PT>
00124 void Gui::View<RT,VT>::reloadData(ResourceTypes::OrganizedPointCloud<PT>, ViewTypes::Color)
00125 {
00126   typedef Gui::ImageView<Gui::ResourceTypes::OrganizedPointCloud<PT>, Gui::ViewTypes::Color> IV;
00127 
00128   int w = this->r_ptr->getData()->width;
00129   int h = this->r_ptr->getData()->height;
00130   static_cast<IV*>(this)->bmp_.reset(new wxBitmap(w,h));
00131   wxNativePixelData data(*(static_cast<IV*>(this)->bmp_));
00132   wxNativePixelData::Iterator pwx(data);
00133   for(int row = 0; row < h; ++row)
00134   {
00135     for(int col = 0; col < w; ++col, ++pwx)
00136     {
00137       PT* ppc = &(*this->r_ptr->getData())[col + row * w];
00138       pwx.Red() = ppc->r;
00139       pwx.Green() = ppc->g;
00140       pwx.Blue() = ppc->b;
00141     }
00142   }
00143 }
00144 
00145 
00146 /* --------- Res: Organized PC -|- View: Depth ---------*/
00147 /* -----------------------------------------------------*/
00148 template<typename RT, typename VT>
00149 template<typename PT>
00150 void Gui::View<RT,VT>::reloadData(ResourceTypes::OrganizedPointCloud<PT>, ViewTypes::Depth_Z)
00151 {
00152   typedef Gui::ImageView<Gui::ResourceTypes::OrganizedPointCloud<PT>, Gui::ViewTypes::Depth_Z> IV;
00153   int w = this->r_ptr->getData()->width;
00154   int h = this->r_ptr->getData()->height;
00155   float z_min, z_max;
00156   Tools::getMinMaxZ<PT>(this->r_ptr->getData(), z_min, z_max);
00157 
00158   static_cast<IV*>(this)->bmp_.reset(new wxBitmap(w,h));
00159   wxNativePixelData data(*(static_cast<IV*>(this)->bmp_));
00160   wxNativePixelData::Iterator pwx(data);
00161   cv::Vec3b bgr;
00162   for(int row = 0; row < h; ++row)
00163   {
00164     for(int col = 0; col < w; ++col, ++pwx)
00165     {
00166       float z = (*this->r_ptr->getData())[col + row * w].z;
00167       if(z != z)
00168       {
00169         pwx.Red() = 0;
00170         pwx.Green() = 0;
00171         pwx.Blue() = 0;
00172       }
00173       else
00174       {
00175         Tools::getGradientColor(z, z_min, z_max, bgr);
00176         pwx.Red() = bgr[2];
00177         pwx.Green() = bgr[1];
00178         pwx.Blue() = bgr[0];
00179       }
00180     }
00181   }
00182 }
00183 
00184 
00185 /* --------- Res: Organized PC -|- View: Normal ---------*/
00186 /* -----------------------------------------------------*/
00187 template<typename RT, typename VT>
00188 template<typename PT, size_t Channel>
00189 void Gui::View<RT,VT>::reloadData(ResourceTypes::OrganizedPointCloud<PT>, ViewTypes::Normal<Channel>)
00190 {
00191   typedef Gui::ImageView<Gui::ResourceTypes::OrganizedPointCloud<PT>, Gui::ViewTypes::Normal<Channel> > IV;
00192 
00193   int w = this->r_ptr->getData()->width;
00194   int h = this->r_ptr->getData()->height;
00195   static_cast<IV*>(this)->bmp_.reset(new wxBitmap(w,h));
00196   wxNativePixelData data(*(static_cast<IV*>(this)->bmp_));
00197   wxNativePixelData::Iterator pwx(data);
00198   cv::Vec3b bgr;
00199   for(int row = 0; row < h; ++row)
00200   {
00201     for(int col = 0; col < w; ++col, ++pwx)
00202     {
00203       PT* ppc = &(*this->r_ptr->getData())[col + row * w];
00204       if(ppc->normal[Channel] != ppc->normal[Channel])
00205       {
00206         pwx.Red() = 0;
00207         pwx.Green() = 255.0f;
00208         pwx.Blue() = 0;
00209       }
00210       else
00211       {
00212         int n_n = (ppc->normal[Channel] + 1.0f) * 127.5f;
00213         pwx.Red() = n_n;
00214         pwx.Green() = n_n;
00215         pwx.Blue() = n_n;
00216       }
00217     }
00218   }
00219 }
00220 
00221 
00222   /* -----------------------------*/
00223  /* --------- ImageView ---------*/
00224 /* -----------------------------*/
00225 template<typename RT, typename VT>
00226 void Gui::ImageView<RT,VT>::render()
00227 {
00228   wxPaintDC dc(this);
00229   render(dc);
00230 }
00231 
00232 template<typename RT, typename VT>
00233 void Gui::ImageView<RT,VT>::render(wxDC& dc)
00234 {
00235   dc.DrawBitmap(*bmp_, 0, 0, false);
00236 }
00237 
00238 
00239 template<typename RT, typename VT>
00240 void Gui::ImageView<RT,VT>::paintEvent(wxPaintEvent& event)
00241 {
00242   wxPaintDC dc(this);
00243   render(dc);
00244 }
00245 
00246 template<typename RT, typename VT>
00247 void Gui::ImageView<RT,VT>::mouseEvent(wxMouseEvent& event)
00248 {
00249   if(event.LeftDClick())
00250   {
00251     wxPoint p1 = event.GetPosition();
00252     //std::cout << "mouse click thing on " << this->name_ << " at " << p1.x << "," << p1.y << std::endl;
00253     this->mouse_sig_(event, this->r_ptr);
00254   }
00255   else if(event.RightDClick())
00256   {
00257     this->mouse_sig_(event, this->r_ptr);
00258   }
00259 }
00260 
00261 template<typename RT, typename VT>
00262 void Gui::ImageView<RT,VT>::keyEvent(wxKeyEvent& event)
00263 {
00264   this->key_sig_(event, this->r_ptr);
00265 }
00266 
00267 // Needed to fix these wxWidget macros (v2.8) to be able to use class templates in event table!
00268 BEGIN_EVENT_TABLE_TEMPLATE2(Gui::ImageView, wxPanel, RT, VT)
00269 wx__DECLARE_EVT0(
00270   wxEVT_PAINT,
00271   (wxObjectEventFunction)(wxEventFunction) static_cast<wxPaintEventFunction>(&Gui::ImageView<RT,VT>::paintEvent))
00272 wx__DECLARE_EVT0(
00273   wxEVT_LEFT_UP,
00274   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00275 wx__DECLARE_EVT0(
00276   wxEVT_MIDDLE_DOWN,
00277   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00278 wx__DECLARE_EVT0(
00279   wxEVT_MIDDLE_UP,
00280   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00281 wx__DECLARE_EVT0(
00282   wxEVT_RIGHT_DOWN,
00283   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00284 wx__DECLARE_EVT0(
00285   wxEVT_RIGHT_UP,
00286   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00287 wx__DECLARE_EVT0(
00288   wxEVT_MOTION,
00289   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00290 wx__DECLARE_EVT0(
00291   wxEVT_LEFT_DCLICK,
00292   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00293 wx__DECLARE_EVT0(
00294   wxEVT_MIDDLE_DCLICK,
00295   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00296 wx__DECLARE_EVT0(
00297   wxEVT_RIGHT_DCLICK,
00298   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00299 wx__DECLARE_EVT0(
00300   wxEVT_LEAVE_WINDOW,
00301   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00302 wx__DECLARE_EVT0(
00303   wxEVT_ENTER_WINDOW,
00304   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00305 wx__DECLARE_EVT0(
00306   wxEVT_MOUSEWHEEL,
00307   (wxObjectEventFunction)(wxEventFunction) static_cast<wxMouseEventFunction>(&Gui::ImageView<RT,VT>::mouseEvent))
00308 
00309 wx__DECLARE_EVT0(
00310   wxEVT_KEY_DOWN,
00311   (wxObjectEventFunction)(wxEventFunction) static_cast<wxCharEventFunction>(&Gui::ImageView<RT,VT>::keyEvent))
00312 wx__DECLARE_EVT0(
00313   wxEVT_KEY_UP,
00314   (wxObjectEventFunction)(wxEventFunction) static_cast<wxCharEventFunction>(&Gui::ImageView<RT,VT>::keyEvent))
00315 wx__DECLARE_EVT0(
00316   wxEVT_CHAR,
00317   (wxObjectEventFunction)(wxEventFunction) static_cast<wxCharEventFunction>(&Gui::ImageView<RT,VT>::keyEvent))
00318 
00319 END_EVENT_TABLE()
00320 
00321 #endif


cob_3d_mapping_tools
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:27