diff --git a/clients/roscpp/include/ros/node_handle.h b/clients/roscpp/include/ros/node_handle.h index fcb6c783ab..d084e5e071 100644 --- a/clients/roscpp/include/ros/node_handle.h +++ b/clients/roscpp/include/ros/node_handle.h @@ -2150,7 +2150,7 @@ if (service) // Enter if advertised service is valid * or is an otherwise invalid graph resource name. */ template - T param(const std::string& param_name, const T& default_val) + T param(const std::string& param_name, const T& default_val) const { T param_val; param(param_name, param_val, default_val); diff --git a/clients/roscpp/include/ros/timer.h b/clients/roscpp/include/ros/timer.h index 2d5663e443..339313cf60 100644 --- a/clients/roscpp/include/ros/timer.h +++ b/clients/roscpp/include/ros/timer.h @@ -71,8 +71,9 @@ class ROSCPP_DECL Timer */ void setPeriod(const Duration& period, bool reset=true); - bool hasStarted() const { return impl_->hasStarted(); } + bool hasStarted() const { return impl_ && impl_->hasStarted(); } bool isValid() { return impl_ && impl_->isValid(); } + bool isValid() const { return impl_ && impl_->isValid(); } operator void*() { return isValid() ? (void*)1 : (void*)0; } bool operator<(const Timer& rhs) @@ -101,6 +102,7 @@ class ROSCPP_DECL Timer bool hasStarted() const; bool isValid(); + bool isValid() const; bool hasPending(); void setPeriod(const Duration& period, bool reset=true); diff --git a/clients/roscpp/src/libros/connection.cpp b/clients/roscpp/src/libros/connection.cpp index cb92aa7a25..fb97ecd21f 100644 --- a/clients/roscpp/src/libros/connection.cpp +++ b/clients/roscpp/src/libros/connection.cpp @@ -337,8 +337,8 @@ void Connection::drop(DropReason reason) if (did_drop) { - drop_signal_(shared_from_this(), reason); transport_->close(); + drop_signal_(shared_from_this(), reason); } } diff --git a/clients/roscpp/src/libros/init.cpp b/clients/roscpp/src/libros/init.cpp index fa3a0430d8..d06eeaa07a 100644 --- a/clients/roscpp/src/libros/init.cpp +++ b/clients/roscpp/src/libros/init.cpp @@ -592,7 +592,8 @@ void shutdown() { g_internal_queue_thread.join(); } - + //ros::console::deregister_appender(g_rosout_appender); + delete g_rosout_appender; g_rosout_appender = 0; if (g_started) diff --git a/clients/roscpp/src/libros/node_handle.cpp b/clients/roscpp/src/libros/node_handle.cpp index 67caeee7fe..82d094c9db 100644 --- a/clients/roscpp/src/libros/node_handle.cpp +++ b/clients/roscpp/src/libros/node_handle.cpp @@ -68,6 +68,10 @@ class NodeHandleBackingCollection V_SrvCImpl srv_cs_; boost::mutex mutex_; + + // keep shared_ptrs to these managers to avoid assertions. Fixes #838 + TopicManagerPtr keep_alive_topic_manager = TopicManager::instance(); + ServiceManagerPtr keep_alive_service_manager = ServiceManager::instance(); }; NodeHandle::NodeHandle(const std::string& ns, const M_string& remappings) diff --git a/clients/roscpp/src/libros/poll_set.cpp b/clients/roscpp/src/libros/poll_set.cpp index 50580ee806..065a607b40 100644 --- a/clients/roscpp/src/libros/poll_set.cpp +++ b/clients/roscpp/src/libros/poll_set.cpp @@ -191,7 +191,10 @@ void PollSet::update(int poll_timeout) boost::shared_ptr > ofds = poll_sockets(epfd_, &ufds_.front(), ufds_.size(), poll_timeout); if (!ofds) { - ROS_ERROR_STREAM("poll failed with error " << last_socket_error_string()); + if (last_socket_error() != EINTR) + { + ROS_ERROR_STREAM("poll failed with error " << last_socket_error_string()); + } } else { diff --git a/clients/roscpp/src/libros/publication.cpp b/clients/roscpp/src/libros/publication.cpp index c51edf3d0c..0b30da9bc8 100644 --- a/clients/roscpp/src/libros/publication.cpp +++ b/clients/roscpp/src/libros/publication.cpp @@ -324,6 +324,8 @@ void Publication::dropAllConnections() void Publication::peerConnect(const SubscriberLinkPtr& sub_link) { + boost::mutex::scoped_lock lock(callbacks_mutex_); + V_Callback::iterator it = callbacks_.begin(); V_Callback::iterator end = callbacks_.end(); for (; it != end; ++it) @@ -339,6 +341,8 @@ void Publication::peerConnect(const SubscriberLinkPtr& sub_link) void Publication::peerDisconnect(const SubscriberLinkPtr& sub_link) { + boost::mutex::scoped_lock lock(callbacks_mutex_); + V_Callback::iterator it = callbacks_.begin(); V_Callback::iterator end = callbacks_.end(); for (; it != end; ++it) diff --git a/clients/roscpp/src/libros/service.cpp b/clients/roscpp/src/libros/service.cpp index c1efc4e510..495e49235d 100644 --- a/clients/roscpp/src/libros/service.cpp +++ b/clients/roscpp/src/libros/service.cpp @@ -88,7 +88,8 @@ bool service::waitForService(const std::string& service_name, ros::Duration time { std::string mapped_name = names::resolve(service_name); - Time start_time = Time::now(); + const WallTime start_time = WallTime::now(); + const WallDuration wall_timeout{timeout.toSec()}; bool printed = false; bool result = false; @@ -103,17 +104,17 @@ bool service::waitForService(const std::string& service_name, ros::Duration time { printed = true; - if (timeout >= Duration(0)) + if (wall_timeout >= WallDuration(0)) { - Time current_time = Time::now(); + const WallTime current_time = WallTime::now(); - if ((current_time - start_time) >= timeout) + if ((current_time - start_time) >= wall_timeout) { return false; } } - Duration(0.02).sleep(); + WallDuration(0.02).sleep(); } } diff --git a/clients/roscpp/src/libros/service_manager.cpp b/clients/roscpp/src/libros/service_manager.cpp index 1f1e94a005..4b0c1edd9e 100644 --- a/clients/roscpp/src/libros/service_manager.cpp +++ b/clients/roscpp/src/libros/service_manager.cpp @@ -200,9 +200,7 @@ bool ServiceManager::unregisterService(const std::string& service) network::getHost().c_str(), connection_manager_->getTCPPort()); args[2] = string(uri_buf); - master::execute("unregisterService", args, result, payload, false); - - return true; + return master::execute("unregisterService", args, result, payload, false); } bool ServiceManager::isServiceAdvertised(const string& serv_name) diff --git a/clients/roscpp/src/libros/statistics.cpp b/clients/roscpp/src/libros/statistics.cpp index a618936fa8..f5bb7e961c 100644 --- a/clients/roscpp/src/libros/statistics.cpp +++ b/clients/roscpp/src/libros/statistics.cpp @@ -113,7 +113,7 @@ void StatisticsLogger::callback(const boost::shared_ptr& connection_he } // should publish new statistics? - if (stats.last_publish + ros::Duration(pub_frequency_) < received_time) + if (stats.last_publish + ros::Duration(1 / pub_frequency_) < received_time) { ros::Time window_start = stats.last_publish; stats.last_publish = received_time; @@ -132,13 +132,13 @@ void StatisticsLogger::callback(const boost::shared_ptr& connection_he // not all message types have this if (stats.age_list.size() > 0) { - msg.stamp_age_mean = ros::Duration(0); + double stamp_age_sum = 0.0; msg.stamp_age_max = ros::Duration(0); for(std::list::iterator it = stats.age_list.begin(); it != stats.age_list.end(); it++) { ros::Duration age = *it; - msg.stamp_age_mean += age; + stamp_age_sum += age.toSec(); if (age > msg.stamp_age_max) { @@ -146,7 +146,7 @@ void StatisticsLogger::callback(const boost::shared_ptr& connection_he } } - msg.stamp_age_mean *= 1.0 / stats.age_list.size(); + msg.stamp_age_mean = ros::Duration(stamp_age_sum / stats.age_list.size()); double stamp_age_variance = 0.0; for(std::list::iterator it = stats.age_list.begin(); it != stats.age_list.end(); it++) diff --git a/clients/roscpp/src/libros/timer.cpp b/clients/roscpp/src/libros/timer.cpp index a063bc480c..13ff569654 100644 --- a/clients/roscpp/src/libros/timer.cpp +++ b/clients/roscpp/src/libros/timer.cpp @@ -52,6 +52,11 @@ bool Timer::Impl::isValid() return !period_.isZero(); } +bool Timer::Impl::isValid() const +{ + return !period_.isZero(); +} + void Timer::Impl::start() { if (!started_) diff --git a/clients/roscpp/src/libros/topic_manager.cpp b/clients/roscpp/src/libros/topic_manager.cpp index 363fb05e10..1c106f65be 100644 --- a/clients/roscpp/src/libros/topic_manager.cpp +++ b/clients/roscpp/src/libros/topic_manager.cpp @@ -97,9 +97,10 @@ void TopicManager::shutdown() } { - boost::recursive_mutex::scoped_lock lock1(advertised_topics_mutex_); - boost::mutex::scoped_lock lock2(subs_mutex_); + boost::lock(subs_mutex_, advertised_topics_mutex_); shutting_down_ = true; + subs_mutex_.unlock(); + advertised_topics_mutex_.unlock(); } // actually one should call poll_manager_->removePollThreadListener(), but the connection is not stored above diff --git a/clients/roscpp/src/libros/transport/transport_tcp.cpp b/clients/roscpp/src/libros/transport/transport_tcp.cpp index e3e152813b..cfdc406eeb 100644 --- a/clients/roscpp/src/libros/transport/transport_tcp.cpp +++ b/clients/roscpp/src/libros/transport/transport_tcp.cpp @@ -138,6 +138,10 @@ bool TransportTCP::initializeSocket() { ROS_DEBUG("Adding tcp socket [%d] to pollset", sock_); poll_set_->addSocket(sock_, boost::bind(&TransportTCP::socketUpdate, this, _1), shared_from_this()); +#if defined(POLLRDHUP) // POLLRDHUP is not part of POSIX! + // This is needed to detect dead connections. #1704 + poll_set_->addEvents(sock_, POLLRDHUP); +#endif } if (!(flags_ & SYNCHRONOUS)) @@ -270,7 +274,7 @@ bool TransportTCP::connect(const std::string& host, int port) bool found = false; struct addrinfo* it = addr; - char namebuf[128]; + char namebuf[128] = {}; for (; it; it = it->ai_next) { if (!s_use_ipv6_ && it->ai_family == AF_INET) @@ -282,7 +286,7 @@ bool TransportTCP::connect(const std::string& host, int port) address->sin_family = it->ai_family; address->sin_port = htons(port); - strcpy(namebuf, inet_ntoa(address->sin_addr)); + strncpy(namebuf, inet_ntoa(address->sin_addr), sizeof(namebuf)-1); found = true; break; } @@ -383,7 +387,7 @@ bool TransportTCP::listen(int port, int backlog, const AcceptCallback& accept_cb sa_len_ = sizeof(sockaddr_in); } - if (sock_ <= 0) + if (sock_ == ROS_INVALID_SOCKET) { ROS_ERROR("socket() failed with error [%s]", last_socket_error_string()); return false; @@ -690,6 +694,9 @@ void TransportTCP::socketUpdate(int events) if((events & POLLERR) || (events & POLLHUP) || +#if defined(POLLRDHUP) // POLLRDHUP is not part of POSIX! + (events & POLLRDHUP) || +#endif (events & POLLNVAL)) { uint32_t error = -1; @@ -728,14 +735,14 @@ std::string TransportTCP::getClientURI() sockaddr_in *sin = (sockaddr_in *)&sas; sockaddr_in6 *sin6 = (sockaddr_in6 *)&sas; - char namebuf[128]; + char namebuf[128] = {}; int port; switch (sas.ss_family) { case AF_INET: port = ntohs(sin->sin_port); - strcpy(namebuf, inet_ntoa(sin->sin_addr)); + strncpy(namebuf, inet_ntoa(sin->sin_addr), sizeof(namebuf)-1); break; case AF_INET6: port = ntohs(sin6->sin6_port); diff --git a/clients/roscpp/src/libros/transport/transport_udp.cpp b/clients/roscpp/src/libros/transport/transport_udp.cpp index 47d969eea4..ec497d7c8d 100644 --- a/clients/roscpp/src/libros/transport/transport_udp.cpp +++ b/clients/roscpp/src/libros/transport/transport_udp.cpp @@ -240,7 +240,7 @@ bool TransportUDP::createIncoming(int port, bool is_server) sock_ = socket(AF_INET, SOCK_DGRAM, 0); - if (sock_ <= 0) + if (sock_ == ROS_INVALID_SOCKET) { ROS_ERROR("socket() failed with error [%s]", last_socket_error_string()); return false; @@ -710,9 +710,9 @@ std::string TransportUDP::getClientURI() sockaddr_in *sin = (sockaddr_in *)&sas; - char namebuf[128]; + char namebuf[128] = {}; int port = ntohs(sin->sin_port); - strcpy(namebuf, inet_ntoa(sin->sin_addr)); + strncpy(namebuf, inet_ntoa(sin->sin_addr), sizeof(namebuf)-1); std::string ip = namebuf; std::stringstream uri; diff --git a/clients/roscpp/src/libros/transport_subscriber_link.cpp b/clients/roscpp/src/libros/transport_subscriber_link.cpp index 898b9ec262..8e57adaa87 100644 --- a/clients/roscpp/src/libros/transport_subscriber_link.cpp +++ b/clients/roscpp/src/libros/transport_subscriber_link.cpp @@ -198,7 +198,7 @@ void TransportSubscriberLink::enqueueMessage(const SerializedMessage& m, bool se if (!queue_full_) { ROS_DEBUG("Outgoing queue full for topic [%s]. " - "Discarding oldest message\n", + "Discarding oldest message", topic_.c_str()); } diff --git a/clients/rospy/src/rospy/__init__.py b/clients/rospy/src/rospy/__init__.py index 337e8f780d..30f3e8fd18 100644 --- a/clients/rospy/src/rospy/__init__.py +++ b/clients/rospy/src/rospy/__init__.py @@ -94,7 +94,7 @@ 'INFO', 'WARN', 'ERROR', - 'FATAL' + 'FATAL', 'is_shutdown', 'signal_shutdown', 'get_node_uri', @@ -107,7 +107,6 @@ 'logerr_throttle', 'logfatal_throttle', 'parse_rosrpc_uri', 'MasterProxy', - 'NodeProxy', 'ROSException', 'ROSSerializationException', 'ROSInitException', diff --git a/clients/rospy/src/rospy/impl/tcpros_base.py b/clients/rospy/src/rospy/impl/tcpros_base.py index 7cb08686f1..34c4f8992a 100644 --- a/clients/rospy/src/rospy/impl/tcpros_base.py +++ b/clients/rospy/src/rospy/impl/tcpros_base.py @@ -157,7 +157,8 @@ def run(self): (errno, msg) = e.args if errno == 4: #interrupted system call continue - raise + if not self.is_shutdown: + raise if self.is_shutdown: break try: diff --git a/clients/rospy/src/rospy/topics.py b/clients/rospy/src/rospy/topics.py index 4f2d8d76d7..124864cfac 100644 --- a/clients/rospy/src/rospy/topics.py +++ b/clients/rospy/src/rospy/topics.py @@ -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): @@ -1264,7 +1264,7 @@ def acquire_impl(self, reg_type, resolved_name, data_class): rmap = self.subs impl_class = _SubscriberImpl else: - raise TypeError("invalid reg_type: %s"%s) + raise TypeError("invalid reg_type: %s"%reg_type) with self.lock: impl = rmap.get(resolved_name, None) if not impl: diff --git a/test/test_roscpp/test/src/params.cpp b/test/test_roscpp/test/src/params.cpp index a54888bd3b..c5ce066eaa 100644 --- a/test/test_roscpp/test/src/params.cpp +++ b/test/test_roscpp/test/src/params.cpp @@ -566,12 +566,23 @@ TEST(Params, getParamNames) { EXPECT_LT(10, test_params.size()); } +TEST(Params, getParamCachedSetParamLoop) { + NodeHandle nh; + const std::string name = "changeable_int"; + for (int i = 0; i < 100; i++) { + nh.setParam(name, i); + int v = 0; + ASSERT_TRUE(nh.getParamCached(name, v)); + ASSERT_EQ(i, v); + } +} + int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); - ros::init( argc, argv, "params" ); -// ros::NodeHandle nh; + ros::init(argc, argv, "params"); + ros::NodeHandle nh; return RUN_ALL_TESTS(); } diff --git a/test/test_rospy/test/rostest/sub_to_multiple_pubs.test b/test/test_rospy/test/rostest/sub_to_multiple_pubs.test index 3fe8362577..7c579d677e 100644 --- a/test/test_rospy/test/rostest/sub_to_multiple_pubs.test +++ b/test/test_rospy/test/rostest/sub_to_multiple_pubs.test @@ -1,4 +1,5 @@ + @@ -98,6 +99,5 @@ - diff --git a/tools/rosbag/scripts/fix_msg_defs.py b/tools/rosbag/scripts/fix_msg_defs.py index 1ba056c323..0f5b2256a8 100755 --- a/tools/rosbag/scripts/fix_msg_defs.py +++ b/tools/rosbag/scripts/fix_msg_defs.py @@ -35,6 +35,7 @@ import sys import rosbag.migration +import roslib.message if __name__ == '__main__': if len(sys.argv) != 3: diff --git a/tools/rosbag/src/player.cpp b/tools/rosbag/src/player.cpp index 76d6a81830..be7c143f5c 100644 --- a/tools/rosbag/src/player.cpp +++ b/tools/rosbag/src/player.cpp @@ -405,7 +405,7 @@ void Player::waitForSubscribers() const foreach(const PublisherMap::value_type& pub, publishers_) { all_topics_subscribed &= pub.second.getNumSubscribers() > 0; } - ros::Duration(0.1).sleep(); + ros::WallDuration(0.1).sleep(); } std::cout << "Finished waiting for subscribers." << std::endl; } diff --git a/tools/rosbag/src/record.cpp b/tools/rosbag/src/record.cpp index f6cbb2067f..d8739bc19a 100644 --- a/tools/rosbag/src/record.cpp +++ b/tools/rosbag/src/record.cpp @@ -123,7 +123,7 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) { ROS_WARN("Use of \"--split \" has been deprecated. Please use --split --size or --split --duration "); if (S < 0) throw ros::Exception("Split size must be 0 or positive"); - opts.max_size = 1048576 * S; + opts.max_size = 1048576 * static_cast(S); } } if(vm.count("max-splits")) diff --git a/tools/rosbag/src/rosbag/bag.py b/tools/rosbag/src/rosbag/bag.py index 3130b43b73..989297dc60 100644 --- a/tools/rosbag/src/rosbag/bag.py +++ b/tools/rosbag/src/rosbag/bag.py @@ -733,8 +733,11 @@ def __str__(self): msg_count = 0 for connection in connections: - for chunk in self._chunks: - msg_count += chunk.connection_counts.get(connection.id, 0) + if self._chunks: + for chunk in self._chunks: + msg_count += chunk.connection_counts.get(connection.id, 0) + else: + msg_count += len(self._connection_indexes.get(connection.id, [])) topic_msg_counts[topic] = msg_count if self._connection_indexes_read: diff --git a/tools/rosbag/src/rosbag/migration.py b/tools/rosbag/src/rosbag/migration.py index 19ea6b1b2a..211454ed70 100644 --- a/tools/rosbag/src/rosbag/migration.py +++ b/tools/rosbag/src/rosbag/migration.py @@ -43,6 +43,7 @@ import os import string import sys +import traceback import genmsg.msgs import genpy @@ -257,6 +258,9 @@ class MessageUpdateRule(object): valid = False + class EmptyType(Exception): + pass + ## Initialize class def __init__(self, migrator, location): # Every rule needs to hang onto the migrator so we can potentially use it @@ -271,23 +275,26 @@ def __init__(self, migrator, location): # Instantiate types dynamically based on definition try: if self.old_type == "": - raise Exception + raise self.EmptyType self.old_types = genpy.dynamic.generate_dynamic(self.old_type, self.old_full_text) self.old_class = self.old_types[self.old_type] self.old_md5sum = self.old_class._md5sum - except: - self.old_types = [] + except Exception as e: + if not isinstance(e, self.EmptyType): + traceback.print_exc(file=sys.stderr) + self.old_types = {} self.old_class = None self.old_md5sum = "" - try: if self.new_type == "": - raise Exception + raise self.EmptyType self.new_types = genpy.dynamic.generate_dynamic(self.new_type, self.new_full_text) self.new_class = self.new_types[self.new_type] self.new_md5sum = self.new_class._md5sum - except: - self.new_types = [] + except Exception as e: + if not isinstance(e, self.EmptyType): + traceback.print_exc(file=sys.stderr) + self.new_types = {} self.new_class = None self.new_md5sum = "" @@ -830,7 +837,7 @@ def scaffold_range(self, old_type, new_type): if (tmp_sn != first_sn): sn_range.append(tmp_sn) if (tmp_sn.new_class._type == new_type): - found_new_type == True + found_new_type = True if (found_new_type and tmp_sn.new_class._type != new_type): break diff --git a/tools/rosbag_storage/include/rosbag/structures.h b/tools/rosbag_storage/include/rosbag/structures.h index ad75b1ee95..d78d1b9903 100644 --- a/tools/rosbag_storage/include/rosbag/structures.h +++ b/tools/rosbag_storage/include/rosbag/structures.h @@ -59,25 +59,25 @@ struct ROSBAG_DECL ConnectionInfo struct ChunkInfo { - ros::Time start_time; //! earliest timestamp of a message in the chunk - ros::Time end_time; //! latest timestamp of a message in the chunk - uint64_t pos; //! absolute byte offset of chunk record in bag file + ros::Time start_time; //!< earliest timestamp of a message in the chunk + ros::Time end_time; //!< latest timestamp of a message in the chunk + uint64_t pos; //!< absolute byte offset of chunk record in bag file - std::map connection_counts; //! number of messages in each connection stored in the chunk + std::map connection_counts; //!< number of messages in each connection stored in the chunk }; struct ROSBAG_DECL ChunkHeader { - std::string compression; //! chunk compression type, e.g. "none" or "bz2" (see constants.h) - uint32_t compressed_size; //! compressed size of the chunk in bytes - uint32_t uncompressed_size; //! uncompressed size of the chunk in bytes + std::string compression; //!< chunk compression type, e.g. "none" or "bz2" (see constants.h) + uint32_t compressed_size; //!< compressed size of the chunk in bytes + uint32_t uncompressed_size; //!< uncompressed size of the chunk in bytes }; struct ROSBAG_DECL IndexEntry { - ros::Time time; //! timestamp of the message - uint64_t chunk_pos; //! absolute byte offset of the chunk record containing the message - uint32_t offset; //! relative byte offset of the message record (either definition or data) in the chunk + ros::Time time; //!< timestamp of the message + uint64_t chunk_pos; //!< absolute byte offset of the chunk record containing the message + uint32_t offset; //!< relative byte offset of the message record (either definition or data) in the chunk bool operator<(IndexEntry const& b) const { return time < b.time; } }; diff --git a/tools/rosbag_storage/src/buffer.cpp b/tools/rosbag_storage/src/buffer.cpp index f51e624cad..cb19977ff1 100644 --- a/tools/rosbag_storage/src/buffer.cpp +++ b/tools/rosbag_storage/src/buffer.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include "rosbag/buffer.h" @@ -65,7 +66,12 @@ void Buffer::ensureCapacity(uint32_t capacity) { capacity_ = capacity; else { while (capacity_ < capacity) + { + if (static_cast(capacity) * 2 > std::numeric_limits::max()) + capacity_ = std::numeric_limits::max(); + else capacity_ *= 2; + } } buffer_ = (uint8_t*) realloc(buffer_, capacity_); diff --git a/tools/rosbag_storage/src/chunked_file.cpp b/tools/rosbag_storage/src/chunked_file.cpp index 9eb665826f..dd5e617c5f 100644 --- a/tools/rosbag_storage/src/chunked_file.cpp +++ b/tools/rosbag_storage/src/chunked_file.cpp @@ -100,7 +100,9 @@ void ChunkedFile::open(string const& filename, string const& mode) { file_ = fopen(filename.c_str(), "w+b"); #endif else { - fclose(file_); + if (fclose(file_) != 0) + throw BagIOException((format("Error closing file: %1%") % filename.c_str()).str()); + // open existing file for update #if defined(_MSC_VER) && (_MSC_VER >= 1400 ) fopen_s( &file_, filename.c_str(), "r+b" ); diff --git a/tools/roslaunch/resources/example.launch b/tools/roslaunch/resources/example.launch index 0c389bf0ca..0b257092ea 100644 --- a/tools/roslaunch/resources/example.launch +++ b/tools/roslaunch/resources/example.launch @@ -70,4 +70,10 @@ + + + + + + diff --git a/tools/roslaunch/src/roslaunch/__init__.py b/tools/roslaunch/src/roslaunch/__init__.py index 6f04d304eb..2c034408e1 100644 --- a/tools/roslaunch/src/roslaunch/__init__.py +++ b/tools/roslaunch/src/roslaunch/__init__.py @@ -205,8 +205,10 @@ def _validate_args(parser, options, args): elif len(args) == 0: parser.error("you must specify at least one input file") - elif [f for f in args if not (f == '-' or os.path.exists(f))]: - parser.error("The following input files do not exist: %s"%f) + else: + missing_files = [f for f in args if not (f == '-' or os.path.exists(f))] + if missing_files: + parser.error("The following input files do not exist: %s"%', '.join(missing_files)) if args.count('-') > 1: parser.error("Only a single instance of the dash ('-') may be specified.") diff --git a/tools/roslaunch/src/roslaunch/core.py b/tools/roslaunch/src/roslaunch/core.py index a6d43e371e..0999da460c 100644 --- a/tools/roslaunch/src/roslaunch/core.py +++ b/tools/roslaunch/src/roslaunch/core.py @@ -208,9 +208,9 @@ def setup_env(node, machine, master_uri, env=None): if ns[-1] == '/': ns = ns[:-1] if ns: - d[rosgraph.ROS_NAMESPACE] = ns + d[rosgraph.ROS_NAMESPACE] = str(ns) for name, value in node.env_args: - d[name] = value + d[str(name)] = str(value) return d @@ -346,7 +346,7 @@ def __init__(self, name, address, self.name = name self.env_loader = env_loader self.user = user or None - self.password = password or None + self.password = password self.address = address self.ssh_port = ssh_port self.assignable = assignable diff --git a/tools/roslaunch/src/roslaunch/depends.py b/tools/roslaunch/src/roslaunch/depends.py index 7e3583770f..a3fbf7a418 100644 --- a/tools/roslaunch/src/roslaunch/depends.py +++ b/tools/roslaunch/src/roslaunch/depends.py @@ -45,7 +45,7 @@ import rospkg -from .loader import convert_value +from .loader import convert_value, load_mappings from .substitution_args import resolve_args NAME="roslaunch-deps" @@ -118,6 +118,7 @@ def _parse_subcontext(tags, context): return subcontext def _parse_launch(tags, launch_file, file_deps, verbose, context): + context['filename'] = os.path.abspath(launch_file) dir_path = os.path.dirname(os.path.abspath(launch_file)) launch_file_pkg = rospkg.get_package_name(dir_path) @@ -205,7 +206,7 @@ def parse_launch(launch_file, file_deps, verbose): file_deps[launch_file] = RoslaunchDeps() launch_tag = dom[0] - context = { 'arg': {}} + context = { 'arg': load_mappings(sys.argv) } _parse_launch(launch_tag.childNodes, launch_file, file_deps, verbose, context) def rl_file_deps(file_deps, launch_file, verbose=False): diff --git a/tools/roslaunch/src/roslaunch/pmon.py b/tools/roslaunch/src/roslaunch/pmon.py index b20a90485b..d3e3bab070 100644 --- a/tools/roslaunch/src/roslaunch/pmon.py +++ b/tools/roslaunch/src/roslaunch/pmon.py @@ -586,7 +586,9 @@ def _run(self): break #stop polling for d in dead: try: - if d.should_respawn(): + # when should_respawn() returns 0.0, bool(0.0) evaluates to False + # work around this by checking if the return value is False + if d.should_respawn() is not False: respawn.append(d) else: self.unregister(d) diff --git a/tools/roslaunch/src/roslaunch/remoteprocess.py b/tools/roslaunch/src/roslaunch/remoteprocess.py index 1f6d65eb02..46ac950c37 100644 --- a/tools/roslaunch/src/roslaunch/remoteprocess.py +++ b/tools/roslaunch/src/roslaunch/remoteprocess.py @@ -186,7 +186,7 @@ def _ssh_exec(self, command, address, port, username=None, password=None): if not err_msg: username_str = '%s@'%username if username else '' try: - if not password: #use SSH agent + if password is None: #use SSH agent ssh.connect(address, port, username, timeout=TIMEOUT_SSH_CONNECT, key_filename=identity_file) else: #use SSH with login/pass ssh.connect(address, port, username, password, timeout=TIMEOUT_SSH_CONNECT) diff --git a/tools/roslaunch/src/roslaunch/xmlloader.py b/tools/roslaunch/src/roslaunch/xmlloader.py index ce50d441a4..40d627c656 100644 --- a/tools/roslaunch/src/roslaunch/xmlloader.py +++ b/tools/roslaunch/src/roslaunch/xmlloader.py @@ -626,8 +626,9 @@ def _include_tag(self, tag, context, ros_config, default_machine, is_core, verbo self._recurse_load(ros_config, launch.childNodes, child_ns, \ default_machine, is_core, verbose) - # check for unused args - loader.post_process_include_args(child_ns) + if not pass_all_args: + # check for unused args + loader.post_process_include_args(child_ns) except ArgException as e: raise XmlParseException("included file [%s] requires the '%s' arg to be set"%(inc_filename, str(e))) @@ -713,7 +714,7 @@ def _load_launch(self, launch, ros_config, is_core=False, filename=None, argv=No argv = sys.argv self._launch_tag(launch, ros_config, filename) - self.root_context = loader.LoaderContext(get_ros_namespace(), filename) + self.root_context = loader.LoaderContext(get_ros_namespace(argv=argv), filename) loader.load_sysargs_into_context(self.root_context, argv) if len(launch.getElementsByTagName('master')) > 0: diff --git a/tools/roslaunch/test/xml/test-arg-valid-include.xml b/tools/roslaunch/test/xml/test-arg-valid-include.xml index d3304239a5..a310183f77 100644 --- a/tools/roslaunch/test/xml/test-arg-valid-include.xml +++ b/tools/roslaunch/test/xml/test-arg-valid-include.xml @@ -1,4 +1,5 @@ + diff --git a/tools/rosmaster/src/rosmaster/master_api.py b/tools/rosmaster/src/rosmaster/master_api.py index fc993692db..c5312618e9 100644 --- a/tools/rosmaster/src/rosmaster/master_api.py +++ b/tools/rosmaster/src/rosmaster/master_api.py @@ -375,7 +375,7 @@ def setParam(self, caller_id, key, value): @rtype: [int, str, int] """ key = resolve_name(key, caller_id) - self.param_server.set_param(key, value, self._notify_param_subscribers) + self.param_server.set_param(key, value, self._notify_param_subscribers, caller_id) mloginfo("+PARAM [%s] by %s",key, caller_id) return 1, "parameter %s set"%key, 0 @@ -623,7 +623,7 @@ def registerService(self, caller_id, service, service_api, caller_api): self.ps_lock.release() return 1, "Registered [%s] as provider of [%s]"%(caller_id, service), 1 - @apivalidate(0, (is_service('service'),)) + @apivalidate('', (is_service('service'),)) def lookupService(self, caller_id, service): """ Lookup all provider of a particular service. @@ -672,7 +672,7 @@ def unregisterService(self, caller_id, service, service_api): ################################################################################## # PUBLISH/SUBSCRIBE - @apivalidate(0, ( is_topic('topic'), valid_type_name('topic_type'), is_api('caller_api'))) + @apivalidate([], ( is_topic('topic'), valid_type_name('topic_type'), is_api('caller_api'))) def registerSubscriber(self, caller_id, topic, topic_type, caller_api): """ Subscribe the caller to the specified topic. In addition to receiving @@ -708,7 +708,7 @@ def registerSubscriber(self, caller_id, topic, topic_type, caller_api): @apivalidate(0, (is_topic('topic'), is_api('caller_api'))) def unregisterSubscriber(self, caller_id, topic, caller_api): """ - Unregister the caller as a publisher of the topic. + Unregister the caller as a subscriber of the topic. @param caller_id: ROS caller id @type caller_id: str @param topic: Fully-qualified name of topic to unregister. @@ -729,7 +729,7 @@ def unregisterSubscriber(self, caller_id, topic, caller_api): finally: self.ps_lock.release() - @apivalidate(0, ( is_topic('topic'), valid_type_name('topic_type'), is_api('caller_api'))) + @apivalidate([], ( is_topic('topic'), valid_type_name('topic_type'), is_api('caller_api'))) def registerPublisher(self, caller_id, topic, topic_type, caller_api): """ Register the caller as a publisher the topic. diff --git a/tools/rosmaster/src/rosmaster/paramserver.py b/tools/rosmaster/src/rosmaster/paramserver.py index a686216c01..d29b4d302c 100644 --- a/tools/rosmaster/src/rosmaster/paramserver.py +++ b/tools/rosmaster/src/rosmaster/paramserver.py @@ -166,7 +166,7 @@ def get_param(self, key): finally: self.lock.release() - def set_param(self, key, value, notify_task=None): + def set_param(self, key, value, notify_task=None, caller_id=None): """ Set the parameter in the parameter dictionary. @@ -178,6 +178,8 @@ def set_param(self, key, value, notify_task=None): [(subscribers, param_key, param_value)*]. The empty dictionary represents an unset parameter. @type notify_task: fn(updates) + @param caller_id: the caller id + @type caller_id: str """ try: self.lock.acquire() @@ -208,7 +210,7 @@ def set_param(self, key, value, notify_task=None): # ParamDictionary needs to queue updates so that the updates are thread-safe if notify_task: - updates = compute_param_updates(self.reg_manager.param_subscribers, key, value) + updates = compute_param_updates(self.reg_manager.param_subscribers, key, value, caller_id) if updates: notify_task(updates) finally: @@ -332,7 +334,7 @@ def _compute_all_keys(param_key, param_value, all_keys=None): _compute_all_keys(new_k, v, all_keys) return all_keys -def compute_param_updates(subscribers, param_key, param_value): +def compute_param_updates(subscribers, param_key, param_value, caller_id_to_ignore=None): """ Compute subscribers that should be notified based on the parameter update @param subscribers: parameter subscribers @@ -341,6 +343,8 @@ def compute_param_updates(subscribers, param_key, param_value): @type param_key: str @param param_value: parameter value @type param_value: str + @param caller_id_to_ignore: the caller to ignore + @type caller_id_to_ignore: str """ # logic correct for both updates and deletions @@ -368,6 +372,11 @@ def compute_param_updates(subscribers, param_key, param_value): ns_key = sub_key + SEP if param_key.startswith(ns_key): node_apis = subscribers[sub_key] + if caller_id_to_ignore is not None: + node_apis = [ + (caller_id, caller_api) + for (caller_id, caller_api) in node_apis + if caller_id != caller_id_to_ignore] updates.append((node_apis, param_key, param_value)) elif all_keys is not None and ns_key.startswith(param_key) \ and not sub_key in all_keys: diff --git a/tools/rosmaster/src/rosmaster/util.py b/tools/rosmaster/src/rosmaster/util.py index ee3a4848a0..6f181ef6a8 100644 --- a/tools/rosmaster/src/rosmaster/util.py +++ b/tools/rosmaster/src/rosmaster/util.py @@ -51,8 +51,9 @@ import errno import socket +import threading -_proxies = {} #cache ServerProxys +_proxies = threading.local() #cache ServerProxys def xmlrpcapi(uri): """ @return: instance for calling remote server or None if not a valid URI @@ -63,16 +64,16 @@ def xmlrpcapi(uri): uriValidate = urlparse(uri) if not uriValidate[0] or not uriValidate[1]: return None - if not uri in _proxies: - _proxies[uri] = ServerProxy(uri) + if not uri in _proxies.__dict__: + _proxies.__dict__[uri] = ServerProxy(uri) close_half_closed_sockets() - return _proxies[uri] + return _proxies.__dict__[uri] def close_half_closed_sockets(): if not hasattr(socket, 'TCP_INFO'): return - for proxy in _proxies.values(): + for proxy in _proxies.__dict__.values(): transport = proxy("transport") if transport._connection and transport._connection[1] is not None and transport._connection[1].sock is not None: try: @@ -86,5 +87,5 @@ def close_half_closed_sockets(): def remove_server_proxy(uri): - if uri in _proxies: - del _proxies[uri] + if uri in _proxies.__dict__: + del _proxies.__dict__[uri] diff --git a/tools/rosnode/src/rosnode/__init__.py b/tools/rosnode/src/rosnode/__init__.py index 4c8322902f..dc42b25a03 100644 --- a/tools/rosnode/src/rosnode/__init__.py +++ b/tools/rosnode/src/rosnode/__init__.py @@ -333,6 +333,9 @@ def rosnode_ping(node_name, max_count=None, verbose=False): if verbose: print("xmlrpc reply from %s\ttime=%fms"%(node_api, dur)) # 1s between pings + except socket.timeout: + print("connection to [%s] timed out"%node_name, file=sys.stderr) + return False except socket.error as e: # 3786: catch ValueError on unpack as socket.error is not always a tuple try: @@ -355,7 +358,7 @@ def rosnode_ping(node_name, max_count=None, verbose=False): continue print("ERROR: connection refused to [%s]"%(node_api), file=sys.stderr) else: - print("connection to [%s] timed out"%node_name, file=sys.stderr) + print("connection to [%s] failed"%node_name, file=sys.stderr) return False except ValueError: print("unknown network error contacting node: %s"%(str(e))) diff --git a/tools/rosout/rosout.cpp b/tools/rosout/rosout.cpp index 95fb328afd..ea45ac06df 100644 --- a/tools/rosout/rosout.cpp +++ b/tools/rosout/rosout.cpp @@ -171,7 +171,7 @@ class Rosout current_file_size_ += written; if (fflush(handle_)) { - std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)); + std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno); } // check for rolling @@ -179,7 +179,7 @@ class Rosout { if (fclose(handle_)) { - std::cerr << "Error closing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl; + std::cerr << "Error closing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno) << std::endl; } current_backup_index_++; if (current_backup_index_ <= max_backup_index_) diff --git a/tools/rosservice/src/rosservice/__init__.py b/tools/rosservice/src/rosservice/__init__.py index 88fa01da2e..27e0c9d883 100644 --- a/tools/rosservice/src/rosservice/__init__.py +++ b/tools/rosservice/src/rosservice/__init__.py @@ -322,7 +322,10 @@ def rosservice_find(service_type): try: _, _, services = master.getSystemState() for s, l in services: - t = get_service_type(s) + try: + t = get_service_type(s) + except ROSServiceIOException: + continue if t == service_type: matches.append(s) except socket.error: diff --git a/tools/rostopic/src/rostopic/__init__.py b/tools/rostopic/src/rostopic/__init__.py index 4b11424f3e..e275a3e1a0 100644 --- a/tools/rostopic/src/rostopic/__init__.py +++ b/tools/rostopic/src/rostopic/__init__.py @@ -1172,11 +1172,11 @@ def build_map(master, state, uricache): if not puri.hostname in tmap: tmap[puri.hostname] = [] # recreate the system state data structure, but for a single host - matches = [l for x, l in tmap[puri.hostname] if x == topic] + matches = [l for x, _, l in tmap[puri.hostname] if x == topic] if matches: matches[0].append(p) else: - tmap[puri.hostname].append((topic, [p])) + tmap[puri.hostname].append((topic, ttype, [p])) return tmap uricache = {} diff --git a/tools/topic_tools/env-hooks/20.transform.bash b/tools/topic_tools/env-hooks/20.transform.bash index d861b17e2f..3b0d174861 100644 --- a/tools/topic_tools/env-hooks/20.transform.bash +++ b/tools/topic_tools/env-hooks/20.transform.bash @@ -20,7 +20,7 @@ function _roscomplete_node_transform fi } -_sav_transform_roscomplete_rosrun=$(complete | grep -w rosrun | awk '{print $3}') +_sav_transform_roscomplete_rosrun=$(complete | { grep -w rosrun || test $? = 1; } | awk '{print $3}') function is_transform_node { diff --git a/tools/topic_tools/scripts/transform b/tools/topic_tools/scripts/transform index 326f28835e..3a1347efe4 100755 --- a/tools/topic_tools/scripts/transform +++ b/tools/topic_tools/scripts/transform @@ -83,8 +83,8 @@ class TopicOp: self.output_class = roslib.message.get_message_class(args.output_type) - self.sub = rospy.Subscriber(input_topic, input_class, self.callback) self.pub = rospy.Publisher(args.output_topic, self.output_class, queue_size=1) + self.sub = rospy.Subscriber(input_topic, input_class, self.callback) def callback(self, m): if self.input_fn is not None: diff --git a/tools/topic_tools/src/mux.cpp b/tools/topic_tools/src/mux.cpp index f6b0b43939..e13205d9dc 100644 --- a/tools/topic_tools/src/mux.cpp +++ b/tools/topic_tools/src/mux.cpp @@ -167,7 +167,7 @@ void in_cb(const boost::shared_ptr& msg, } } - if (s != g_selected->msg) + if (g_selected == g_subs.end() || s != g_selected->msg) return; // If we're in lazy subscribe mode, and nobody's listening, then unsubscribe diff --git a/utilities/roslz4/src/lz4s.c b/utilities/roslz4/src/lz4s.c index 8db1dfc9e1..2ae7b77667 100644 --- a/utilities/roslz4/src/lz4s.c +++ b/utilities/roslz4/src/lz4s.c @@ -247,6 +247,14 @@ int streamStateAlloc(roslz4_stream *str) { state->finished = 0; state->xxh32_state = XXH32_init(0); + if (state->xxh32_state == NULL) { + if (state->buffer != NULL) { + free(state->buffer); + } + free(state); + str->state = NULL; + return ROSLZ4_MEMORY_ERROR; // Allocation failed + } state->stream_checksum = 0; state->stream_checksum_read = 0; diff --git a/utilities/roslz4/src/xxhash.c b/utilities/roslz4/src/xxhash.c index 8304ec21c0..3edcfa8470 100644 --- a/utilities/roslz4/src/xxhash.c +++ b/utilities/roslz4/src/xxhash.c @@ -331,7 +331,10 @@ XXH_errorcode XXH32_resetState(void* state_in, U32 seed) void* XXH32_init (U32 seed) { void* state = XXH_malloc (sizeof(struct XXH_state32_t)); - XXH32_resetState(state, seed); + if (state != NULL) + { + XXH32_resetState(state, seed); + } return state; } diff --git a/utilities/roswtf/src/roswtf/plugins.py b/utilities/roswtf/src/roswtf/plugins.py index f595b11927..27660c527b 100644 --- a/utilities/roswtf/src/roswtf/plugins.py +++ b/utilities/roswtf/src/roswtf/plugins.py @@ -89,7 +89,7 @@ def load_plugins(): else: print("Loaded plugin", p_module) - except Exception: - print("Unable to load plugin [%s] from package [%s]"%(p_module, pkg), file=sys.stderr) + except Exception as e: + print("Unable to load plugin [%s] from package [%s]. Exception thrown: [%s]"%(p_module, pkg, str(e)), file=sys.stderr) return static_plugins, online_plugins diff --git a/utilities/roswtf/src/roswtf/roslaunchwtf.py b/utilities/roswtf/src/roswtf/roslaunchwtf.py index 92cf89274a..45265dcccd 100644 --- a/utilities/roswtf/src/roswtf/roslaunchwtf.py +++ b/utilities/roswtf/src/roswtf/roslaunchwtf.py @@ -293,6 +293,8 @@ def _load_online_ctx(ctx): def wtf_check_online(ctx): _load_online_ctx(ctx) + if not ctx.roslaunch_uris: + return for r in online_roslaunch_warnings: warning_rule(r, r[0](ctx), ctx) for r in online_roslaunch_errors: diff --git a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcValue.h b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcValue.h index 50d3c478e8..0b9bc4abe6 100644 --- a/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcValue.h +++ b/utilities/xmlrpcpp/include/xmlrpcpp/XmlRpcValue.h @@ -42,7 +42,7 @@ namespace XmlRpc { typedef std::vector ValueArray; typedef std::map ValueStruct; typedef ValueStruct::iterator iterator; - + typedef ValueStruct::const_iterator const_iterator; //! Constructors XmlRpcValue() : _type(TypeInvalid) { _value.asBinary = 0; } @@ -80,6 +80,7 @@ namespace XmlRpc { // Operators XmlRpcValue& operator=(XmlRpcValue const& rhs); + XmlRpcValue& operator=(bool const& rhs) { return operator=(XmlRpcValue(rhs)); } XmlRpcValue& operator=(int const& rhs) { return operator=(XmlRpcValue(rhs)); } XmlRpcValue& operator=(double const& rhs) { return operator=(XmlRpcValue(rhs)); } XmlRpcValue& operator=(const char* rhs) { return operator=(XmlRpcValue(std::string(rhs))); } @@ -97,12 +98,17 @@ namespace XmlRpc { XmlRpcValue const& operator[](int i) const { assertArray(i+1); return _value.asArray->at(i); } XmlRpcValue& operator[](int i) { assertArray(i+1); return _value.asArray->at(i); } + XmlRpcValue& operator[](std::string const& k) const { assertStruct(); return (*_value.asStruct)[k]; } XmlRpcValue& operator[](std::string const& k) { assertStruct(); return (*_value.asStruct)[k]; } + XmlRpcValue& operator[](const char* k) const { assertStruct(); std::string s(k); return (*_value.asStruct)[s]; } XmlRpcValue& operator[](const char* k) { assertStruct(); std::string s(k); return (*_value.asStruct)[s]; } iterator begin() {assertStruct(); return (*_value.asStruct).begin(); } iterator end() {assertStruct(); return (*_value.asStruct).end(); } + const_iterator begin() const {assertStruct(); return (*_value.asStruct).begin(); } + const_iterator end() const {assertStruct(); return (*_value.asStruct).end(); } + // Accessors //! Return true if the value has been set to something. bool valid() const { return _type != TypeInvalid; } @@ -144,6 +150,7 @@ namespace XmlRpc { void assertTypeOrInvalid(Type t); void assertArray(int size) const; void assertArray(int size); + void assertStruct() const; void assertStruct(); // XML decoding diff --git a/utilities/xmlrpcpp/src/XmlRpcValue.cpp b/utilities/xmlrpcpp/src/XmlRpcValue.cpp index ffbaad3354..9b526bf090 100644 --- a/utilities/xmlrpcpp/src/XmlRpcValue.cpp +++ b/utilities/xmlrpcpp/src/XmlRpcValue.cpp @@ -107,6 +107,12 @@ namespace XmlRpc { throw XmlRpcException("type error: expected an array"); } + void XmlRpcValue::assertStruct() const + { + if (_type != TypeStruct) + throw XmlRpcException("type error: expected a struct"); + } + void XmlRpcValue::assertStruct() { if (_type == TypeInvalid) {