|
From: <mar...@us...> - 2009-04-02 19:01:12
|
Revision: 13322
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=13322&view=rev
Author: mariusmuja
Date: 2009-04-02 19:01:08 +0000 (Thu, 02 Apr 2009)
Log Message:
-----------
Moved stereodcam_params script into dcam package.
Modified Paths:
--------------
pkg/trunk/drivers/cam/dcam/manifest.xml
Added Paths:
-----------
pkg/trunk/drivers/cam/dcam/scripts/
pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params
pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.py
pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.wxg
Removed Paths:
-------------
pkg/trunk/vision/stereodcam_params/manifest.xml
pkg/trunk/vision/stereodcam_params/stereodcam_params
pkg/trunk/vision/stereodcam_params/stereodcam_params.py
pkg/trunk/vision/stereodcam_params/stereodcam_params.wxg
pkg/trunk/vision/stereodcam_params/stereodcam_params_test.py
Modified: pkg/trunk/drivers/cam/dcam/manifest.xml
===================================================================
--- pkg/trunk/drivers/cam/dcam/manifest.xml 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/drivers/cam/dcam/manifest.xml 2009-04-02 19:01:08 UTC (rev 13322)
@@ -15,6 +15,7 @@
<depend package="std_srvs"/>
<depend package="image_msgs"/>
<depend package="diagnostic_updater"/>
+ <depend package="rospy"/>
<sysdepend os="ubuntu" version="7.04-feisty" package="libfltk1.1-dev"/>
<sysdepend os="ubuntu" version="8.04-hardy" package="libfltk1.1-dev"/>
Copied: pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params (from rev 13320, pkg/trunk/vision/stereodcam_params/stereodcam_params)
===================================================================
--- pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params (rev 0)
+++ pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params 2009-04-02 19:01:08 UTC (rev 13322)
@@ -0,0 +1 @@
+link stereodcam_params.py
\ No newline at end of file
Property changes on: pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params
___________________________________________________________________
Added: svn:special
+ *
Copied: pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.py (from rev 13320, pkg/trunk/vision/stereodcam_params/stereodcam_params.py)
===================================================================
--- pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.py (rev 0)
+++ pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.py 2009-04-02 19:01:08 UTC (rev 13322)
@@ -0,0 +1,334 @@
+#!/usr/bin/env python
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2009, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of the Willow Garage nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+# Author: Marius Muja
+
+import wx
+import wx.lib.intctrl
+import sys
+import os
+
+PKG = 'stereodcam_params' # this package name
+import roslib; roslib.load_manifest(PKG)
+from roslib.scriptutil import get_param_server, script_resolve_name
+from roslib.names import ns_join, get_ros_namespace, make_caller_id, make_global_ns, GLOBALNS
+
+import rospy
+from std_msgs.msg import Empty
+
+def _get_caller_id():
+ return make_caller_id('%s-%s'%(PKG,os.getpid()))
+
+
+def succeed(args):
+ code, msg, val = args
+ if code != 1:
+ raise RosParamException(msg)
+ return val
+
+def _get_param(param):
+ return succeed(get_param_server().getParam(_get_caller_id(), param))
+
+def _set_param(param, value):
+ succeed(get_param_server().setParam(_get_caller_id(), param, value))
+
+
+
+class IntParameterWidget(wx.Panel):
+
+ def __init__(self, parent, name, param, update_callback = None):
+
+ self.param = param
+ self.update_callback = update_callback
+
+ wx.Panel.__init__(self, parent ,-1)
+ self.label = wx.StaticText(self, -1, name)
+ self.edit = wx.lib.intctrl.IntCtrl(self, -1)
+
+ # properties
+ self.label.SetMinSize((150,-1))
+
+ # layout
+ sizer = wx.BoxSizer(wx.HORIZONTAL)
+ sizer.Add(self.label,0,0,0)
+ sizer.Add(self.edit,0,0,0)
+ self.SetSizer(sizer)
+
+ # bindings
+ self.Bind(wx.EVT_TEXT, self.onEdit, self.edit)
+
+ self._initValue()
+
+
+ def _initValue(self):
+ try:
+ value = _get_param(self.param)
+ self.edit.SetValue(value)
+ except:
+ print "Cannot read value for parameter: "+self.param
+
+
+ def _setParam(self, param, value):
+ try:
+ _set_param(param, value)
+ if self.update_callback != None:
+ self.update_callback()
+ except:
+ print "Cannot set parameter: "+self.param
+
+ def onEdit(self, event):
+ str_value = event.GetString()
+ #print str_value
+ value = int(str_value)
+ #print value
+ self._setParam(self.param, value)
+
+
+class BoolParameterWidget(wx.Panel):
+
+ def __init__(self, parent, name, param, update_callback = None):
+
+ self.param = param
+ self.update_callback = update_callback
+
+ wx.Panel.__init__(self, parent ,-1)
+ self.label = wx.StaticText(self, -1, name)
+ self.checkbox = wx.CheckBox(self, -1, "active")
+
+ # properties
+ self.label.SetMinSize((150,-1))
+
+ # layout
+ sizer = wx.BoxSizer(wx.HORIZONTAL)
+ sizer.Add(self.label,0,0,0)
+ sizer.Add(self.checkbox,0,0,0)
+ self.SetSizer(sizer)
+
+ # bindings
+ self.Bind(wx.EVT_CHECKBOX, self.onCheckbox, self.checkbox)
+
+ self._initValue()
+
+
+ def _initValue(self):
+ try:
+ value = _get_param(self.param)
+ self.checkbox.SetValue(value)
+ except:
+ print "Cannot read value for parameter: "+self.param
+
+
+ def _setParam(self, param, value):
+ try:
+ _set_param(param, value)
+ if self.update_callback != None:
+ self.update_callback()
+ except:
+ print "Cannot set parameter: "+self.param
+
+ def onCheckbox(self, event):
+ value = event.IsChecked();
+ self._setParam(self.param, value)
+
+
+class RangeParameterWidget(wx.Panel):
+
+ def __init__(self, parent, name, param, update_callback = None, has_auto = False):
+
+ self.param = param
+ self.update_callback = update_callback
+ self.has_auto = has_auto
+
+ wx.Panel.__init__(self, parent ,-1)
+ self.label = wx.StaticText(self, -1, name)
+ self.slider = wx.Slider(self, -1, 0, 0, 100)
+ self.spin = wx.SpinCtrl(self, -1, "", min=0, max=100)
+ if self.has_auto:
+ self.checkbox = wx.CheckBox(self, -1, "auto")
+
+ # properties
+ self.label.SetMinSize((150,-1))
+
+ # layout
+ sizer = wx.BoxSizer(wx.HORIZONTAL)
+ sizer.Add(self.label,0,0,0)
+ sizer.Add(self.slider,1,0,0)
+ sizer.Add(self.spin,0,0,0)
+ if self.has_auto:
+ sizer.Add(self.checkbox,0,0,0)
+ self.SetSizer(sizer)
+
+ # bindings
+ self.Bind(wx.EVT_COMMAND_SCROLL, self.onSlider, self.slider)
+ self.Bind(wx.EVT_SPINCTRL, self.onSpin, self.spin)
+ if self.has_auto:
+ self.Bind(wx.EVT_CHECKBOX, self.onCheckbox, self.checkbox)
+
+ self._initRange()
+ self._initValue()
+
+ def _initRange(self):
+ try:
+ min_value = _get_param(self.param+"_min")
+ max_value = _get_param(self.param+"_max")
+ self.slider.SetRange(min_value, max_value)
+ self.spin.SetRange(min_value, max_value)
+ except:
+ print "Cannot read range for parameter: "+self.param
+
+ def _initValue(self):
+ try:
+ value = _get_param(self.param)
+ self.slider.SetValue(value)
+ self.spin.SetValue(value)
+ except:
+ print "Cannot read value for parameter: "+self.param
+ if self.has_auto:
+ try:
+ value = _get_param(self.param+"_auto")
+ self.checkbox.SetValue(value)
+ if value:
+ self.slider.Disable()
+ self.spin.Disable()
+ else:
+ self.slider.Enable()
+ self.spin.Enable()
+ except:
+ print "Cannot tell if auto is set for parameter: "+self.param
+
+ def _setParam(self, param, value):
+ try:
+ _set_param(param, value)
+ if self.update_callback != None:
+ self.update_callback()
+ except:
+ print "Cannot set parameter: "+param
+
+ def onSlider(self, event):
+ value = event.GetPosition()
+ self.spin.SetValue(value)
+ self._setParam(self.param, value)
+
+ def onSpin(self, event):
+ value = event.GetInt()
+ self.slider.SetValue(value)
+ self._setParam(self.param, value)
+
+ def onCheckbox(self, event):
+ value = event.IsChecked();
+ self._setParam(self.param+"_auto", value)
+ if value:
+ self.slider.Disable()
+ self.spin.Disable()
+ else:
+ self.slider.Enable()
+ self.spin.Enable()
+
+
+class StereoParameters(wx.Frame):
+ def __init__(self, *args, **kwds):
+
+ kwds["style"] = wx.DEFAULT_FRAME_STYLE
+ wx.Frame.__init__(self, *args, **kwds)
+
+ self.widgets = []
+ self.widgets.append(RangeParameterWidget(self, "Exposure", "stereo/exposure", has_auto = True, update_callback = self.update_stereo_params))
+ self.widgets.append(RangeParameterWidget(self, "Gain", "stereo/gain", has_auto = True, update_callback = self.update_stereo_params))
+ self.widgets.append(RangeParameterWidget(self, "Brightness", "stereo/brightness", has_auto = True, update_callback = self.update_stereo_params))
+ self.widgets.append(BoolParameterWidget(self, "Companding", "stereo/companding", update_callback = self.update_stereo_params))
+ self.widgets.append(BoolParameterWidget(self, "HDR", "stereo/hdr", update_callback = self.update_stereo_params))
+ self.widgets.append(BoolParameterWidget(self, "Unique Check", "stereo/unique_check", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Texture Threshold", "stereo/texture_thresh", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Unique Threshold", "stereo/unique_thresh", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Smoothness Threshold", "stereo/smoothness_thresh", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Horopter", "stereo/horopter", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Speckle Size", "stereo/speckle_size", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Speckle Diff", "stereo/speckle_diff", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Corr Size", "stereo/corr_size", update_callback = self.update_stereo_params))
+ self.widgets.append(IntParameterWidget(self, "Num Disp", "stereo/num_disp", update_callback = self.update_stereo_params))
+
+ self.close_button = wx.Button(self, -1, "Close")
+
+ self.__set_properties()
+ self.__do_layout()
+
+ self.Bind(wx.EVT_BUTTON, self.onClose, self.close_button)
+
+ self.check_params = rospy.Publisher('stereo/check_params', Empty)
+ rospy.init_node('stereodcam_params', anonymous=True)
+
+
+ def update_stereo_params(self):
+ self.check_params.publish(Empty())
+
+
+ def __set_properties(self):
+ self.SetTitle("Stereo Parameters")
+ self.SetSize((498, 500))
+
+ def __do_layout(self):
+ vsizer = wx.BoxSizer(wx.VERTICAL)
+ vsizer.Add((10, 10), 0, 0, 0)
+
+ for widget in self.widgets:
+ vsizer.Add(widget, 1, wx.EXPAND, 0)
+
+ vsizer.Add(self.close_button, 0, wx.ALIGN_CENTER_HORIZONTAL|wx.ALIGN_CENTER_VERTICAL, 0)
+ vsizer.Add((10, 10), 0, 0, 0)
+ hsizer = wx.BoxSizer(wx.HORIZONTAL)
+ hsizer.Add((10, 10), 0, 0, 0)
+ hsizer.Add(vsizer, 1, wx.EXPAND, 0)
+ hsizer.Add((10, 10), 0, 0, 0)
+ self.SetSizer(hsizer)
+
+ self.Layout()
+
+
+ def onClose(self, event):
+ sys.exit(0)
+
+
+
+class MyApp(wx.App):
+ def OnInit(self):
+ wx.InitAllImageHandlers()
+ frame_2 = StereoParameters(None, -1, "")
+ self.SetTopWindow(frame_2)
+ frame_2.Show()
+ return 1
+
+# end of class MyApp
+
+if __name__ == "__main__":
+ app = MyApp(0)
+ app.MainLoop()
Copied: pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.wxg (from rev 13320, pkg/trunk/vision/stereodcam_params/stereodcam_params.wxg)
===================================================================
--- pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.wxg (rev 0)
+++ pkg/trunk/drivers/cam/dcam/scripts/stereodcam_params.wxg 2009-04-02 19:01:08 UTC (rev 13322)
@@ -0,0 +1,97 @@
+<?xml version="1.0"?>
+<!-- generated by wxGlade 0.6.3 on Fri Mar 20 15:34:19 2009 -->
+
+<application path="/u/mariusm/ros/ros-pkg/vision/stereodcam_params/stereodcam_params_test.py" name="" class="MyApp" option="0" language="python" top_window="frame_1" encoding="UTF-8" use_gettext="0" overwrite="0" use_new_namespace="1" for_version="2.8" is_template="0">
+ <object class="MyFrame" name="frame_1" base="EditFrame">
+ <style>wxDEFAULT_FRAME_STYLE</style>
+ <title>frame_1</title>
+ <object class="wxBoxSizer" name="sizer_2" base="EditBoxSizer">
+ <orient>wxVERTICAL</orient>
+ <object class="sizeritem">
+ <flag>wxEXPAND</flag>
+ <border>10</border>
+ <option>1</option>
+ <object class="wxPanel" name="panel_1" base="EditPanel">
+ <style>wxTAB_TRAVERSAL</style>
+ <object class="wxBoxSizer" name="sizer_2_copy_copy_copy" base="EditBoxSizer">
+ <orient>wxHORIZONTAL</orient>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>0</option>
+ <object class="wxStaticText" name="exposure_label_copy" base="EditStaticText">
+ <attribute>1</attribute>
+ <label>Exposure</label>
+ <size>100, -1</size>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>0</option>
+ <object class="wxCheckBox" name="checkbox_1" base="EditCheckBox">
+ <label>auto</label>
+ <events>
+ <handler event="EVT_CHECKBOX">onCheckbox</handler>
+ </events>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>1</option>
+ <object class="wxSlider" name="exposure_slider_copy" base="EditSlider">
+ <style>wxSL_HORIZONTAL</style>
+ <events>
+ <handler event="EVT_COMMAND_SCROLL">onExposureSlider</handler>
+ </events>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>0</option>
+ <object class="wxSpinCtrl" name="exposure_spin_copy" base="EditSpinCtrl">
+ <events>
+ <handler event="EVT_SPINCTRL">onExposureSpin</handler>
+ </events>
+ </object>
+ </object>
+ </object>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <flag>wxEXPAND</flag>
+ <border>0</border>
+ <option>1</option>
+ <object class="wxPanel" name="panel_2" base="EditPanel">
+ <style>wxTAB_TRAVERSAL</style>
+ <object class="wxStaticBoxSizer" name="sizer_3" base="EditStaticBoxSizer">
+ <orient>wxHORIZONTAL</orient>
+ <label>Test</label>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>0</option>
+ <object class="wxStaticText" name="exposure_label_copy_copy" base="EditStaticText">
+ <attribute>1</attribute>
+ <label>Exposure</label>
+ <size>100, -1</size>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>1</option>
+ <object class="spacer" name="spacer" base="EditSpacer">
+ <height>20</height>
+ <width>20</width>
+ </object>
+ </object>
+ <object class="sizeritem">
+ <border>0</border>
+ <option>0</option>
+ <object class="wxTextCtrl" name="text_ctrl_1" base="EditTextCtrl">
+ <size>100, -1</size>
+ </object>
+ </object>
+ </object>
+ </object>
+ </object>
+ </object>
+ </object>
+</application>
Deleted: pkg/trunk/vision/stereodcam_params/manifest.xml
===================================================================
--- pkg/trunk/vision/stereodcam_params/manifest.xml 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/vision/stereodcam_params/manifest.xml 2009-04-02 19:01:08 UTC (rev 13322)
@@ -1,14 +0,0 @@
-<package>
- <description brief="Sets stereo camera parameters">
- This is a small GUI for setting the stereo camera parameters.
- </description>
- <author>Marius Muja</author>
- <license>BSD</license>
- <review status="unreviewed" notes=""/>
- <url>http://pr.willowgarage.com</url>
- <depend package="rospy"/>
- <depend package="rostest"/>
- <depend package="std_srvs"/>
- <depend package="std_msgs"/>
-</package>
-
Deleted: pkg/trunk/vision/stereodcam_params/stereodcam_params
===================================================================
--- pkg/trunk/vision/stereodcam_params/stereodcam_params 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/vision/stereodcam_params/stereodcam_params 2009-04-02 19:01:08 UTC (rev 13322)
@@ -1 +0,0 @@
-link stereodcam_params.py
\ No newline at end of file
Deleted: pkg/trunk/vision/stereodcam_params/stereodcam_params.py
===================================================================
--- pkg/trunk/vision/stereodcam_params/stereodcam_params.py 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/vision/stereodcam_params/stereodcam_params.py 2009-04-02 19:01:08 UTC (rev 13322)
@@ -1,331 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2009, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of the Willow Garage nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-
-
-import wx
-import wx.lib.intctrl
-import sys
-import os
-
-PKG = 'stereodcam_params' # this package name
-import roslib; roslib.load_manifest(PKG)
-from roslib.scriptutil import get_param_server, script_resolve_name
-from roslib.names import ns_join, get_ros_namespace, make_caller_id, make_global_ns, GLOBALNS
-
-import rospy
-from std_msgs.msg import Empty
-
-def _get_caller_id():
- return make_caller_id('%s-%s'%(PKG,os.getpid()))
-
-
-def succeed(args):
- code, msg, val = args
- if code != 1:
- raise RosParamException(msg)
- return val
-
-def _get_param(param):
- return succeed(get_param_server().getParam(_get_caller_id(), param))
-
-def _set_param(param, value):
- succeed(get_param_server().setParam(_get_caller_id(), param, value))
-
-
-
-class IntParameterWidget(wx.Panel):
-
- def __init__(self, parent, name, param, update_callback = None):
-
- self.param = param
- self.update_callback = update_callback
-
- wx.Panel.__init__(self, parent ,-1)
- self.label = wx.StaticText(self, -1, name)
- self.edit = wx.lib.intctrl.IntCtrl(self, -1)
-
- # properties
- self.label.SetMinSize((150,-1))
-
- # layout
- sizer = wx.BoxSizer(wx.HORIZONTAL)
- sizer.Add(self.label,0,0,0)
- sizer.Add(self.edit,0,0,0)
- self.SetSizer(sizer)
-
- # bindings
- self.Bind(wx.EVT_TEXT, self.onEdit, self.edit)
-
- self._initValue()
-
-
- def _initValue(self):
- try:
- value = _get_param(self.param)
- self.edit.SetValue(value)
- except:
- print "Cannot read value for parameter: "+self.param
-
-
- def _setParam(self, param, value):
- try:
- _set_param(param, value)
- if self.update_callback != None:
- self.update_callback()
- except:
- print "Cannot set parameter: "+self.param
-
- def onEdit(self, event):
- value = int(event.GetString())
- print value
- self._setParam(self.param, value)
-
-
-class BoolParameterWidget(wx.Panel):
-
- def __init__(self, parent, name, param, update_callback = None):
-
- self.param = param
- self.update_callback = update_callback
-
- wx.Panel.__init__(self, parent ,-1)
- self.label = wx.StaticText(self, -1, name)
- self.checkbox = wx.CheckBox(self, -1, "active")
-
- # properties
- self.label.SetMinSize((150,-1))
-
- # layout
- sizer = wx.BoxSizer(wx.HORIZONTAL)
- sizer.Add(self.label,0,0,0)
- sizer.Add(self.checkbox,0,0,0)
- self.SetSizer(sizer)
-
- # bindings
- self.Bind(wx.EVT_CHECKBOX, self.onCheckbox, self.checkbox)
-
- self._initValue()
-
-
- def _initValue(self):
- try:
- value = _get_param(self.param)
- self.checkbox.SetValue(value)
- except:
- print "Cannot read value for parameter: "+self.param
-
-
- def _setParam(self, param, value):
- try:
- _set_param(param, value)
- if self.update_callback != None:
- self.update_callback()
- except:
- print "Cannot set parameter: "+self.param
-
- def onCheckbox(self, event):
- value = event.IsChecked();
- self._setParam(self.param, value)
-
-
-class RangeParameterWidget(wx.Panel):
-
- def __init__(self, parent, name, param, update_callback = None, has_auto = False):
-
- self.param = param
- self.update_callback = update_callback
- self.has_auto = has_auto
-
- wx.Panel.__init__(self, parent ,-1)
- self.label = wx.StaticText(self, -1, name)
- self.slider = wx.Slider(self, -1, 0, 0, 100)
- self.spin = wx.SpinCtrl(self, -1, "", min=0, max=100)
- if self.has_auto:
- self.checkbox = wx.CheckBox(self, -1, "auto")
-
- # properties
- self.label.SetMinSize((150,-1))
-
- # layout
- sizer = wx.BoxSizer(wx.HORIZONTAL)
- sizer.Add(self.label,0,0,0)
- sizer.Add(self.slider,1,0,0)
- sizer.Add(self.spin,0,0,0)
- if self.has_auto:
- sizer.Add(self.checkbox,0,0,0)
- self.SetSizer(sizer)
-
- # bindings
- self.Bind(wx.EVT_COMMAND_SCROLL, self.onSlider, self.slider)
- self.Bind(wx.EVT_SPINCTRL, self.onSpin, self.spin)
- if self.has_auto:
- self.Bind(wx.EVT_CHECKBOX, self.onCheckbox, self.checkbox)
-
- self._initRange()
- self._initValue()
-
- def _initRange(self):
- try:
- min_value = _get_param(self.param+"_min")
- max_value = _get_param(self.param+"_max")
- self.slider.SetRange(min_value, max_value)
- self.spin.SetRange(min_value, max_value)
- except:
- print "Cannot read range for parameter: "+self.param
-
- def _initValue(self):
- try:
- value = _get_param(self.param)
- self.slider.SetValue(value)
- self.spin.SetValue(value)
- except:
- print "Cannot read value for parameter: "+self.param
- if self.has_auto:
- try:
- value = _get_param(self.param+"_auto")
- self.checkbox.SetValue(value)
- if value:
- self.slider.Disable()
- self.spin.Disable()
- else:
- self.slider.Enable()
- self.spin.Enable()
- except:
- print "Cannot tell if auto is set for parameter: "+self.param
-
- def _setParam(self, param, value):
- try:
- _set_param(param, value)
- if self.update_callback != None:
- self.update_callback()
- except:
- print "Cannot set parameter: "+param
-
- def onSlider(self, event):
- value = event.GetPosition()
- self.spin.SetValue(value)
- self._setParam(self.param, value)
-
- def onSpin(self, event):
- value = event.GetInt()
- self.slider.SetValue(value)
- self._setParam(self.param, value)
-
- def onCheckbox(self, event):
- value = event.IsChecked();
- self._setParam(self.param+"_auto", value)
- if value:
- self.slider.Disable()
- self.spin.Disable()
- else:
- self.slider.Enable()
- self.spin.Enable()
-
-
-class StereoParameters(wx.Frame):
- def __init__(self, *args, **kwds):
-
- kwds["style"] = wx.DEFAULT_FRAME_STYLE
- wx.Frame.__init__(self, *args, **kwds)
-
- self.widgets = []
- self.widgets.append(RangeParameterWidget(self, "Exposure", "stereo/exposure", has_auto = True, update_callback = self.update_stereo_params))
- self.widgets.append(RangeParameterWidget(self, "Gain", "stereo/gain", has_auto = True, update_callback = self.update_stereo_params))
- self.widgets.append(RangeParameterWidget(self, "Brightness", "stereo/brightness", has_auto = True, update_callback = self.update_stereo_params))
- self.widgets.append(BoolParameterWidget(self, "Companding", "stereo/companding", update_callback = self.update_stereo_params))
- self.widgets.append(BoolParameterWidget(self, "HDR", "stereo/hdr", update_callback = self.update_stereo_params))
- self.widgets.append(BoolParameterWidget(self, "Unique Check", "stereo/unique_check", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Texture Threshold", "stereo/texture_thresh", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Unique Threshold", "stereo/unique_thresh", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Smoothness Threshold", "stereo/smoothness_thresh", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Horopter", "stereo/horopter", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Speckle Size", "stereo/speckle_size", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Speckle Diff", "stereo/speckle_diff", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Corr Size", "stereo/corr_size", update_callback = self.update_stereo_params))
- self.widgets.append(IntParameterWidget(self, "Num Disp", "stereo/num_disp", update_callback = self.update_stereo_params))
-
- self.close_button = wx.Button(self, -1, "Close")
-
- self.__set_properties()
- self.__do_layout()
-
- self.Bind(wx.EVT_BUTTON, self.onClose, self.close_button)
-
- self.check_params = rospy.Publisher('stereo/check_params', Empty)
- rospy.init_node('stereodcam_params', anonymous=True)
-
-
- def update_stereo_params(self):
- self.check_params.publish(Empty())
-
-
- def __set_properties(self):
- self.SetTitle("Stereo Parameters")
- self.SetSize((498, 500))
-
- def __do_layout(self):
- vsizer = wx.BoxSizer(wx.VERTICAL)
- vsizer.Add((10, 10), 0, 0, 0)
-
- for widget in self.widgets:
- vsizer.Add(widget, 1, wx.EXPAND, 0)
-
- vsizer.Add(self.close_button, 0, wx.ALIGN_CENTER_HORIZONTAL|wx.ALIGN_CENTER_VERTICAL, 0)
- vsizer.Add((10, 10), 0, 0, 0)
- hsizer = wx.BoxSizer(wx.HORIZONTAL)
- hsizer.Add((10, 10), 0, 0, 0)
- hsizer.Add(vsizer, 1, wx.EXPAND, 0)
- hsizer.Add((10, 10), 0, 0, 0)
- self.SetSizer(hsizer)
-
- self.Layout()
-
-
- def onClose(self, event):
- sys.exit(0)
-
-
-
-class MyApp(wx.App):
- def OnInit(self):
- wx.InitAllImageHandlers()
- frame_2 = StereoParameters(None, -1, "")
- self.SetTopWindow(frame_2)
- frame_2.Show()
- return 1
-
-# end of class MyApp
-
-if __name__ == "__main__":
- app = MyApp(0)
- app.MainLoop()
Deleted: pkg/trunk/vision/stereodcam_params/stereodcam_params.wxg
===================================================================
--- pkg/trunk/vision/stereodcam_params/stereodcam_params.wxg 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/vision/stereodcam_params/stereodcam_params.wxg 2009-04-02 19:01:08 UTC (rev 13322)
@@ -1,97 +0,0 @@
-<?xml version="1.0"?>
-<!-- generated by wxGlade 0.6.3 on Fri Mar 20 15:34:19 2009 -->
-
-<application path="/u/mariusm/ros/ros-pkg/vision/stereodcam_params/stereodcam_params_test.py" name="" class="MyApp" option="0" language="python" top_window="frame_1" encoding="UTF-8" use_gettext="0" overwrite="0" use_new_namespace="1" for_version="2.8" is_template="0">
- <object class="MyFrame" name="frame_1" base="EditFrame">
- <style>wxDEFAULT_FRAME_STYLE</style>
- <title>frame_1</title>
- <object class="wxBoxSizer" name="sizer_2" base="EditBoxSizer">
- <orient>wxVERTICAL</orient>
- <object class="sizeritem">
- <flag>wxEXPAND</flag>
- <border>10</border>
- <option>1</option>
- <object class="wxPanel" name="panel_1" base="EditPanel">
- <style>wxTAB_TRAVERSAL</style>
- <object class="wxBoxSizer" name="sizer_2_copy_copy_copy" base="EditBoxSizer">
- <orient>wxHORIZONTAL</orient>
- <object class="sizeritem">
- <border>0</border>
- <option>0</option>
- <object class="wxStaticText" name="exposure_label_copy" base="EditStaticText">
- <attribute>1</attribute>
- <label>Exposure</label>
- <size>100, -1</size>
- </object>
- </object>
- <object class="sizeritem">
- <border>0</border>
- <option>0</option>
- <object class="wxCheckBox" name="checkbox_1" base="EditCheckBox">
- <label>auto</label>
- <events>
- <handler event="EVT_CHECKBOX">onCheckbox</handler>
- </events>
- </object>
- </object>
- <object class="sizeritem">
- <border>0</border>
- <option>1</option>
- <object class="wxSlider" name="exposure_slider_copy" base="EditSlider">
- <style>wxSL_HORIZONTAL</style>
- <events>
- <handler event="EVT_COMMAND_SCROLL">onExposureSlider</handler>
- </events>
- </object>
- </object>
- <object class="sizeritem">
- <border>0</border>
- <option>0</option>
- <object class="wxSpinCtrl" name="exposure_spin_copy" base="EditSpinCtrl">
- <events>
- <handler event="EVT_SPINCTRL">onExposureSpin</handler>
- </events>
- </object>
- </object>
- </object>
- </object>
- </object>
- <object class="sizeritem">
- <flag>wxEXPAND</flag>
- <border>0</border>
- <option>1</option>
- <object class="wxPanel" name="panel_2" base="EditPanel">
- <style>wxTAB_TRAVERSAL</style>
- <object class="wxStaticBoxSizer" name="sizer_3" base="EditStaticBoxSizer">
- <orient>wxHORIZONTAL</orient>
- <label>Test</label>
- <object class="sizeritem">
- <border>0</border>
- <option>0</option>
- <object class="wxStaticText" name="exposure_label_copy_copy" base="EditStaticText">
- <attribute>1</attribute>
- <label>Exposure</label>
- <size>100, -1</size>
- </object>
- </object>
- <object class="sizeritem">
- <border>0</border>
- <option>1</option>
- <object class="spacer" name="spacer" base="EditSpacer">
- <height>20</height>
- <width>20</width>
- </object>
- </object>
- <object class="sizeritem">
- <border>0</border>
- <option>0</option>
- <object class="wxTextCtrl" name="text_ctrl_1" base="EditTextCtrl">
- <size>100, -1</size>
- </object>
- </object>
- </object>
- </object>
- </object>
- </object>
- </object>
-</application>
Deleted: pkg/trunk/vision/stereodcam_params/stereodcam_params_test.py
===================================================================
--- pkg/trunk/vision/stereodcam_params/stereodcam_params_test.py 2009-04-02 18:51:31 UTC (rev 13321)
+++ pkg/trunk/vision/stereodcam_params/stereodcam_params_test.py 2009-04-02 19:01:08 UTC (rev 13322)
@@ -1,95 +0,0 @@
-#!/usr/bin/env python
-# -*- coding: utf-8 -*-
-# generated by wxGlade 0.6.3 on Fri Mar 20 14:03:53 2009
-
-import wx
-
-# begin wxGlade: extracode
-# end wxGlade
-
-
-
-class MyFrame(wx.Frame):
- def __init__(self, *args, **kwds):
- # begin wxGlade: MyFrame.__init__
- kwds["style"] = wx.DEFAULT_FRAME_STYLE
- wx.Frame.__init__(self, *args, **kwds)
- self.panel_2 = wx.Panel(self, -1)
- self.sizer_3_staticbox = wx.StaticBox(self.panel_2, -1, "Test")
- self.panel_1 = wx.Panel(self, -1)
- self.exposure_label_copy = wx.StaticText(self.panel_1, -1, "Exposure")
- self.checkbox_1 = wx.CheckBox(self.panel_1, -1, "auto")
- self.exposure_slider_copy = wx.Slider(self.panel_1, -1, 0, 0, 10)
- self.exposure_spin_copy = wx.SpinCtrl(self.panel_1, -1, "", min=0, max=100)
- self.exposure_label_copy_copy = wx.StaticText(self.panel_2, -1, "Exposure")
- self.text_ctrl_1 = wx.TextCtrl(self.panel_2, -1, "")
-
- self.__set_properties()
- self.__do_layout()
-
- self.Bind(wx.EVT_CHECKBOX, self.onCheckbox, self.checkbox_1)
- self.Bind(wx.EVT_COMMAND_SCROLL, self.onExposureSlider, self.exposure_slider_copy)
- self.Bind(wx.EVT_SPINCTRL, self.onExposureSpin, self.exposure_spin_copy)
- # end wxGlade
-
- def __set_properties(self):
- # begin wxGlade: MyFrame.__set_properties
- self.SetTitle("frame_1")
- self.exposure_label_copy.SetMinSize((100, -1))
- self.exposure_label_copy_copy.SetMinSize((100, -1))
- self.text_ctrl_1.SetMinSize((100, -1))
- # end wxGlade
-
- def __do_layout(self):
- # begin wxGlade: MyFrame.__do_layout
- sizer_2 = wx.BoxSizer(wx.VERTICAL)
- sizer_3 = wx.StaticBoxSizer(self.sizer_3_staticbox, wx.HORIZONTAL)
- sizer_2_copy_copy_copy = wx.BoxSizer(wx.HORIZONTAL)
- sizer_2_copy_copy_copy.Add(self.exposure_label_copy, 0, 0, 0)
- sizer_2_copy_copy_copy.Add(self.checkbox_1, 0, 0, 0)
- sizer_2_copy_copy_copy.Add(self.exposure_slider_copy, 1, 0, 0)
- sizer_2_copy_copy_copy.Add(self.exposure_spin_copy, 0, 0, 0)
- self.panel_1.SetSizer(sizer_2_copy_copy_copy)
- sizer_2.Add(self.panel_1, 1, wx.EXPAND, 0)
- sizer_3.Add(self.exposure_label_copy_copy, 0, 0, 0)
- sizer_3.Add((20, 20), 1, 0, 0)
- sizer_3.Add(self.text_ctrl_1, 0, 0, 0)
- self.panel_2.SetSizer(sizer_3)
- sizer_2.Add(self.panel_2, 1, wx.EXPAND, 0)
- self.SetSizer(sizer_2)
- sizer_2.Fit(self)
- self.Layout()
- # end wxGlade
-
- def onExposureSlider(self, event): # wxGlade: MyFrame.<event_handler>
- print "Event handler `onExposureSlider' not implemented!"
- event.Skip()
-
- def onExposureSpin(self, event): # wxGlade: MyFrame.<event_handler>
- print "Event handler `onExposureSpin' not implemented!"
- event.Skip()
-
- def onCheckbox(self, event): # wxGlade: MyFrame.<event_handler>
- print "Event handler `onCheckbox' not implemented"
- event.Skip()
-
- def onEdit(self, event): # wxGlade: MyFrame.<event_handler>
- print "Event handler `onEdit' not implemented"
- event.Skip()
-
-# end of class MyFrame
-
-
-class MyApp(wx.App):
- def OnInit(self):
- wx.InitAllImageHandlers()
- frame_1 = MyFrame(None, -1, "")
- self.SetTopWindow(frame_1)
- frame_1.Show()
- return 1
-
-# end of class MyApp
-
-if __name__ == "__main__":
- app = MyApp(0)
- app.MainLoop()
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|