8000 Changes between 1.14.9 and 1.14.10 for backporting to Kinetic by jacobperron · Pull Request #2084 · ros/ros_comm · GitHub
[go: up one dir, main page]
More Web Proxy on the site http://driver.im/
Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

Changes between 1.14.9 and 1.14.10 for backporting to Kinetic #2084

Merged
merged 12 commits into from
Oct 26, 2020
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
11 changes: 11 additions & 0 deletions clients/roscpp/include/ros/param.h
Original file line number Diff line number Diff line change
Expand Up @@ -591,6 +591,17 @@ ROSCPP_DECL bool search(const std::string& key, std::string& result);
*/
ROSCPP_DECL bool getParamNames(std::vector<std::string>& keys);

/**
* \brief Unsubscribe cached parameter from the master
* \param key the cached parameter to be unsubscribed
*/
ROSCPP_DECL void unsubscribeCachedParam(const std::string& key);

/**
* \brief Unsubscribe all cached parameter from the master
*/
ROSCPP_DECL void unsubscribeCachedParam(void);

/** \brief Assign value from parameter server, with default.
*
* This method tries to retrieve the indicated parameter value from the
Expand Down
5 changes: 4 additions & 1 deletion clients/roscpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,17 @@
roscpp is the most widely used ROS client library and is designed to
be the high-performance library for ROS.
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
<maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
<maintainer email="sloretz@openrobotics.org">Shane Loretz</maintainer>
<license>BSD</license>

<url>http://ros.org/wiki/roscpp</url>
<author>Morgan Quigley</author>
<author>Josh Faust</author>
<author>Brian Gerkey</author>
<author>Troy Straszheim</author>
<author email="dthomas@osrfoundation.org">Dirk Thomas</author>

<buildtool_depend version_gte="0.5.78">catkin</buildtool_depend>

Expand Down
28 changes: 27 additions & 1 deletion clients/roscpp/src/libros/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,11 @@ bool del(const std::string& key)
{
boost::mutex::scoped_lock lock(g_params_mutex);

g_subscribed_params.erase(mapped_key);
if (g_subscribed_params.find(mapped_key) != g_subscribed_params.end())
{
g_subscribed_params.erase(mapped_key);
unsubscribeCachedParam(mapped_key);
}
g_params.erase(mapped_key);
}

Expand Down Expand Up @@ -807,6 +811,28 @@ void paramUpdateCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& resul
ros::param::update((std::string)params[1], params[2]);
}

void unsubscribeCachedParam(const std::string& key)
{
XmlRpc::XmlRpcValue params, result, payload;
params[0] = this_node::getName();
params[1] = XMLRPCManager::instance()->getServerURI();
params[2] = key;
master::execute("unsubscribeParam", params, result, payload, false);
}

void unsubscribeCachedParam(void)
{
// lock required, all of the cached parameter will be unsubscribed.
boost::mutex::scoped_lock lock(g_params_mutex);

for(S_string::iterator itr = g_subscribed_params.begin();
itr != g_subscribed_params.end(); ++itr)
{
const std::string mapped_key(*itr);
unsubscribeCachedParam(mapped_key);
}
}

void init(const M_string& remappings)
{
M_string::const_iterator it = remappings.begin();
Expand Down
5 changes: 4 additions & 1 deletion clients/roscpp/src/libros/rosout_appender.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,10 @@ void ROSOutAppender::logThread()
return;
}

queue_condition_.wait(lock);
if (log_queue_.empty())
{
queue_condition_.wait(lock);
}

if (shutting_down_)
{
Expand Down
1 change: 1 addition & 0 deletions clients/roscpp/src/libros/service_server_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,6 +262,7 @@ void ServiceServerLink::callFinished()

current_call_->finished_ = true;
current_call_->finished_condition_.notify_all();
current_call_->call_finished_ = true;

saved_call = current_call_;
current_call_ = CallInfoPtr();
Expand Down
3 changes: 3 additions & 0 deletions clients/roscpp/src/libros/xmlrpc_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,9 @@ void XMLRPCManager::shutdown()
return;
}

// before shutting down, unsubscribe all the cached parameter
ros::param::unsubscribeCachedParam();

shutting_down_ = true;
server_thread_.join();

Expand Down
5 changes: 4 additions & 1 deletion clients/rospy/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,14 @@
and <a href="http://ros.org/wiki/rosservice">rosservice</a>, are
built on top of rospy.
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
<maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
<maintainer email="sloretz@openrobotics.org">Shane Loretz</maintainer>
<license>BSD</license>

<url>http://ros.org/wiki/rospy</url>
<author>Ken Conley</author>
<author email="dthomas@osrfoundation.org">Dirk Thomas</author>

<buildtool_depend version_gte="0.5.78">catkin</buildtool_depend>

Expand Down
4 changes: 4 additions & 0 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,10 @@ def __call__(self, caller_id, logging_func, period, msg):
(now - last_logging_time) > rospy.Duration(period)):
logging_func(msg)
self.last_logging_time_table[caller_id] = now
elif last_logging_time > now:
logging_func(msg)
self.last_logging_time_table = {}
self.last_logging_time_table[caller_id] = now


_logging_throttle = LoggingThrottle()
Expand Down
8 changes: 7 additions & 1 deletion clients/rospy/src/rospy/msproxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,14 @@ def __setitem__(self, key, val):
@param val: parameter value
@type val: XMLRPC legal value
"""
resolved_key = rospy.names.resolve_name(key)

with self._lock:
self.target.setParam(rospy.names.get_caller_id(), rospy.names.resolve_name(key), val)
self.target.setParam(rospy.names.get_caller_id(), resolved_key, val)
try:
rospy.impl.paramserver.get_param_server_cache().update(resolved_key, val)
except KeyError:
pass

def search_param(self, key):
"""
Expand Down
5 changes: 4 additions & 1 deletion ros_comm/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,9 @@
<description>
ROS communications-related packages, including core client libraries (roscpp, rospy) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
<maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
<maintainer email="sloretz@openrobotics.org">Shane Loretz</maintainer>
<license>BSD</license>

<url>http://www.ros.org/wiki/ros_comm</url>
Expand All @@ -20,6 +22,7 @@
<author email="bhaskara@willowgarage.com">Bhaskara Marthi</author>
<author email="straszheim@willowgarage.com">Troy Straszheim</author>
<author email="wheeler@willowgarage.com">Rob Wheeler</author>
<author email="dthomas@osrfoundation.org">Dirk Thomas</author>

<buildtool_depend>catkin</buildtool_depend>

Expand Down
2 changes: 2 additions & 0 deletions test/test_rosbag/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ if(CATKIN_ENABLE_TESTING)
add_rostest(${PROJECT_BINARY_DIR}/test/latched_sub.test)
add_rostest(test/record_two_publishers.test)
add_rostest(test/record_one_publisher_two_topics.test)
add_rostest(test/record_sigint_cleanup.test)
add_rostest(test/record_sigterm_cleanup.test)

include_directories(${GTEST_INCLUDE_DIRS})
add_executable(double_pub EXCLUDE_FROM_ALL test/double_pub.cpp)
Expand Down
5 changes: 4 additions & 1 deletion test/test_rosbag/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,16 @@
<description>
A package containing the unit tests for rosbag.
</description>
<maintainer email="dthomas@osrfoundation.org">Dirk Thomas</maintainer>
<maintainer email="jacob@openrobotics.org">Jacob Perron</maintainer>
<maintainer email="michael@openrobotics.org">Michael Carroll</maintainer>
<maintainer email="sloretz@openrobotics.org">Shane Loretz</maintainer>
<license>BSD</license>

<url>http://ros.org/wiki/rosbag</url>
<author>Tim Field</author>
<author>Jeremy Leibs</author>
<author>James Bowman</author>
<author email="dthomas@osrfoundation.org">Dirk Thomas</author>

<buildtool_depend version_gte="0.5.68">catkin</buildto 10000 ol_depend>

Expand Down
60 changes: 60 additions & 0 deletions test/test_rosbag/test/record_sigint_cleanup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2020 Amazon.com, Inc. or its affiliates.
# 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 roslib
roslib.load_manifest('rosbag')

import os
import unittest
import rostest
import sys
import signal
from record_signal_cleanup_helper import test_signal_cleanup

TEST_BAG_FILE_NAME = '/tmp/record_sigint_cleanup_test.bag'

class RecordSigintCleanup(unittest.TestCase):

def test_sigint_cleanup(self):
"""
Test that rosbag cleans up after handling SIGINT
"""
test_signal_cleanup(TEST_BAG_FILE_NAME, signal.SIGINT)

# check that the recorded file is no longer active
self.assertTrue(os.path.isfile(TEST_BAG_FILE_NAME))
self.assertFalse(os.path.isfile(TEST_BAG_FILE_NAME+ '.active'))


if __name__ == '__main__':
rostest.unitrun('test_rosbag', 'test_sigint_cleanup', RecordSigintCleanup, sys.argv)
5 changes: 5 additions & 0 deletions test/test_rosbag/test/record_sigint_cleanup.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<launch>
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
args="pub -r 10 chatter std_msgs/String chatter1"/>
<test test-name="test_sigint_cleanup" pkg="test_rosbag" type="record_sigint_cleanup.py"/>
</launch>
58 changes: 58 additions & 0 deletions test/test_rosbag/test/record_signal_cleanup_helper.py
< 10000 /div>
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2020 Amazon.com, Inc. or its affiliates.
# 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 time
import subprocess

RECORD_COMMAND = ['rosbag',
'record',
'chatter',
'-O',
'--duration=5']
SLEEP_TIME_SEC = 10

def test_signal_cleanup(test_bag_file_name, test_signal):
"""
Run rosbag record and send a signal to it after some time.

:param test_bag_file_name: bag name for recorded output
:param test_signal: signal to send to rosbag
"""
test_command = list(RECORD_COMMAND)
test_command.insert(4, test_bag_file_name)

p = subprocess.Popen(test_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE)
# wait while the recorder creates a bag for us to examine
time.sleep(SLEEP_TIME_SEC)
p.send_signal(test_signal)
p.wait()
60 changes: 60 additions & 0 deletions test/test_rosbag/test/record_sigterm_cleanup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
#!/usr/bin/env python
# Software License Agreement (BSD License)
#
# Copyright (c) 2020 Amazon.com, Inc. or its affiliates.
# 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 roslib
roslib.load_manifest('rosbag')

import os
import unittest
import rostest
import sys
import signal
from record_signal_cleanup_helper import test_signal_cleanup

TEST_BAG_FILE_NAME = '/tmp/record_sigterm_cleanup_test.bag'

class RecordSigtermCleanup(unittest.TestCase):

def test_sigterm_cleanup(self):
"""
Test that rosbag cleans up after handling SIGTERM
"""
test_signal_cleanup(TEST_BAG_FILE_NAME, signal.SIGTERM)

# check that the recorded file is no longer active
self.assertTrue(os.path.isfile(TEST_BAG_FILE_NAME))
self.assertFalse(os.path.isfile(TEST_BAG_FILE_NAME+ '.active'))


if __name__ == '__main__':
rostest.unitrun('test_rosbag', 'test_sigterm_cleanup', RecordSigtermCleanup, sys.argv)
5 changes: 5 additions & 0 deletions test/test_rosbag/test/record_sigterm_cleanup.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
<launch>
<node pkg="rostopic" type="rostopic" name="rostopic_pub1"
args="pub -r 10 chatter std_msgs/String chatter1"/>
<test test-name="test_sigterm_cleanup" pkg="test_rosbag" type="record_sigterm_cleanup.py"/>
</launch>
Loading
0