Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions .github/workflows/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,8 @@ jobs:
source /opt/ros/${{ matrix.ROS_DISTRO }}/setup.bash
set -x
cd ~/ws/
# smach_viewer is not depend on roseus_smach, but we need to build roseus_smach before smach_viewer for tests
[ ${{ matrix.ROS_DISTRO }} != "one" ] || catkin build roseus_smach --no-status -sv ${{ matrix.CATKIN_OPTIONS }} --cmake-args -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON ${{ matrix.CMAKE_OPTIONS }}
catkin build --no-status -sv ${{ matrix.CATKIN_OPTIONS }} --cmake-args -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON ${{ matrix.CMAKE_OPTIONS }}
shell: bash

Expand All @@ -130,9 +132,8 @@ jobs:
run: |
source ~/ws/devel/setup.bash
set -x
cd ~/ws/
[ ${{ matrix.ROS_DISTRO }} != "one" ] || touch src/jsk_roseus/CATKIN_IGNORE
catkin test --no-status -sv ${{ matrix.CATKIN_OPTIONS }} --cmake-args -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON ${{ matrix.CMAKE_OPTIONS }}
cd ~/ws/build/smach_viewer
make run_tests
shell: bash

- name: Show Test Results
Expand Down
3 changes: 3 additions & 0 deletions smach_viewer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,17 +18,20 @@ catkin_install_python(
catkin_install_python(
PROGRAMS test/test_smach.py
test/test_rosout_error.py
test/test_smach_event.py
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/test)
if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest(test/test_smach_py.test)
add_rostest(test/test_smach_image.test)
add_rostest(test/test_smach_event.test)
find_package(roseus QUIET)
if(roseus_FOUND)
add_rostest(test/test_smach_eus.test)
endif()
find_package(roseus_smach QUIET)
if(roseus_smach_FOUND)
add_rostest(test/test_roseus_smach_state_machine_ros_sample.test)
add_rostest(test/test_smach_event.test ARGS target_python:=false target_roseus:=true)
endif()
endif()
3 changes: 3 additions & 0 deletions smach_viewer/scripts/smach_viewer.py
Original file line number Diff line number Diff line change
Expand Up @@ -484,6 +484,9 @@ def selection_changed(self, event):

# Generate the userdata string
ud_str = ''
if not isinstance(container._local_data._data, dict):
rospy.logwarn("userdata is not dictionary({}), please fix sender proram".format(container._local_data._data))
container._local_data._data = {}
for (k,v) in container._local_data._data.items():
ud_str += str(k)+": "
vstr = str(v)
Expand Down
62 changes: 62 additions & 0 deletions smach_viewer/test/test_smach_event.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#!/usr/bin/env python

import sys
import os

parent_dir_name = os.path.dirname(os.path.dirname(os.path.realpath(__file__)))

try:
import importlib.util
file_path = parent_dir_name + "/scripts/smach_viewer.py"
module_name = 'smach_viewer_frame'
spec = importlib.util.spec_from_file_location(module_name, file_path)
smach_viewer_frame = importlib.util.module_from_spec(spec)
sys.modules[module_name] = smach_viewer_frame
spec.loader.exec_module(smach_viewer_frame)

except:
sys.path.insert(0, parent_dir_name + "/scripts")
import smach_viewer as smach_viewer_frame

import wx

import rospy
import rostest
import unittest

import time

class TestSmachViewerEvent(unittest.TestCase):

def setUp(self):
rospy.init_node('test_smach_event', anonymous=True)
app = wx.App()

self.frame = smach_viewer_frame.SmachViewerFrame()
self.frame.set_filter('dot')
#/server_namsmach/container_statsup
self.frame.Show()
self.frame.is_button = type('DummyButton', (object, ), {'Disable': lambda self: None, 'Enable': lambda self: None})();
#app.MainLoop()
self.evtloop = wx.GUIEventLoop()
#old = wx.EventLoop.GetActive()
wx.EventLoop.SetActive(self.evtloop)

def test_samch_event(self):
try:
for i in range(10):
self.frame.path_input.SetValue('/SM_ROOT/FOO')
self.frame.selection_changed(None)
time.sleep(1)
self.evtloop.ProcessIdle()
rospy.loginfo("SUCCEEDED: _local_data {}".format(self.frame._containers))
rospy.loginfo("SUCCEEDED: _local_data {}".format([v._local_data._data for v in self.frame._containers.values()]))
self.frame.kill()
except Exception as e:
rospy.logerr(e)
rospy.logerr("FAILED: _local_data {}".format(self.frame._containers))
rospy.logerr("FAILED: _local_data {}".format([v._local_data._data for v in self.frame._containers.values()]))
self.assertFalse(e)

if __name__ == '__main__':
rostest.run('smach_viewer', 'test_smach_event', TestSmachViewerEvent, sys.argv)
10 changes: 10 additions & 0 deletions smach_viewer/test/test_smach_event.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<launch>
<arg name="target_python" default="true" />
<arg name="target_roseus" default="false" />
<node if="$(arg target_python)"
pkg="smach_viewer" name="test_smach_py" type="test_smach.py" />
<node if="$(arg target_roseus)"
pkg="roseus" name="test_smach_eus" type="roseus" args="$(find smach_viewer)/test/test_smach.l" />
<test test-name="smach_viewer_event_test"
pkg="smach_viewer" type="test_smach_event.py" name="smach_viewer_event_test" />
</launch>