Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[jsk_tools] add ROS param set test #1535

Merged
merged 3 commits into from
Nov 14, 2017
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
4 changes: 4 additions & 0 deletions jsk_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ if (CATKIN_ENABLE_TESTING)
find_package(roslint REQUIRED)
roslint_python(src/jsk_tools/cltool.py)
roslint_python(src/test_topic_published.py)
roslint_python(src/test_rosparam_set.py)
roslint_python(src/test_stdout.py)
roslint_python(src/rostopic_host_sanity)
roslint_add_test()
Expand All @@ -44,6 +45,9 @@ if (CATKIN_ENABLE_TESTING)
# FIXME: jsk_tools/sanity_lib.py does not work on hydro travis/jenkins
# https://github.com/jsk-ros-pkg/jsk_common/pull/1405#issuecomment-225218625
jsk_tools_add_rostest(test/python/sanity_lib.test)
# FIXME: jsk_tools/test_topic_published.py does not work on hydro travis/jenkins
# https://github.com/jsk-ros-pkg/jsk_common/pull/1293#issuecomment-164158260
jsk_tools_add_rostest(test/test_rosparam_set.test)
endif()
jsk_tools_add_rostest(test/test_stdout.test)
find_package(jsk_tools REQUIRED)
Expand Down
87 changes: 87 additions & 0 deletions jsk_tools/src/test_rosparam_set.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
#!/usr/bin/env python
# -*- coding: utf-8 -*-

import re
import sys
import time
import unittest

from nose.tools import assert_true

import rospy


PKG = 'jsk_tools'
NAME = 'test_rosparam_set'


class ROSParamChecker(object):
def __init__(self, param_name, expected, timeout):
self.param_name = param_name
self.expected = expected
self.deadline = rospy.Time.now() + rospy.Duration(timeout)

def assert_rosparam(self):
param = rospy.get_param(self.param_name, None)
if param == self.expected:
return True
if rospy.Time.now() > self.deadline:
return False
return None


class TestROSParamSet(unittest.TestCase):
def __init__(self, *args):
super(TestROSParamSet, self).__init__(*args)
rospy.init_node(NAME)
# params to check sanity
self.param_names = []
self.timeouts = []
self.expecteds = []
params = rospy.get_param('~params', None)
for param in params:
self.param_names.append(param['name'])
self.expecteds.append(param['expected'])
self.timeouts.append(param['timeout'])
if not self.param_names:
rospy.logerr('No ROS param is specified.')
sys.exit(1)

def test_set(self):
"""Test ROS params are correctly set"""
use_sim_time = rospy.get_param('/use_sim_time', False)
t_start = time.time()
while not rospy.is_shutdown() and \
use_sim_time and (rospy.Time.now() == rospy.Time(0)):
rospy.logwarn('/use_sim_time is specified and rostime is 0, '
'/clock is published?')
if time.time() - t_start > 10:
self.fail('Timed out (10s) of /clock publication.')
time.sleep(1)

checkers = []
for param_name, timeout, expected in zip(
self.param_names, self.timeouts, self.expecteds):
checker = ROSParamChecker(param_name, expected, timeout)
checkers.append(checker)

params_finished = []
while not rospy.is_shutdown():
if len(params_finished) == len(checkers):
break
for i, checker in enumerate(checkers):
if checker.param_name in params_finished:
continue
ret = checker.assert_rosparam()
if ret is None:
continue
params_finished.append(checker.param_name)
assert_true(
ret, 'ROS param [%s] is not correctly set' %
checker.param_name)
rospy.sleep(0.01)


if __name__ == '__main__':
import rostest
rostest.run(PKG, NAME, TestROSParamSet, sys.argv)
19 changes: 19 additions & 0 deletions jsk_tools/test/test_rosparam_set.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<launch>
<param name="test_param_0" value="true" />
<param name="test_param_1" value="hello" />

<test test-name="test_rosparam_set"
name="test_rosparam_set"
pkg="jsk_tools" type="test_rosparam_set.py">
<rosparam>
params:
- name: /test_param_0
expected: true
timeout: 10
- name: /test_param_1
expected: hello
timeout: 10
</rosparam>
</test>

</launch>