Skip to content

Commit

Permalink
rosmsg: clean up test dependencies (#2103)
Browse files Browse the repository at this point in the history
All dependencies must be declared in the package.xml, and all these
dependencies must be in the ROS distro. rosmsg doesn't meet either of
these requirements today, by using but not depending on both rostest and
std_srvs, and by using test_rosmaster, which isn't in the ROS distro at
all.

Update rosmsg to properly depend upon what it requires, and stop using
test_rosmaster completely. In place of test_rosmaster, use
diagnostic_msgs, which satisfies the same requirements of the existing
tests by having both messages and services as well as standalone and
recursive messages.

Signed-off-by: Kyle Fazzari <kyle@canonical.com>
  • Loading branch information
kyrofa committed Mar 11, 2021
1 parent 70d4b5b commit f8022d7
Show file tree
Hide file tree
Showing 13 changed files with 103 additions and 69 deletions.
3 changes: 3 additions & 0 deletions tools/rosmsg/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,10 @@
<exec_depend>rosbag</exec_depend>
<exec_depend>roslib</exec_depend>

<test_depend>rostest</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>std_srvs</test_depend>
<test_depend>diagnostic_msgs</test_depend>

<export>
<rosdoc config="rosdoc.yaml"/>
Expand Down
11 changes: 11 additions & 0 deletions tools/rosmsg/test/DiagnosticStatus_raw.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
byte OK=0
byte WARN=1
byte ERROR=2
byte STALE=3
byte level
string name
string message
string hardware_id
diagnostic_msgs/KeyValue[] values
string key
string value
4 changes: 0 additions & 4 deletions tools/rosmsg/test/RosmsgC_raw.txt

This file was deleted.

9 changes: 9 additions & 0 deletions tools/rosmsg/test/msg/DiagnosticStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
byte OK=0
byte WARN=1
byte ERROR=2
byte STALE=3
byte level
string name
string message
string hardware_id
diagnostic_msgs/KeyValue[] values
2 changes: 2 additions & 0 deletions tools/rosmsg/test/msg/KeyValue.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string key
string value
1 change: 0 additions & 1 deletion tools/rosmsg/test/msg/RosmsgA.msg

This file was deleted.

1 change: 0 additions & 1 deletion tools/rosmsg/test/msg/RosmsgB.msg

This file was deleted.

4 changes: 4 additions & 0 deletions tools/rosmsg/test/srv/AddDiagnostics.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
string load_namespace
---
bool success
string message
3 changes: 0 additions & 3 deletions tools/rosmsg/test/srv/RossrvA.srv

This file was deleted.

3 changes: 0 additions & 3 deletions tools/rosmsg/test/srv/RossrvB.srv

This file was deleted.

15 changes: 15 additions & 0 deletions tools/rosmsg/test/srv/SelfTest.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
---
string id
byte passed
diagnostic_msgs/DiagnosticStatus[] status
byte OK=0
byte WARN=1
byte ERROR=2
byte STALE=3
byte level
string name
string message
string hardware_id
diagnostic_msgs/KeyValue[] values
string key
string value
36 changes: 19 additions & 17 deletions tools/rosmsg/test/test_rosmsg.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,21 +69,21 @@ def test_get_msg_text(self):
d = get_test_path()
msg_d = os.path.join(d, 'msg')

test_message_package = 'test_rosmaster'
test_message_package = 'diagnostic_msgs'
rospack = rospkg.RosPack()
msg_raw_d = os.path.join(rospack.get_path(test_message_package), 'msg')
for t in ['RosmsgA', 'RosmsgB']:
with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
text = f.read()
with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
text_raw = f.read()
type_ = test_message_package+'/'+t
self.assertEquals(text, rosmsg.get_msg_text(type_, raw=False))
self.assertEquals(text_raw, rosmsg.get_msg_text(type_, raw=True))
t = 'KeyValue'
with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
text = f.read()
with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
text_raw = f.read()

type_ = test_message_package+'/'+t
self.assertEquals(text, rosmsg.get_msg_text(type_, raw=False))
self.assertEquals(text_raw, rosmsg.get_msg_text(type_, raw=True))

# test recursive types
t = 'RosmsgC'
t = 'DiagnosticStatus'
with open(os.path.join(d, '%s_raw.txt'%t), 'r') as f:
text = f.read()
with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
Expand Down Expand Up @@ -120,24 +120,26 @@ def test_list_types(self):
# test msgs
l = rosmsg.list_types('rospy', mode='.msg')
self.assertEquals([], l)
l = rosmsg.list_types('test_rosmaster', mode='.msg')
for t in ['test_rosmaster/RosmsgA', 'test_rosmaster/RosmsgB', 'test_rosmaster/RosmsgC']:
l = rosmsg.list_types('diagnostic_msgs', mode='.msg')
for t in ['diagnostic_msgs/DiagnosticArray',
'diagnostic_msgs/DiagnosticStatus',
'diagnostic_msgs/KeyValue']:
assert t in l

l = rosmsg.list_types('rospy', mode='.srv')
self.assertEquals([], l)
l = rosmsg.list_types('test_rosmaster', mode='.srv')
for t in ['test_rosmaster/RossrvA', 'test_rosmaster/RossrvB']:
l = rosmsg.list_types('diagnostic_msgs', mode='.srv')
for t in ['diagnostic_msgs/AddDiagnostics', 'diagnostic_msgs/SelfTest']:
assert t in l

def test_get_srv_text(self):
d = get_test_path()
srv_d = os.path.join(d, 'srv')

test_srv_package = 'test_rosmaster'
test_srv_package = 'diagnostic_msgs'
rospack = rospkg.RosPack()
srv_raw_d = os.path.join(rospack.get_path(test_srv_package), 'srv')
for t in ['RossrvA', 'RossrvB']:
for t in ['AddDiagnostics', 'SelfTest']:
with open(os.path.join(srv_d, '%s.srv'%t), 'r') as f:
text = f.read()
with open(os.path.join(srv_raw_d, '%s.srv'%t), 'r') as f:
Expand Down
80 changes: 40 additions & 40 deletions tools/rosmsg/test/test_rosmsg_command_line.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ def test_cmd_packages(self):
l1 = [x for x in output1.split() if x]
l2 = [x.strip() for x in output2.split('\n') if x.strip()]
self.assertEquals(l1, l2)
for p in ['std_msgs', 'test_rosmaster']:
for p in ['std_msgs', 'diagnostic_msgs']:
self.assert_(p in l1)
for p in ['std_srvs', 'rosmsg']:
self.assert_(p not in l1)
Expand All @@ -85,7 +85,7 @@ def test_cmd_packages(self):
l1 = [x for x in output1.split() if x]
l2 = [x.strip() for x in output2.split('\n') if x.strip()]
self.assertEquals(l1, l2)
for p in ['std_srvs', 'test_rosmaster']:
for p in ['std_srvs', 'diagnostic_msgs']:
self.assert_(p in l1)
for p in ['std_msgs', 'rospy']:
self.assert_(p not in l1)
Expand All @@ -94,7 +94,7 @@ def test_cmd_list(self):
# - multi-line
output1 = Popen([sys.executable, os.path.join(_SCRIPT_FOLDER,'rosmsg'), 'list'], stdout=PIPE).communicate()[0].decode()
l1 = [x.strip() for x in output1.split('\n') if x.strip()]
for p in ['std_msgs/String', 'test_rosmaster/Floats']:
for p in ['std_msgs/String', 'diagnostic_msgs/DiagnosticArray']:
self.assert_(p in l1)
for p in ['std_srvs/Empty', 'roscpp/Empty']:
self.assert_(p not in l1)
Expand All @@ -103,31 +103,31 @@ def test_cmd_list(self):
l1 = [x.strip() for x in output1.split('\n') if x.strip()]
for p in ['std_srvs/Empty', 'roscpp/Empty']:
self.assert_(p in l1)
for p in ['std_msgs/String', 'test_rosmaster/Floats']:
for p in ['std_msgs/String', 'diagnostic_msgs/DiagnosticStatus']:
self.assert_(p not in l1)

def test_cmd_package(self):
# this test is obviously very brittle, but should stabilize as the tests stabilize
# - single line output
output1 = Popen(['rosmsg', 'package', '-s', 'test_rosmaster'], stdout=PIPE).communicate()[0].decode()
output1 = Popen(['rosmsg', 'package', '-s', 'diagnostic_msgs'], stdout=PIPE).communicate()[0].decode()
# - multi-line output
output2 = Popen(['rosmsg', 'package', 'test_rosmaster'], stdout=PIPE).communicate()[0].decode()
output2 = Popen(['rosmsg', 'package', 'diagnostic_msgs'], stdout=PIPE).communicate()[0].decode()
l = set([x for x in output1.split() if x])
l2 = set([x.strip() for x in output2.split('\n') if x.strip()])
self.assertEquals(l, l2)

for m in ['test_rosmaster/RosmsgA',
'test_rosmaster/RosmsgB',
'test_rosmaster/RosmsgC']:
for m in ['diagnostic_msgs/DiagnosticArray',
'diagnostic_msgs/DiagnosticStatus',
'diagnostic_msgs/KeyValue']:
self.assertTrue(m in l, l)

output = Popen(['rossrv', 'package', '-s', 'test_rosmaster'], stdout=PIPE).communicate()[0].decode()
output2 = Popen(['rossrv', 'package','test_rosmaster'], stdout=PIPE).communicate()[0].decode()
output = Popen(['rossrv', 'package', '-s', 'diagnostic_msgs'], stdout=PIPE).communicate()[0].decode()
output2 = Popen(['rossrv', 'package','diagnostic_msgs'], stdout=PIPE).communicate()[0].decode()
l = set([x for x in output.split() if x])
l2 = set([x.strip() for x in output2.split('\n') if x.strip()])
self.assertEquals(l, l2)

for m in ['test_rosmaster/RossrvA', 'test_rosmaster/RossrvB']:
for m in ['diagnostic_msgs/AddDiagnostics', 'diagnostic_msgs/SelfTest']:
self.assertTrue(m in l, l)

## test that the rosmsg/rossrv show command works
Expand All @@ -139,41 +139,41 @@ def test_cmd_show(self):
self.assertEquals('---', output.strip())
output = Popen(['rossrv', 'show', 'std_srvs/Empty'], stdout=PIPE).communicate()[0].decode()
self.assertEquals('---', output.strip())
output = Popen(['rossrv', 'show', 'test_rosmaster/AddTwoInts'], stdout=PIPE).communicate()[0].decode()
self.assertEquals(os.linesep.join(['int64 a', 'int64 b', '---', 'int64 sum']), output.strip())
output = Popen(['rossrv', 'show', 'diagnostic_msgs/AddDiagnostics'], stdout=PIPE).communicate()[0].decode()
self.assertEquals('string load_namespace\n---\nbool success\nstring message', output.strip())

# test against test_rosmsg package
d = os.path.abspath(os.path.dirname(__file__))
msg_d = os.path.join(d, 'msg')

test_message_package = 'test_rosmaster'
test_message_package = 'diagnostic_msgs'
rospack = rospkg.RosPack()
msg_raw_d = os.path.join(rospack.get_path(test_message_package), 'msg')

# - test with non-recursive types
for t in ['RosmsgA', 'RosmsgB']:
with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
text = f.read()
with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
text_raw = f.read()
text = text.strip()
text_raw = text_raw.strip()
type_ =test_message_package+'/'+t
output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text, output.strip())
output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())
output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())
t = 'KeyValue'
with open(os.path.join(msg_d, '%s.msg'%t), 'r') as f:
text = f.read()
with open(os.path.join(msg_raw_d, '%s.msg'%t), 'r') as f:
text_raw = f.read()
text = text.strip()
text_raw = text_raw.strip()
type_ =test_message_package+'/'+t
output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text, output.strip())
output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())
output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())

# test as search
type_ = t
text_prefix = "[test_rosmaster/%s]:"%t
text = os.linesep.join([text_prefix, text])
text_raw = os.linesep.join([text_prefix, text_raw])
output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text, output.strip())
output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE, stderr=PIPE).communicate()
self.assertEquals(text_raw, output[0].decode().strip(), "Failed: %s"%(str(output)))
output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())
# test as search
type_ = t
text_prefix = "[diagnostic_msgs/%s]:"%t
text = os.linesep.join([text_prefix, text])
text_raw = os.linesep.join([text_prefix, text_raw])
output = Popen(['rosmsg', 'show', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text, output.strip())
output = Popen(['rosmsg', 'show', '-r',type_], stdout=PIPE, stderr=PIPE).communicate()
self.assertEquals(text_raw, output[0].decode().strip(), "Failed: %s"%(str(output)))
output = Popen(['rosmsg', 'show', '--raw', type_], stdout=PIPE).communicate()[0].decode()
self.assertEquals(text_raw, output.strip())

0 comments on commit f8022d7

Please sign in to comment.