color_gui.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *********************************************************************/
29 
32 #include <ros/ros.h>
33 #include <opencv2/opencv.hpp>
34 #include <sensor_msgs/Image.h>
35 #include <wx/wx.h>
36 
37 #include "cmvision.h"
38 
39 class ColorGuiFrame : public wxFrame
40 {
41  enum {ID_Reset=1};
42 
44  public: ColorGuiFrame();
45 
47  public: void OnQuit(wxCommandEvent &event);
48 
50  public: void OnReset(wxCommandEvent &event);
51 
53  public: void OnClick(wxMouseEvent &event);
54 
56  public: void OnMouseWheel(wxMouseEvent &event);
57 
59  public: void DrawImage(const sensor_msgs::ImageConstPtr& msg);
60 
61  private: int width_, height_;
62  private: wxTextCtrl *abText_;
63  private: wxTextCtrl *rgbText_;
64  private: wxPanel *image_panel_;
65 
66  private: unsigned char *rgb_image_;
67  private: unsigned char *lab_image_;
68 
69  private: int scale_pos_x_, scale_pos_y_;
70  private: float scale_;
71 
72  private: CMVision *vision_;
73 };
74 
75 
76 class ColorGuiApp : public wxApp
77 {
79  public: bool OnInit();
80 
82  public: void OnUpdate( wxTimerEvent &event );
83 
85  private: void imageCB(const sensor_msgs::ImageConstPtr& msg);
86 
88  private: wxTimer *update_timer_;
89  private: ColorGuiFrame *frame_;
90 };
91 
92 DECLARE_APP(ColorGuiApp)
93 IMPLEMENT_APP(ColorGuiApp)
ColorGuiFrame::DrawImage
void DrawImage(const sensor_msgs::ImageConstPtr &msg)
Draw an image frame.
Definition: color_gui.cpp:140
ColorGuiFrame::height_
int height_
Definition: color_gui.h:88
ColorGuiFrame::OnQuit
void OnQuit(wxCommandEvent &event)
Quit callback.
Definition: color_gui.cpp:135
ColorGuiFrame::abText_
wxTextCtrl * abText_
Definition: color_gui.h:89
ColorGuiFrame::OnMouseWheel
void OnMouseWheel(wxMouseEvent &event)
Callback for zooming.
Definition: color_gui.cpp:290
ColorGuiFrame::vision_
CMVision * vision_
Definition: color_gui.h:99
ColorGuiFrame::OnClick
void OnClick(wxMouseEvent &event)
On image click callback.
Definition: color_gui.cpp:241
ros.h
ColorGuiFrame::rgb_image_
unsigned char * rgb_image_
Definition: color_gui.h:93
ColorGuiFrame::scale_
float scale_
Definition: color_gui.h:97
ColorGuiFrame::width_
int width_
Definition: color_gui.h:88
ColorGuiApp::OnUpdate
void OnUpdate(wxTimerEvent &event)
On update, used for ros::spin.
Definition: color_gui.cpp:62
ColorGuiApp::imageCB
void imageCB(const sensor_msgs::ImageConstPtr &msg)
The image callback.
Definition: color_gui.cpp:67
ColorGuiFrame::ID_Reset
@ ID_Reset
Definition: color_gui.h:95
ColorGuiFrame::rgbText_
wxTextCtrl * rgbText_
Definition: color_gui.h:90
cmvision.h
ColorGuiFrame::scale_pos_x_
int scale_pos_x_
Definition: color_gui.h:96
ColorGuiFrame::scale_pos_y_
int scale_pos_y_
Definition: color_gui.h:96
ColorGuiApp
Definition: color_gui.h:76
ColorGuiFrame::lab_image_
unsigned char * lab_image_
Definition: color_gui.h:94
ColorGuiApp::update_timer_
wxTimer * update_timer_
Definition: color_gui.h:88
ColorGuiFrame::OnReset
void OnReset(wxCommandEvent &event)
Reset callback.
Definition: color_gui.cpp:234
ColorGuiApp::frame_
ColorGuiFrame * frame_
Definition: color_gui.h:89
ColorGuiFrame::image_panel_
wxPanel * image_panel_
Definition: color_gui.h:91
ColorGuiFrame::ColorGuiFrame
ColorGuiFrame()
Constructor.
Definition: color_gui.cpp:72
ColorGuiFrame
Definition: color_gui.h:39
CMVision
Definition: cmvision.h:108
ColorGuiApp::OnInit
bool OnInit()
On init of the application.
Definition: color_gui.cpp:38
ColorGuiApp::image_subscriber_
ros::Subscriber image_subscriber_
Definition: color_gui.h:87
ros::Subscriber


cmvision
Author(s): Nate Koenig, Nate Koenig
autogenerated on Wed Mar 2 2022 00:03:25