Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

changes between 1.12.14 and 1.14.7 for backporting #2015

Merged
merged 55 commits into from
Aug 7, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
55 commits
Select commit Hold shift + click to select a range
ee4132f
fix topic_tools environment hook (#1486)
mintar Aug 27, 2018
3baa1fe
rosnode: Explicitly handle socket.timeout in rosnode ping (#1517)
msadowski Oct 8, 2018
18f8fc2
Fix stamp_age_mean overflow when stamp age very big (#1526)
KindDragon Nov 10, 2018
317902f
Fix #889 : Exclude unused args check if pass_all_args is set (#1520)
alextoind Nov 20, 2018
8507c26
Setting correctly typed @apivalidate default return values (#1472)
KKostya Nov 20, 2018
1fe09fb
roscpp: Add const specifier to `NodeHandle::param(param_name, default…
achim-k Nov 21, 2018
d0c33a7
Fixed docstring in unregisterSubscriber (#1553)
BoukeKromTNO Jan 2, 2019
aba500a
Removed nullptr access from Timer().hasStarted() (#1541)
kunaltyagi Jan 2, 2019
3200fc6
Fix race due unprotected access to callbacks_ in roscpp client (#1595)
igor-semenov Jan 30, 2019
0a67ed1
normalize strings to utf-8 before setting as environment variable (#1…
kejxu Jan 30, 2019
f848210
/topic_tools/mux: do not dereference the end-iterator (#1579)
cwecht Jan 30, 2019
04bcf54
Catch exeption when searching for services and a single service fails…
mistoll Feb 1, 2019
0e94607
respawn if process died while checking should_respawn() (#1590)
kejxu Feb 8, 2019
868cb08
[rosbag] Fix waitForSubscribers hanging with simtime (#1543)
Feb 19, 2019
7581e3f
fix infinite loop in rosbag buffer resize (#1623)
ipa-fez Feb 20, 2019
67c13ea
fixed bug in statistics decision making if one should publish (#1625)
Feb 26, 2019
cd2e6f1
roscpp/service: use WallTime/WallDuration for waiting (#1638)
cwecht Feb 28, 2019
d7e4059
roscpp/TopicManager: avoid deadlock (#1645)
cwecht Mar 8, 2019
f9cc01b
#1455 reviseted: make roslaunch-check respect arg remappings with co…
cwecht Mar 14, 2019
60af411
Fix wrong error handling in migration. (#1639)
omangin Mar 15, 2019
1bd134f
topic_tools/transfom: create publisher before subscriber, because cal…
cwecht Mar 22, 2019
6625217
Fix $(dirname) for roslaunch-check. (#1624)
mikepurvis Mar 29, 2019
e0c4677
fix topic message count for rosbag indexed v1.2. (#1648)
kmiku7 Mar 29, 2019
52c3a30
/libros/node_handle: alternative way to fix #838 (#1656)
cwecht Mar 30, 2019
6b2ad8f
Fixed issue occuring during alternating calls of getParamCached and s…
cwecht Apr 1, 2019
ebd3643
Resolve memory leak. (#1503)
tahsinkose Apr 15, 2019
7385c90
Fix error handling for Topic constructor (#1701)
scooler Apr 23, 2019
b9bc8f1
Add missing comma in the list of strings (#1760)
yegle Jul 16, 2019
b4e70c1
Added const indexer for xmlrpc (#1759)
Jul 16, 2019
4d6fbcb
rosbag/record: fix signed int overflow (#1741)
cwecht Jul 16, 2019
f5176eb
fixing string check (#1771)
Jul 29, 2019
1dad989
Fix use-after-free issue in rosout (#1764)
Jul 29, 2019
934bb15
Check for fclose returning 0 in rosbag_storage (#1750)
artivis Jul 29, 2019
eef0aaa
rostopic: _rostopic_list_group_by_host: publisher/subscriber lists ha…
cwecht Aug 7, 2019
787f756
check for XXH_malloc NULL return (#1778)
artivis Aug 7, 2019
7ef1304
unregisterService returns result of execute("unregisterService") (#1751)
artivis Aug 7, 2019
4b7441b
roscpp/transport_tcp: enable poll event POLLRDHUP to detect dead (#1704)
cwecht Aug 7, 2019
dcb8be7
add Timer::isValid() const (#1779)
artivis Aug 7, 2019
4c1fa82
XmlRpcValue added bool assignment operator (#1709)
cwecht Aug 7, 2019
60f98df
fixed #1776 deadcode (#1786)
Aug 12, 2019
7687ee2
Missing args (#1733)
DLu Aug 12, 2019
9b89034
[roswtf] Print exception content to show better idea why loading plug…
130s Aug 12, 2019
5153a75
Do not raise socket exception during shutdown (#1720)
yli-cpr Aug 12, 2019
f1d4a11
Use thread local storage for caching instances of ServerProxy (#1732)
johnfettig Oct 3, 2019
1886ef1
roscpp: TransportTCP: Allow socket() to return 0 (#1707)
g-arjones Oct 3, 2019
82658d7
Bug: roslib not being imported (#1818)
dallinbriggs Oct 3, 2019
97b180d
do not try to run online checks if there are no roslaunch uris (#1848)
flixr Jan 8, 2020
a21599a
Allowed empty ssh password for remote launching (#1826)
5tan Feb 7, 2020
5b6cf04
Do not display error message if poll yields EINTR (#1868)
Arusekk Feb 10, 2020
68c6ea1
fix dictionary changed size during iteration (#1894)
dirk-thomas Feb 21, 2020
0f4845f
Fix brief description comments after members (#1920)
elektrokokke Mar 27, 2020
bd3b237
Remove extra \n in ROS_DEBUG. (#1925)
zbynekwinkler Apr 3, 2020
c4c303f
Fix a bug that using a destroyed connection object. (#1950)
Barry-Xu-2018 May 21, 2020
2e159af
fix NameError in launch error handling (#1965)
dirk-thomas May 26, 2020
8cfc4e8
remove not existing NodeProxy from rospy __all__ (#2007)
dirk-thomas Jul 23, 2020
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
2 changes: 1 addition & 1 deletion clients/roscpp/include/ros/node_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -2150,7 +2150,7 @@ if (service) // Enter if advertised service is valid
* or is an otherwise invalid graph resource name.
*/
template<typename T>
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);
Expand Down
4 changes: 3 additions & 1 deletion clients/roscpp/include/ros/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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);

Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

Expand Down
3 changes: 2 additions & 1 deletion clients/roscpp/src/libros/init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
4 changes: 4 additions & 0 deletions clients/roscpp/src/libros/node_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
5 changes: 4 additions & 1 deletion clients/roscpp/src/libros/poll_set.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,10 @@ void PollSet::update(int poll_timeout)
boost::shared_ptr<std::vector<socket_pollfd> > 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
{
Expand Down
4 changes: 4 additions & 0 deletions clients/roscpp/src/libros/publication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)
Expand Down
11 changes: 6 additions & 5 deletions clients/roscpp/src/libros/service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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();
}
}

Expand Down
4 changes: 1 addition & 3 deletions clients/roscpp/src/libros/service_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
8 changes: 4 additions & 4 deletions clients/roscpp/src/libros/statistics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& 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;
Expand All @@ -132,21 +132,21 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& 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<ros::Duration>::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)
{
msg.stamp_age_max = age;
}
}

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<ros::Duration>::iterator it = stats.age_list.begin(); it != stats.age_list.end(); it++)
Expand Down
5 changes: 5 additions & 0 deletions clients/roscpp/src/libros/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_)
Expand Down
5 changes: 3 additions & 2 deletions clients/roscpp/src/libros/topic_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
17 changes: 12 additions & 5 deletions clients/roscpp/src/libros/transport/transport_tcp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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))
Expand Down Expand Up @@ -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)
Expand All @@ -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;
}
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions clients/roscpp/src/libros/transport/transport_udp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/transport_subscriber_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}

Expand Down
3 changes: 1 addition & 2 deletions clients/rospy/src/rospy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@
'INFO',
'WARN',
'ERROR',
'FATAL'
'FATAL',
'is_shutdown',
'signal_shutdown',
'get_node_uri',
Expand All @@ -107,7 +107,6 @@
'logerr_throttle', 'logfatal_throttle',
'parse_rosrpc_uri',
'MasterProxy',
'NodeProxy',
'ROSException',
'ROSSerializationException',
'ROSInitException',
Expand Down
3 changes: 2 additions & 1 deletion clients/rospy/src/rospy/impl/tcpros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
4 changes: 2 additions & 2 deletions clients/rospy/src/rospy/topics.py
Original file line number Diff line number Diff line change
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 Expand Up @@ -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:
Expand Down
15 changes: 13 additions & 2 deletions test/test_roscpp/test/src/params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/sub_to_multiple_pubs.test
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<launch>
<node name="listener" pkg="test_rospy" type="listener.py" />
<node name="talker1" pkg="test_rospy" type="talker.py" />
<node name="talker2" pkg="test_rospy" type="talker.py" />
<node name="talker3" pkg="test_rospy" type="talker.py" />
Expand Down Expand Up @@ -98,6 +99,5 @@
<node name="talker97" pkg="test_rospy" type="talker.py" />
<node name="talker98" pkg="test_rospy" type="talker.py" />
<node name="talker99" pkg="test_rospy" type="talker.py" />
<node name="listener" pkg="test_rospy" type="listener.py" />
<test test-name="sub_to_multiple_pubs" pkg="test_rospy" type="test_sub_to_multiple_pubs.py" />
</launch>
1 change: 1 addition & 0 deletions tools/rosbag/scripts/fix_msg_defs.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@

import sys
import rosbag.migration
import roslib.message

if __name__ == '__main__':
if len(sys.argv) != 3:
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag/src/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand Down
2 changes: 1 addition & 1 deletion tools/rosbag/src/record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
ROS_WARN("Use of \"--split <MAX_SIZE>\" has been deprecated. Please use --split --size <MAX_SIZE> or --split --duration <MAX_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<uint64_t>(S);
}
}
if(vm.count("max-splits"))
Expand Down
Loading