Skip to content

Commit

Permalink
Merge pull request #2081 from ros/jacob/backports_melodic
Browse files Browse the repository at this point in the history
Changes between 1.15.8 and 1.15.9 for backporting to Melodic
  • Loading branch information
jacobperron authored Oct 16, 2020
2 parents 121bac9 + 9e0a483 commit 8e66056
Show file tree
Hide file tree
Showing 100 changed files with 668 additions and 120 deletions.
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
2 changes: 1 addition & 1 deletion clients/roscpp/include/ros/statistics.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ class ROSCPP_DECL StatisticsLogger
std::list<ros::Duration> age_list;
// number of dropped messages
uint64_t dropped_msgs;
// latest sequence number observered (if available)
// latest sequence number observed (if available)
uint64_t last_seq;
// latest total traffic volume observed
uint64_t stat_bytes_last;
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 @@ -797,6 +801,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 @@ -137,7 +137,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 @@ -23,14 +23,17 @@
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 type="website">http://wiki.ros.org/rospy</url>
<url type="bugtracker">https://github.com/ros/ros_comm/issues</url>
<url type="repository">https://github.com/ros/ros_comm</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
8 changes: 6 additions & 2 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@
import warnings
def deprecated(func):
"""This is a decorator which can be used to mark functions
as deprecated. It will result in a warning being emmitted
as deprecated. It will result in a warning being emitted
when the function is used."""
def newFunc(*args, **kwargs):
warnings.warn("Call to deprecated function %s." % func.__name__,
Expand Down Expand Up @@ -223,6 +223,10 @@ def __call__(self, caller_id, period):
(now - last_logging_time) > rospy.Duration(period)):
self.last_logging_time_table[caller_id] = now
return True
elif last_logging_time > now:
self.last_logging_time_table = {}
self.last_logging_time_table[caller_id] = now
return True
return False


Expand Down Expand Up @@ -325,7 +329,7 @@ def logfatal_once(msg, *args, **kwargs):
import functools
def deprecated(func):
"""This is a decorator which can be used to mark functions
as deprecated. It will result in a warning being emmitted
as deprecated. It will result in a warning being emitted
when the function is used."""
@functools.wraps(func)
def newFunc(*args, **kwargs):
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/impl/masterslave.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ def validated_f(*args, **kwds):
_logger.debug("%s%s", f.__name__, str(args[1:]))
#print "%s%s"%(f.func_name, str(args[1:]))
if len(args) == 1:
_logger.error("%s invoked without caller_id paramter"%f.__name__)
_logger.error("%s invoked without caller_id parameter"%f.__name__)
return -1, "missing required caller_id parameter", error_return_value
elif len(args) != f.__code__.co_argcount:
return -1, "Error: bad call arity", error_return_value
Expand Down
4 changes: 2 additions & 2 deletions clients/rospy/src/rospy/impl/paramserver.py
Original file line number Diff line number Diff line change
Expand Up @@ -96,11 +96,11 @@ def update(self, key, value):
# partially borrowed from rosmaster/paramserver.py
namespaces = [x for x in key.split(SEP) if x]
# - last namespace is the actual key we're storing in
value_key = namespaces[-1]
namespaces = namespaces[:-1]
d = self.d
if d is None:
raise KeyError(key)
value_key = namespaces[-1]
namespaces = namespaces[:-1]
# - descend tree to the node we're setting
for ns in namespaces:
if ns not in d:
Expand Down
4 changes: 2 additions & 2 deletions clients/rospy/src/rospy/impl/tcpros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ class TCPROSServer(object):

