Skip to content

Commit

Permalink
Merge pull request #1917 from ros/backports_melodic
Browse files Browse the repository at this point in the history
changes between 1.15.4 (Noetic) and 1.14.4 for backporting into Melodic
  • Loading branch information
dirk-thomas authored Mar 20, 2020
2 parents 12eaf94 + 73c50de commit 07b70a0
Show file tree
Hide file tree
Showing 8 changed files with 95 additions and 20 deletions.
2 changes: 2 additions & 0 deletions clients/rospy/src/rospy/impl/tcpros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,8 @@ def run(self):
(client_sock, client_addr) = self.server_sock.accept()
except socket.timeout:
continue
except ConnectionAbortedError:
continue
except IOError as e:
(e_errno, msg) = e.args
if e_errno == errno.EINTR: #interrupted system call
Expand Down
3 changes: 1 addition & 2 deletions clients/rospy/src/rospy/msproxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -159,8 +159,7 @@ def get_param_cached(self, key):
return rospy.impl.paramserver.get_param_server_cache().get(resolved_key)
except KeyError:
# first access, make call to parameter server
with self._lock:
code, msg, value = self.target.subscribeParam(rospy.names.get_caller_id(), rospy.core.get_node_uri(), resolved_key)
code, msg, value = self.target.subscribeParam(rospy.names.get_caller_id(), rospy.core.get_node_uri(), resolved_key)
if code != 1: #unwrap value with Python semantics
raise KeyError(key)
# set the value in the cache so that it's marked as subscribed
Expand Down
16 changes: 8 additions & 8 deletions clients/rospy/src/rospy/topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,13 @@ class Poller(object):
on multiple platforms. NOT thread-safe.
"""
def __init__(self):
if hasattr(select, 'epoll'):
if hasattr(select, 'kqueue'):
self.poller = select.kqueue()
self.add_fd = self.add_kqueue
self.remove_fd = self.remove_kqueue
self.error_iter = self.error_kqueue_iter
self.kevents = []
elif hasattr(select, 'epoll'):
self.poller = select.epoll()
self.add_fd = self.add_epoll
self.remove_fd = self.remove_epoll
Expand All @@ -202,12 +208,6 @@ def __init__(self):
self.add_fd = self.add_poll
self.remove_fd = self.remove_poll
self.error_iter = self.error_poll_iter
elif hasattr(select, 'kqueue'):
self.poller = select.kqueue()
self.add_fd = self.add_kqueue
self.remove_fd = self.remove_kqueue
self.error_iter = self.error_kqueue_iter
self.kevents = []
else:
#TODO: non-Noop impl for Windows
self.poller = self.noop
Expand Down Expand Up @@ -1173,7 +1173,7 @@ def check_all(self):
Check all registered publication and subscriptions.
"""
with self.lock:
for t in chain(iter(self.pubs.values()), iter(self.subs.values())):
for t in chain(list(self.pubs.values()), list(self.subs.values())):
t.check()

def _add(self, ps, rmap, reg_type):
Expand Down
10 changes: 8 additions & 2 deletions test/test_rospy/test/rostest/test_topic_statistics.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,10 @@ def setUp(self):
self.topic_statistic_msg_map = {}

def new_msg(self, msg):
self.topic_statistic_msg_map[msg.topic] = msg
# need at least two messages to compute the period fields
# since messages without period fields aren't useful skip them
if msg.delivered_msgs > 1:
self.topic_statistic_msg_map[msg.topic] = msg

