v01
This commit is contained in:
71
thirdparty/ros/ros_comm/tools/topic_tools/test/args.py
vendored
Normal file
71
thirdparty/ros/ros_comm/tools/topic_tools/test/args.py
vendored
Normal file
@@ -0,0 +1,71 @@
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, 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 Willow Garage, Inc. 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: Brian Gerkey
|
||||
|
||||
# Test that arg-parsing works
|
||||
|
||||
PKG = 'topic_tools'
|
||||
|
||||
import unittest
|
||||
import os
|
||||
from subprocess import call
|
||||
|
||||
|
||||
class TopicToolsTestCase(unittest.TestCase):
|
||||
|
||||
def test_drop_invalid(self):
|
||||
cmd = ['rosrun', 'topic_tools', 'drop']
|
||||
self.assertNotEquals(0, call(cmd))
|
||||
self.assertNotEquals(0, call(cmd + ['//', '1', '2', 'output']))
|
||||
self.assertNotEquals(0, call(cmd + ['input', '1', '2', 'output', 'extra']))
|
||||
self.assertNotEquals(0, call(cmd + ['input', '-1', '2', 'output']))
|
||||
self.assertNotEquals(0, call(cmd + ['input', '1', '0', 'output']))
|
||||
|
||||
def test_mux_invalid(self):
|
||||
cmd = ['rosrun', 'topic_tools', 'mux']
|
||||
self.assertNotEquals(0, call(cmd))
|
||||
self.assertNotEquals(0, call(cmd + ['//', 'input']))
|
||||
|
||||
def test_switch_mux_invalid(self):
|
||||
cmd = ['rosrun', 'topic_tools', 'switch_mux']
|
||||
self.assertNotEquals(0, call(cmd))
|
||||
self.assertNotEquals(0, call(cmd + ['//', 'input']))
|
||||
|
||||
def test_relay_invalid(self):
|
||||
cmd = ['rosrun', 'topic_tools', 'relay']
|
||||
self.assertNotEquals(0, call(cmd))
|
||||
self.assertNotEquals(0, call(cmd + ['//', 'input']))
|
||||
|
||||
if __name__ == "__main__":
|
||||
import rostest
|
||||
rostest.unitrun(PKG, 'topic_tools_arg_parsing', TopicToolsTestCase)
|
||||
14
thirdparty/ros/ros_comm/tools/topic_tools/test/delete_mux.test
vendored
Normal file
14
thirdparty/ros/ros_comm/tools/topic_tools/test/delete_mux.test
vendored
Normal file
@@ -0,0 +1,14 @@
|
||||
<!-- Testing the condition described in #2863 -->
|
||||
<launch>
|
||||
<node pkg="topic_tools" type="mux" name="mux"
|
||||
args="a b c" output="screen"/>
|
||||
<node pkg="topic_tools" type="test_mux_delete_add.py"
|
||||
name="test_mux_delete_add" />
|
||||
<test test-name="delete_mux_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="a"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
25
thirdparty/ros/ros_comm/tools/topic_tools/test/drop.test
vendored
Normal file
25
thirdparty/ros/ros_comm/tools/topic_tools/test/drop.test
vendored
Normal file
@@ -0,0 +1,25 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub -r 10 input std_msgs/String chatter"/>
|
||||
|
||||
<!-- Automatic output name -->
|
||||
<node pkg="topic_tools" type="drop" name="drop"
|
||||
args="input 1 2"/>
|
||||
<test test-name="drop_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="input_drop"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="drop" name="drop_explicit"
|
||||
args="input 1 2 output"/>
|
||||
<test test-name="drop_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
28
thirdparty/ros/ros_comm/tools/topic_tools/test/lazy_transport.test
vendored
Normal file
28
thirdparty/ros/ros_comm/tools/topic_tools/test/lazy_transport.test
vendored
Normal file
@@ -0,0 +1,28 @@
|
||||
<launch>
|
||||
|
||||
<node pkg="rostopic" type="rostopic" name="input"
|
||||
args="pub /input std_msgs/String 'data: spam' -r 10">
|
||||
</node>
|
||||
|
||||
<node name="simple_lazy_string_transport"
|
||||
pkg="topic_tools" type="simple_lazy_transport.py">
|
||||
<remap from="~input" to="input" />
|
||||
<param name="~lazy" value="true" />
|
||||
<rosparam>
|
||||
msg_name: std_msgs/String
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<test test-name="test_lazy_transport"
|
||||
name="test_lazy_transport"
|
||||
pkg="topic_tools" type="test_lazy_transport.py"
|
||||
retry="3">
|
||||
<remap from="~input" to="simple_lazy_string_transport/output" />
|
||||
<rosparam>
|
||||
input_topic_type: std_msgs/String
|
||||
check_connected_topics: [simple_lazy_string_transport/output, input]
|
||||
wait_for_connection: 3
|
||||
</rosparam>
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
17
thirdparty/ros/ros_comm/tools/topic_tools/test/mux.test
vendored
Normal file
17
thirdparty/ros/ros_comm/tools/topic_tools/test/mux.test
vendored
Normal file
@@ -0,0 +1,17 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
|
||||
args="pub -r 10 input1 std_msgs/String input1"/>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
|
||||
args="pub -r 5 input2 std_msgs/String input2"/>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="mux" name="mux_explicit" output="screen"
|
||||
args="output input1 input2"/>
|
||||
<test test-name="mux_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="10.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
10
thirdparty/ros/ros_comm/tools/topic_tools/test/mux_add.test
vendored
Normal file
10
thirdparty/ros/ros_comm/tools/topic_tools/test/mux_add.test
vendored
Normal file
@@ -0,0 +1,10 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
|
||||
args="pub -r 10 input1 std_msgs/String input"/>
|
||||
|
||||
<node pkg="topic_tools" type="mux" name="mux_explicit" output="screen"
|
||||
args="output input"/>
|
||||
<test test-name="mux_services" pkg="test_topic_tools" type="test_mux_services.py"/>
|
||||
|
||||
</launch>
|
||||
|
||||
25
thirdparty/ros/ros_comm/tools/topic_tools/test/relay.test
vendored
Normal file
25
thirdparty/ros/ros_comm/tools/topic_tools/test/relay.test
vendored
Normal file
@@ -0,0 +1,25 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub -r 10 input std_msgs/String chatter"/>
|
||||
|
||||
<!-- Automatic output name -->
|
||||
<node pkg="topic_tools" type="relay" name="relay"
|
||||
args="input"/>
|
||||
<test test-name="relay_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="input_relay"/>
|
||||
<param name="hz" value="10.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="relay" name="relay_explicit"
|
||||
args="input output"/>
|
||||
<test test-name="relay_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="10.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
7
thirdparty/ros/ros_comm/tools/topic_tools/test/relay_latched.test
vendored
Normal file
7
thirdparty/ros/ros_comm/tools/topic_tools/test/relay_latched.test
vendored
Normal file
@@ -0,0 +1,7 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub input std_msgs/String chatter"/>
|
||||
<node pkg="topic_tools" type="relay" name="relay"
|
||||
args="input output"/>
|
||||
<test test-name="relay_latched" pkg="test_topic_tools" type="test_one_message.py" time-limit="10"/>
|
||||
</launch>
|
||||
6
thirdparty/ros/ros_comm/tools/topic_tools/test/shapeshifter.test
vendored
Normal file
6
thirdparty/ros/ros_comm/tools/topic_tools/test/shapeshifter.test
vendored
Normal file
@@ -0,0 +1,6 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub -r 10 input std_msgs/String chatter"/>
|
||||
|
||||
<test test-name="test_shapeshifter" pkg="topic_tools" type="topic_tools-test_shapeshifter"/>
|
||||
</launch>
|
||||
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux.test
vendored
Normal file
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux.test
vendored
Normal file
@@ -0,0 +1,19 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
|
||||
args="pub -r 10 input1 std_msgs/String chatter"/>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
|
||||
args="pub -r 5 input2 std_msgs/String chatter"/>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="mux" name="mux_explicit"
|
||||
args="output input1 input2"/>
|
||||
<node pkg="topic_tools" type="mux_select" name="mux_select"
|
||||
args="mux input2"/>
|
||||
<test test-name="switch_mux_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux_leading_slash.test
vendored
Normal file
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux_leading_slash.test
vendored
Normal file
@@ -0,0 +1,19 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
|
||||
args="pub -r 10 input1 std_msgs/String chatter"/>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
|
||||
args="pub -r 5 input2 std_msgs/String chatter"/>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="mux" name="mux_explicit"
|
||||
args="output input1 input2"/>
|
||||
<node pkg="topic_tools" type="mux_select" name="mux_select"
|
||||
args="mux /input2"/>
|
||||
<test test-name="switch_mux_leading_slash_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux_none.test
vendored
Normal file
19
thirdparty/ros/ros_comm/tools/topic_tools/test/switch_mux_none.test
vendored
Normal file
@@ -0,0 +1,19 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
|
||||
args="pub -r 10 input1 std_msgs/String chatter"/>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub2"
|
||||
args="pub -r 5 input2 std_msgs/String chatter"/>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="mux" name="mux_explicit"
|
||||
args="output input1 input2"/>
|
||||
<node pkg="topic_tools" type="mux_select" name="mux_select"
|
||||
args="mux __none"/>
|
||||
<test test-name="switch_mux_none_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="0.0"/>
|
||||
<param name="hzerror" value="0.5"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
64
thirdparty/ros/ros_comm/tools/topic_tools/test/test_lazy_transport.py
vendored
Executable file
64
thirdparty/ros/ros_comm/tools/topic_tools/test/test_lazy_transport.py
vendored
Executable file
@@ -0,0 +1,64 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
import os
|
||||
import sys
|
||||
|
||||
import unittest
|
||||
|
||||
import rosgraph
|
||||
import rospy
|
||||
import rosmsg
|
||||
import roslib
|
||||
|
||||
|
||||
PKG = 'topic_tools'
|
||||
NAME = 'test_lazy_transport'
|
||||
|
||||
|
||||
class TestLazyTransport(unittest.TestCase):
|
||||
|
||||
def __init__(self, *args):
|
||||
super(self.__class__, self).__init__(*args)
|
||||
rospy.init_node(NAME)
|
||||
|
||||
def test_no_subscribers(self):
|
||||
check_connected_topics = rospy.get_param('~check_connected_topics')
|
||||
master = rosgraph.Master('/test_connection')
|
||||
_, sub, _ = master.getSystemState()
|
||||
# Check assumed topics are not there
|
||||
master = rosgraph.Master('test_connection')
|
||||
_, subscriptions, _ = master.getSystemState()
|
||||
for check_topic in check_connected_topics:
|
||||
for topic, sub_node in subscriptions:
|
||||
if topic == rospy.get_namespace() + check_topic:
|
||||
raise ValueError('Found topic: {}'.format(check_topic))
|
||||
|
||||
def test_subscriber_appears(self):
|
||||
topic_type = rospy.get_param('~input_topic_type')
|
||||
check_connected_topics = rospy.get_param('~check_connected_topics')
|
||||
wait_time = rospy.get_param('~wait_for_connection', 0)
|
||||
msg_class = roslib.message.get_message_class(topic_type)
|
||||
# Subscribe topic and bond connection
|
||||
sub = rospy.Subscriber('~input', msg_class,
|
||||
self._cb_test_subscriber_appears)
|
||||
print('Waiting for connection for {} sec.'.format(wait_time))
|
||||
rospy.sleep(wait_time)
|
||||
# Check assumed topics are there
|
||||
master = rosgraph.Master('test_connection')
|
||||
_, subscriptions, _ = master.getSystemState()
|
||||
for check_topic in check_connected_topics:
|
||||
for topic, sub_node in subscriptions:
|
||||
if topic == rospy.get_namespace() + check_topic:
|
||||
break
|
||||
else:
|
||||
raise ValueError('Topic Not Found: {}'
|
||||
.format(rospy.get_namespace() + check_topic))
|
||||
sub.unregister()
|
||||
|
||||
def _cb_test_subscriber_appears(self, msg):
|
||||
pass
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
import rostest
|
||||
rostest.rosrun(PKG, NAME, TestLazyTransport)
|
||||
74
thirdparty/ros/ros_comm/tools/topic_tools/test/test_mux_delete_add.py
vendored
Executable file
74
thirdparty/ros/ros_comm/tools/topic_tools/test/test_mux_delete_add.py
vendored
Executable file
@@ -0,0 +1,74 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, 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 Willow Garage, Inc. 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: Brian Gerkey
|
||||
|
||||
PKG = 'topic_tools'
|
||||
|
||||
import rospy
|
||||
|
||||
from topic_tools.srv import MuxAdd
|
||||
from topic_tools.srv import MuxDelete
|
||||
from topic_tools.srv import MuxList
|
||||
from topic_tools.srv import MuxSelect
|
||||
from std_msgs.msg import String
|
||||
|
||||
def go():
|
||||
rospy.init_node('chatter')
|
||||
|
||||
rospy.wait_for_service('mux/add', 5)
|
||||
rospy.wait_for_service('mux/delete', 5)
|
||||
rospy.wait_for_service('mux/list', 5)
|
||||
rospy.wait_for_service('mux/select', 5)
|
||||
|
||||
add_srv = rospy.ServiceProxy('mux/add', MuxAdd)
|
||||
delete_srv = rospy.ServiceProxy('mux/delete', MuxDelete)
|
||||
list_srv = rospy.ServiceProxy('mux/list', MuxList)
|
||||
select_srv = rospy.ServiceProxy('mux/select', MuxSelect)
|
||||
|
||||
b_pub = rospy.Publisher('b', String)
|
||||
|
||||
# Execute the sequence given in #2863
|
||||
select_srv('c')
|
||||
delete_srv('b')
|
||||
add_srv('b')
|
||||
select_srv('b')
|
||||
|
||||
# Now start publishing on b
|
||||
while not rospy.is_shutdown():
|
||||
b_pub.publish('foo')
|
||||
rospy.sleep(0.2)
|
||||
|
||||
if __name__ == "__main__":
|
||||
go()
|
||||
107
thirdparty/ros/ros_comm/tools/topic_tools/test/test_mux_services.py
vendored
Executable file
107
thirdparty/ros/ros_comm/tools/topic_tools/test/test_mux_services.py
vendored
Executable file
@@ -0,0 +1,107 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, 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 Willow Garage, Inc. 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: Brian Gerkey
|
||||
|
||||
PKG = 'topic_tools'
|
||||
|
||||
import unittest
|
||||
import rospy
|
||||
|
||||
from topic_tools.srv import MuxAdd
|
||||
from topic_tools.srv import MuxDelete
|
||||
from topic_tools.srv import MuxList
|
||||
from topic_tools.srv import MuxSelect
|
||||
|
||||
class MuxServiceTestCase(unittest.TestCase):
|
||||
def make_srv_proxies(self):
|
||||
try:
|
||||
rospy.wait_for_service('mux/add', 5)
|
||||
rospy.wait_for_service('mux/delete', 5)
|
||||
rospy.wait_for_service('mux/list', 5)
|
||||
rospy.wait_for_service('mux/select', 5)
|
||||
except rospy.ROSException as e:
|
||||
self.fail('failed to find a required service: ' + repr(e))
|
||||
|
||||
add_srv = rospy.ServiceProxy('mux/add', MuxAdd)
|
||||
delete_srv = rospy.ServiceProxy('mux/delete', MuxDelete)
|
||||
list_srv = rospy.ServiceProxy('mux/list', MuxList)
|
||||
select_srv = rospy.ServiceProxy('mux/select', MuxSelect)
|
||||
|
||||
return (add_srv, delete_srv, list_srv, select_srv)
|
||||
|
||||
def test_add_delete_list(self):
|
||||
add_srv, delete_srv, list_srv, select_srv = self.make_srv_proxies()
|
||||
# Check initial condition
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set(['/input']))
|
||||
# Add a topic and make sure it's there
|
||||
add_srv('/new_input')
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set(['/input', '/new_input']))
|
||||
# Try to add the same topic again, make sure it fails, and that
|
||||
# nothing changes.
|
||||
try:
|
||||
add_srv('/new_input')
|
||||
except rospy.ServiceException:
|
||||
pass
|
||||
else:
|
||||
self.fail('service call should have thrown an exception')
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set(['/input', '/new_input']))
|
||||
# Select a topic, then try to delete it, make sure it fails, and
|
||||
# that nothing changes.
|
||||
select_srv('/input')
|
||||
try:
|
||||
delete_srv('/input')
|
||||
except rospy.ServiceException:
|
||||
pass
|
||||
else:
|
||||
self.fail('service call should have thrown an exception')
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set(['/input', '/new_input']))
|
||||
# Select nothing, to allow deletion
|
||||
select_srv('__none')
|
||||
# Delete topics
|
||||
delete_srv('/input')
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set(['/new_input']))
|
||||
delete_srv('/new_input')
|
||||
topics = list_srv().topics
|
||||
self.assertEquals(set(topics), set([]))
|
||||
|
||||
if __name__ == "__main__":
|
||||
import rostest
|
||||
rostest.unitrun(PKG, 'mux_services', MuxServiceTestCase)
|
||||
|
||||
60
thirdparty/ros/ros_comm/tools/topic_tools/test/test_one_message.py
vendored
Executable file
60
thirdparty/ros/ros_comm/tools/topic_tools/test/test_one_message.py
vendored
Executable file
@@ -0,0 +1,60 @@
|
||||
#!/usr/bin/env python
|
||||
# Software License Agreement (BSD License)
|
||||
#
|
||||
# Copyright (c) 2008, 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 Willow Garage, Inc. 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 unittest
|
||||
import rospy
|
||||
import rostest
|
||||
import sys
|
||||
from std_msgs.msg import *
|
||||
|
||||
class LatchedSub(unittest.TestCase):
|
||||
|
||||
def msg_cb(self, msg):
|
||||
self.success = True
|
||||
|
||||
|
||||
def test_latched_sub(self):
|
||||
rospy.init_node('random_sub')
|
||||
|
||||
self.success = False
|
||||
|
||||
sub = rospy.Subscriber("output", String, self.msg_cb)
|
||||
|
||||
while not self.success:
|
||||
rospy.sleep(rospy.Duration.from_sec(0.5))
|
||||
|
||||
self.assertEqual(self.success, True)
|
||||
|
||||
if __name__ == '__main__':
|
||||
rostest.rosrun('rosbag', 'latched_sub', LatchedSub, sys.argv)
|
||||
|
||||
170
thirdparty/ros/ros_comm/tools/topic_tools/test/test_shapeshifter.cpp
vendored
Normal file
170
thirdparty/ros/ros_comm/tools/topic_tools/test/test_shapeshifter.cpp
vendored
Normal file
@@ -0,0 +1,170 @@
|
||||
/*********************************************************************
|
||||
* 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 Willow Garage, Inc. 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.
|
||||
********************************************************************/
|
||||
|
||||
// Bring in my package's API, which is what I'm testing
|
||||
#include "ros/ros.h"
|
||||
#include "topic_tools/shape_shifter.h"
|
||||
#include "std_msgs/String.h"
|
||||
#include "std_msgs/Int32.h"
|
||||
|
||||
// Bring in gtest
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
class ShapeShifterSubscriber : public testing::Test
|
||||
{
|
||||
public:
|
||||
|
||||
bool success;
|
||||
|
||||
void messageCallbackInt(const topic_tools::ShapeShifter::ConstPtr& msg)
|
||||
{
|
||||
try {
|
||||
std_msgs::Int32::Ptr s = msg->instantiate<std_msgs::Int32>();
|
||||
} catch (topic_tools::ShapeShifterException& e)
|
||||
{
|
||||
success = true;
|
||||
}
|
||||
}
|
||||
|
||||
void messageCallbackString(const topic_tools::ShapeShifter::ConstPtr& msg)
|
||||
{
|
||||
try {
|
||||
std_msgs::String::Ptr s = msg->instantiate<std_msgs::String>();
|
||||
if (s->data == "chatter")
|
||||
success = true;
|
||||
} catch (topic_tools::ShapeShifterException& e)
|
||||
{
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void messageCallbackLoopback(const topic_tools::ShapeShifter::ConstPtr& msg)
|
||||
{
|
||||
try {
|
||||
std_msgs::String::Ptr s = msg->instantiate<std_msgs::String>();
|
||||
printf("Got data: %s", s->data.c_str());
|
||||
if (s->data == "abc123")
|
||||
success = true;
|
||||
} catch (topic_tools::ShapeShifterException& e)
|
||||
{
|
||||
printf("Instantiate failed!\n");
|
||||
}
|
||||
}
|
||||
|
||||
protected:
|
||||
ShapeShifterSubscriber() {}
|
||||
|
||||
void SetUp()
|
||||
{
|
||||
success = false;
|
||||
}
|
||||
|
||||
void TearDown() {}
|
||||
};
|
||||
|
||||
|
||||
TEST_F(ShapeShifterSubscriber, testInstantiateString)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber sub = nh.subscribe<topic_tools::ShapeShifter>("input",1,&ShapeShifterSubscriber::messageCallbackString, (ShapeShifterSubscriber*)this);
|
||||
|
||||
ros::Time t1(ros::Time::now()+ros::Duration(10.0));
|
||||
|
||||
while(ros::Time::now() < t1 && !success)
|
||||
{
|
||||
ros::WallDuration(0.01).sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
|
||||
EXPECT_FALSE(topic_tools::ShapeShifter::uses_old_API_);
|
||||
|
||||
if(success)
|
||||
SUCCEED();
|
||||
else
|
||||
FAIL();
|
||||
}
|
||||
|
||||
TEST_F(ShapeShifterSubscriber, testInstantiateInt)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber sub = nh.subscribe<topic_tools::ShapeShifter>("input",1,&ShapeShifterSubscriber::messageCallbackInt, (ShapeShifterSubscriber*)this);
|
||||
|
||||
ros::Time t1(ros::Time::now()+ros::Duration(10.0));
|
||||
|
||||
while(ros::Time::now() < t1 && !success)
|
||||
{
|
||||
ros::WallDuration(0.01).sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
|
||||
EXPECT_FALSE(topic_tools::ShapeShifter::uses_old_API_);
|
||||
|
||||
if(success)
|
||||
SUCCEED();
|
||||
else
|
||||
FAIL();
|
||||
}
|
||||
|
||||
TEST_F(ShapeShifterSubscriber, testLoopback)
|
||||
{
|
||||
ros::NodeHandle nh;
|
||||
ros::Subscriber sub = nh.subscribe<topic_tools::ShapeShifter>("loopback",1,&ShapeShifterSubscriber::messageCallbackLoopback, (ShapeShifterSubscriber*)this);
|
||||
|
||||
ros::Time t1(ros::Time::now()+ros::Duration(10.0));
|
||||
|
||||
ros::Publisher pub = nh.advertise<std_msgs::String>("loopback", 1);
|
||||
std_msgs::String s;
|
||||
s.data = "abc123";
|
||||
pub.publish(s);
|
||||
|
||||
while(ros::Time::now() < t1 && !success)
|
||||
{
|
||||
ros::WallDuration(0.01).sleep();
|
||||
ros::spinOnce();
|
||||
}
|
||||
|
||||
EXPECT_FALSE(topic_tools::ShapeShifter::uses_old_API_);
|
||||
|
||||
if(success)
|
||||
SUCCEED();
|
||||
else
|
||||
FAIL();
|
||||
}
|
||||
|
||||
int main(int argc, char **argv){
|
||||
ros::init(argc, argv, "test_shapeshifter");
|
||||
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
||||
42
thirdparty/ros/ros_comm/tools/topic_tools/test/throttle.test
vendored
Normal file
42
thirdparty/ros/ros_comm/tools/topic_tools/test/throttle.test
vendored
Normal file
@@ -0,0 +1,42 @@
|
||||
<launch>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub -r 20 input std_msgs/String chatter"/>
|
||||
|
||||
<!-- Automatic output name -->
|
||||
<node pkg="topic_tools" type="throttle" name="throttle"
|
||||
args="messages input 5"/>
|
||||
<test test-name="throttle_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="input_throttle"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="1.0"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
<!-- Explicit output name -->
|
||||
<node pkg="topic_tools" type="throttle" name="throttle_explicit"
|
||||
args="messages input 5 output"/>
|
||||
<test test-name="throttle_hztest_explicit" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="1.0"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
|
||||
<!-- Test byte-based throttling. Note that the desired rate for the
|
||||
hztest is a function of both the requested bytes/second and the length of
|
||||
the string being published:
|
||||
10 msg/sec = 110 B/sec / 11 B/msg
|
||||
(11 = 4-byte length + 7 characters in "chatter")
|
||||
It would be more direct to test the bandwidth directly, but hztest
|
||||
doesn't do that. -->
|
||||
<node pkg="topic_tools" type="throttle" name="throttle_bytes"
|
||||
args="bytes input 110 1 output_bytes"/>
|
||||
<test test-name="throttle_hztest_bytes" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="output_bytes"/>
|
||||
<param name="hz" value="10.0"/>
|
||||
<!-- Wider tolerance because we're seeing occasional under-minimum failures -->
|
||||
<param name="hzerror" value="1.5"/>
|
||||
<param name="test_duration" value="4.0" />
|
||||
</test>
|
||||
|
||||
</launch>
|
||||
18
thirdparty/ros/ros_comm/tools/topic_tools/test/throttle_simtime.test
vendored
Normal file
18
thirdparty/ros/ros_comm/tools/topic_tools/test/throttle_simtime.test
vendored
Normal file
@@ -0,0 +1,18 @@
|
||||
<launch>
|
||||
<param name="use_sim_time" value="True"/>
|
||||
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
|
||||
args="pub -r 20 input std_msgs/String chatter"/>
|
||||
|
||||
<!-- Automatic output name -->
|
||||
<node pkg="topic_tools" type="throttle" name="throttle"
|
||||
args="messages input 5">
|
||||
<param name="wall_clock" value="True"/>
|
||||
</node>
|
||||
<test test-name="throttle_simtime_hztest" pkg="rostest" type="hztest">
|
||||
<param name="topic" value="input_throttle"/>
|
||||
<param name="hz" value="5.0"/>
|
||||
<param name="hzerror" value="1.0"/>
|
||||
<param name="wall_clock" value="True"/>
|
||||
<param name="test_duration" value="2.0" />
|
||||
</test>
|
||||
</launch>
|
||||
94
thirdparty/ros/ros_comm/tools/topic_tools/test/utest.cpp
vendored
Normal file
94
thirdparty/ros/ros_comm/tools/topic_tools/test/utest.cpp
vendored
Normal file
@@ -0,0 +1,94 @@
|
||||
// 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 Willow Garage, Inc. 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.
|
||||
|
||||
#include "topic_tools/parse.h"
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
TEST(GetBaseName, simpleName)
|
||||
{
|
||||
std::string in("foo");
|
||||
std::string expected("foo");
|
||||
std::string out;
|
||||
|
||||
ASSERT_TRUE(topic_tools::getBaseName(in, out));
|
||||
ASSERT_EQ(expected, out);
|
||||
}
|
||||
|
||||
TEST(GetBaseName, leadingSlash)
|
||||
{
|
||||
std::string in("/foo");
|
||||
std::string expected("foo");
|
||||
std::string out;
|
||||
|
||||
ASSERT_TRUE(topic_tools::getBaseName(in, out));
|
||||
ASSERT_EQ(expected, out);
|
||||
}
|
||||
|
||||
TEST(GetBaseName, trailingSlash)
|
||||
{
|
||||
std::string in("foo/");
|
||||
std::string expected("foo");
|
||||
std::string out;
|
||||
|
||||
ASSERT_TRUE(topic_tools::getBaseName(in, out));
|
||||
ASSERT_EQ(expected, out);
|
||||
}
|
||||
|
||||
TEST(GetBaseName, multipleLevels)
|
||||
{
|
||||
std::string in("bar/bat/baz/foo");
|
||||
std::string expected("foo");
|
||||
std::string out;
|
||||
|
||||
ASSERT_TRUE(topic_tools::getBaseName(in, out));
|
||||
ASSERT_EQ(expected, out);
|
||||
}
|
||||
|
||||
TEST(GetBaseName, multipleSlashes)
|
||||
{
|
||||
std::string in("//bar///bat/baz/foo///");
|
||||
std::string expected("foo");
|
||||
std::string out;
|
||||
|
||||
ASSERT_TRUE(topic_tools::getBaseName(in, out));
|
||||
ASSERT_EQ(expected, out);
|
||||
}
|
||||
|
||||
TEST(GetBaseName, emptyName)
|
||||
{
|
||||
std::string in("///");
|
||||
std::string out;
|
||||
|
||||
ASSERT_FALSE(topic_tools::getBaseName(in, out));
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
||||
Reference in New Issue
Block a user