def __init__(self, port=0):
"""
Constructur
Constructor
@param port: port number to bind to (default 0/any)
@type port: int
"""
Expand Down Expand Up @@ -314,7 +314,7 @@ def _tcp_server_callback(self, sock, client_addr):
@type sock: socket.socket
@param client_addr: client address
@type client_addr: (str, int)
@raise TransportInitError: If transport cannot be succesfully initialized
@raise TransportInitError: If transport cannot be successfully initialized
"""
#TODOXXX:rewrite this logic so it is possible to create TCPROSTransport object first, set its protocol,
#and then use that to do the writing
Expand Down
4 changes: 2 additions & 2 deletions clients/rospy/src/rospy/impl/tcpros_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,7 @@ def _read_ok_byte(self, b, sock):

def read_messages(self, b, msg_queue, sock):
"""
In service implementation, reads in OK byte that preceeds each
In service implementation, reads in OK byte that precedes each
response. The OK byte allows for the passing of error messages
instead of a response message
@param b: buffer
Expand Down Expand Up @@ -403,7 +403,7 @@ def __init__(self, name, service_class, persistent=False, headers=None):
@param persistent: (optional) if True, proxy maintains a persistent
connection to service. While this results in better call
performance, persistent connections are discouraged as they are
less resistent to network issues and service restarts.
less resistant to network issues and service restarts.
@type persistent: bool
@param headers: (optional) arbitrary headers
@type headers: dict
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 @@ -131,7 +131,13 @@ def __setitem__(self, key, val):
@param val: parameter value
@type val: XMLRPC legal value
"""
self.target.setParam(rospy.names.get_caller_id(), rospy.names.resolve_name(key), val)
resolved_key = rospy.names.resolve_name(key)

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
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/rostime.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
import genpy

## /time support. This hooks into the rospy Time representation and
## allows it to be overriden with data from the /time topic.
## allows it to be overridden with data from the /time topic.

_rostime_initialized = False
_rostime_current = None
Expand Down
6 changes: 3 additions & 3 deletions clients/rospy/src/rospy/topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -420,7 +420,7 @@ def add_connection(self, c):
# implementation) would be to start a thread that
# regularly polls all fds, but that would create a lot of
# synchronization events and also have a separate thread
# to manage. It would be desireable to move to this, but
# to manage. It would be desirable to move to this, but
# this change is less impactful and keeps the codebase
# more stable as we move towards an entirely different
# event loop for rospy -- the heart of the problem is that
Expand Down Expand Up @@ -599,7 +599,7 @@ def unregister(self):

class _SubscriberImpl(_TopicImpl):
"""
Underyling L{_TopicImpl} implementation for subscriptions.
Underlying L{_TopicImpl} implementation for subscriptions.
"""
def __init__(self, name, data_class):
"""
Expand Down Expand Up @@ -889,7 +889,7 @@ def publish(self, *args, **kwds):

class _PublisherImpl(_TopicImpl):
"""
Underyling L{_TopicImpl} implementation for publishers.
Underlying L{_TopicImpl} implementation for publishers.
"""

def __init__(self, name, data_class):
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/test_nodes/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def listener():
# node are launched, the previous one is kicked off. The
# anonymous=True flag means that rospy will choose a unique
# name for our 'talker' node so that multiple talkers can
# run simultaenously.
# run simultaneously.
rospy.init_node('listener', anonymous=True)

rospy.Subscriber("chatter", String, callback)
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://wiki.ros.org/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
2 changes: 1 addition & 1 deletion test/test_rosbag/bag_migration_tests/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ $ source devel_isolated/test_rosbag/setup.bash

## Generate Data

The **generate_data** script generates *.bag* data files for one or multiple messsage generations. The output directory is the **bag_migration_tests/test** folder inside the **test_rosbag** package. It's the user responsability to move the output *.bag* files to an HTTP server and download them from the **CMakeLists.txt** file as in this example:
The **generate_data** script generates *.bag* data files for one or multiple messsage generations. The output directory is the **bag_migration_tests/test** folder inside the **test_rosbag** package. It's the user responsibility to move the output *.bag* files to an HTTP server and download them from the **CMakeLists.txt** file as in this example:

``` cmake
catkin_download_test_data(download_data_test_constants_gen1.bag http://download.ros.org/data/test_rosbag/constants_gen1.bag FILENAME test/constants_gen1.bag MD5 77ec8cb20e823ee3f3a87d07ea1132df )
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 @@ -8,7 +8,9 @@
<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 type="website">http://wiki.ros.org/rosbag</url>
Expand All @@ -17,6 +19,7 @@
<author>Tim Field</author>
<author>Jeremy Leibs</author>
<author>James Bowman</author>
<author email="dthomas@osrfoundation.org">Dirk Thomas</author>

<depend>rosbag</depend>
<depend>rostest</depend>
Expand Down
Loading

0 comments on commit 8e66056

Please sign in to comment.