def assert_eventually(
self, cond, timeout=rospy.Duration(5.0), interval=rospy.Duration(0.5)
Expand All @@ -67,6 +70,8 @@ def frequency_acceptable(self, topic, expected, error_margin=0.1):
''' return True if topic message's measured frequency
is within some error margin of expected frequency '''
msg = self.topic_statistic_msg_map[topic]
# need at least two messages to compute the period fields
assert msg.delivered_msgs > 1
found_freq = 1.0 / msg.period_mean.to_sec()
rospy.loginfo(
"Testing {}'s found frequency {} against expected {}".format(
Expand All @@ -83,7 +88,8 @@ def test_frequencies(self):
self.assert_eventually(
lambda: '/slow_chatter' in self.topic_statistic_msg_map)
self.assert_eventually(
lambda: '/very_slow_chatter' in self.topic_statistic_msg_map)
lambda: '/very_slow_chatter' in self.topic_statistic_msg_map,
timeout=rospy.Duration(10.0))

self.assertTrue(self.frequency_acceptable('/very_fast_chatter', 150))
self.assertTrue(self.frequency_acceptable('/fast_chatter', 53))
Expand Down
76 changes: 72 additions & 4 deletions tools/roslaunch/test/unit/test_roslaunch_param_dump.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ def fakestdout():
import rospkg
import logging

SAMPLE1 = """/rosparam_load/dict1/head: 1
SAMPLE1_OLD_YAML = """/rosparam_load/dict1/head: 1
/rosparam_load/dict1/knees: 3
/rosparam_load/dict1/shoulders: 2
/rosparam_load/dict1/toes: 4
Expand All @@ -72,7 +72,39 @@ def fakestdout():
/rosparam_load/string1: bar
/rosparam_load/string2: '10'"""

SAMPLE2 = """/load_ns/subns/dict1/head: 1
SAMPLE1_NEW_YAML = """/rosparam_load/dict1/head: 1
/rosparam_load/dict1/knees: 3
/rosparam_load/dict1/shoulders: 2
/rosparam_load/dict1/toes: 4
/rosparam_load/integer1: 1
/rosparam_load/integer2: 2
/rosparam_load/list1:
- head
- shoulders
- knees
- toes
/rosparam_load/list2:
- 1
- 1
- 2
- 3
- 5
- 8
/rosparam_load/preformattedtext: 'This is the first line
This is the second line
Line breaks are preserved
Indentation is stripped
'
/rosparam_load/robots/child/grandchildparam: a grandchild namespace param
/rosparam_load/robots/childparam: a child namespace parameter
/rosparam_load/string1: bar
/rosparam_load/string2: '10'"""

SAMPLE2_OLD_YAML = """/load_ns/subns/dict1/head: 1
/load_ns/subns/dict1/knees: 3
/load_ns/subns/dict1/shoulders: 2
/load_ns/subns/dict1/toes: 4
Expand All @@ -94,6 +126,38 @@ def fakestdout():
/load_ns/subns/string1: bar
/load_ns/subns/string2: '10'"""

SAMPLE2_NEW_YAML = """/load_ns/subns/dict1/head: 1
/load_ns/subns/dict1/knees: 3
/load_ns/subns/dict1/shoulders: 2
/load_ns/subns/dict1/toes: 4
/load_ns/subns/integer1: 1
/load_ns/subns/integer2: 2
/load_ns/subns/list1:
- head
- shoulders
- knees
- toes
/load_ns/subns/list2:
- 1
- 1
- 2
- 3
- 5
- 8
/load_ns/subns/preformattedtext: 'This is the first line
This is the second line
Line breaks are preserved
Indentation is stripped
'
/load_ns/subns/robots/child/grandchildparam: a grandchild namespace param
/load_ns/subns/robots/childparam: a child namespace parameter
/load_ns/subns/string1: bar
/load_ns/subns/string2: '10'"""


def test_dump_params():
# normal entrypoint has logging configured
Expand All @@ -107,14 +171,18 @@ def test_dump_params():
s = b.getvalue().strip()
# remove float vals as serialization is not stable
s = '\n'.join([x for x in s.split('\n') if not 'float' in x])
assert str(s) == str(SAMPLE1), "[%s]\nvs\n[%s]"%(s, SAMPLE1)
assert str(s) in (SAMPLE1_OLD_YAML, SAMPLE1_NEW_YAML), \
"[%s]\nvs\n[%s]\nor\n[%s]" % \
(s, SAMPLE1_OLD_YAML, SAMPLE1_NEW_YAML)
node_rosparam_f = os.path.join(test_d, 'test-node-rosparam-load-ns.xml')
with fakestdout() as b:
assert dump_params([node_rosparam_f])
s = b.getvalue().strip()
# remove float vals as serialization is not stable
s = '\n'.join([x for x in s.split('\n') if not 'float' in x])
assert str(s) == str(SAMPLE2), "[%s]\nvs\n[%s]"%(s, SAMPLE2)
assert str(s) in(SAMPLE2_OLD_YAML, SAMPLE2_NEW_YAML), \
"[%s]\nvs\n[%s]\nor\n[%s]" % \
(s, SAMPLE2_OLD_YAML, SAMPLE2_NEW_YAML)

invalid_f = os.path.join(test_d, 'invalid-xml.xml')
with fakestdout() as b:
Expand Down
2 changes: 1 addition & 1 deletion tools/rostest/test/advertisetest.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<node pkg="rostopic" type="rostopic" name="once_topic_pub" args="pub /once_topic std_msgs/Bool 'data: false' -1l" />
<node pkg="rostest" type="service_server.py" name="service_server"/>

<test test-name="advertisetest_test" pkg="rostest" type="advertisetest" time-limit="5.0" retry="3">
<test test-name="advertisetest_test" pkg="rostest" type="advertisetest" time-limit="7.0" retry="3">
<rosparam>
topics:
- name: /frequent_topic
Expand Down
2 changes: 1 addition & 1 deletion tools/rostest/test/publishtest.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<node pkg="rostopic" type="rostopic" name="freq_topic_pub" args="pub /frequent_topic std_msgs/Bool 'data: false' -r 10" />
<node pkg="rostopic" type="rostopic" name="once_topic_pub" args="pub /once_topic std_msgs/Bool 'data: false' -1l" />

<test test-name="publishtest_test" pkg="rostest" type="publishtest" time-limit="3.0" retry="3">
<test test-name="publishtest_test" pkg="rostest" type="publishtest" time-limit="5.0" retry="3">
<rosparam>
topics:
- name: /frequent_topic
Expand Down
4 changes: 2 additions & 2 deletions tools/topic_tools/test/transform.test
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
args="pub -r 2 /num1 std_msgs/Float32 'data: 1.0'"/>
<node pkg="topic_tools" type="transform" name="transform"
args="/num1 /num2 std_msgs/Float32 'm.data * 3.0'"/>
args="--wait-for-start /num1 /num2 std_msgs/Float32 'm.data * 3.0'"/>

<test test-name="transform_" pkg="topic_tools"
type="test_transform.py" time-limit="3.0"
Expand All @@ -18,7 +18,7 @@
<node pkg="rostopic" type="rostopic" name="rostopic_pub"
args="pub -r 2 num3 std_msgs/Float32 'data: 3.0'" />
<node pkg="topic_tools" type="transform" name="transform"
args="num3 num4 std_msgs/Float32 'm.data * 2.0'"/>
args="--wait-for-start num3 num4 std_msgs/Float32 'm.data * 2.0'"/>

<test test-name="transform_ns" pkg="topic_tools"
type="test_transform.py" time-limit="3.0"
Expand Down

0 comments on commit 07b70a0

Please sign in to comment.