Skip to content

Commit

Permalink
Merge pull request #1477 from ros/backports_lunar
Browse files Browse the repository at this point in the history
changes between 1.14.3 and 1.13.6 for backporting
  • Loading branch information
dirk-thomas authored Aug 17, 2018
2 parents e1ac4cf + d80aa6d commit 3017d57
Show file tree
Hide file tree
Showing 31 changed files with 121 additions and 77 deletions.
2 changes: 2 additions & 0 deletions clients/roscpp/include/ros/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ class ROSCPP_DECL Timer
*/
void setPeriod(const Duration& period, bool reset=true);

bool hasStarted() const { return impl_->hasStarted(); }
bool isValid() { return impl_ && impl_->isValid(); }
operator void*() { return isValid() ? (void*)1 : (void*)0; }

Expand Down Expand Up @@ -98,6 +99,7 @@ class ROSCPP_DECL Timer
Impl();
~Impl();

bool hasStarted() const;
bool isValid();
bool hasPending();
void setPeriod(const Duration& period, bool reset=true);
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/include/ros/timer_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -576,7 +576,7 @@ void TimerManager<T, D, E>::threadFunc()
{
// On system time we can simply sleep for the rest of the wait time, since anything else requiring processing will
// signal the condition variable
int32_t remaining_time = std::max((int32_t)((sleep_end - current).toSec() * 1000.0f), 1);
int64_t remaining_time = std::max<int64_t>((sleep_end - current).toSec() * 1000.0f, 1);
timers_cond_.timed_wait(lock, boost::posix_time::milliseconds(remaining_time));
}
}
Expand Down
14 changes: 2 additions & 12 deletions clients/roscpp/src/libros/connection_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,20 +40,10 @@
namespace ros
{

ConnectionManagerPtr g_connection_manager;
boost::mutex g_connection_manager_mutex;
const ConnectionManagerPtr& ConnectionManager::instance()
{
if (!g_connection_manager)
{
boost::mutex::scoped_lock lock(g_connection_manager_mutex);
if (!g_connection_manager)
{
g_connection_manager = boost::make_shared<ConnectionManager>();
}
}

return g_connection_manager;
static ConnectionManagerPtr connection_manager = boost::make_shared<ConnectionManager>();
return connection_manager;
}

ConnectionManager::ConnectionManager()
Expand Down
4 changes: 4 additions & 0 deletions clients/roscpp/src/libros/io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,8 @@ void close_socket_watcher(int fd) {
void add_socket_to_watcher(int epfd, int fd) {
#if defined(HAVE_EPOLL)
struct epoll_event ev;
bzero(&ev, sizeof(ev));

ev.events = 0;
ev.data.fd = fd;

Expand Down Expand Up @@ -147,6 +149,8 @@ void del_socket_from_watcher(int epfd, int fd) {
void set_events_on_socket(int epfd, int fd, int events) {
#if defined(HAVE_EPOLL)
struct epoll_event ev;
bzero(&ev, sizeof(ev));

ev.events = events;
ev.data.fd = fd;
if (::epoll_ctl(epfd, EPOLL_CTL_MOD, fd, &ev))
Expand Down
14 changes: 2 additions & 12 deletions clients/roscpp/src/libros/poll_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,20 +33,10 @@
namespace ros
{

PollManagerPtr g_poll_manager;
boost::mutex g_poll_manager_mutex;
const PollManagerPtr& PollManager::instance()
{
if (!g_poll_manager)
{
boost::mutex::scoped_lock lock(g_poll_manager_mutex);
if (!g_poll_manager)
{
g_poll_manager.reset(new PollManager);
}
}

return g_poll_manager;
static PollManagerPtr poll_manager = boost::make_shared<PollManager>();
return poll_manager;
}

PollManager::PollManager()
Expand Down
2 changes: 2 additions & 0 deletions clients/roscpp/src/libros/poll_set.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,7 @@ bool PollSet::addEvents(int sock, int events)

set_events_on_socket(epfd_, sock, it->second.events_);

sockets_changed_ = true;
signal();

return true;
Expand All @@ -161,6 +162,7 @@ bool PollSet::delEvents(int sock, int events)

set_events_on_socket(epfd_, sock, it->second.events_);

sockets_changed_ = true;
signal();

return true;
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 @@ -202,7 +202,7 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
msg.period_mean *= 1.0 / (stats.arrival_time_list.size() - 1);

// then, calc the stddev
msg.period_stddev = ros::Duration(0);
double period_variance = 0.0;
for(std::list<ros::Time>::iterator it = stats.arrival_time_list.begin(); it != stats.arrival_time_list.end(); it++)
{
if (it == stats.arrival_time_list.begin())
Expand All @@ -212,11 +212,11 @@ void StatisticsLogger::callback(const boost::shared_ptr<M_string>& connection_he
}
ros::Duration period = *it - prev;
ros::Duration t = msg.period_mean - period;
msg.period_stddev += ros::Duration(t.toSec() * t.toSec());
period_variance += t.toSec() * t.toSec();
prev = *it;
}
msg.period_stddev = ros::Duration(sqrt(msg.period_stddev.toSec() / (stats.arrival_time_list.size() - 1)));

double period_stddev = sqrt(period_variance / (stats.arrival_time_list.size() - 1));
msg.period_stddev = ros::Duration(period_stddev);
}
else
{
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 @@ -42,6 +42,11 @@ Timer::Impl::~Impl()
stop();
}

bool Timer::Impl::hasStarted() const
{
return started_;
}

bool Timer::Impl::isValid()
{
return !period_.isZero();
Expand Down
14 changes: 2 additions & 12 deletions clients/roscpp/src/libros/xmlrpc_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,20 +95,10 @@ void getPid(const XmlRpcValue& params, XmlRpcValue& result)

const ros::WallDuration CachedXmlRpcClient::s_zombie_time_(30.0); // reap after 30 seconds

XMLRPCManagerPtr g_xmlrpc_manager;
boost::mutex g_xmlrpc_manager_mutex;
const XMLRPCManagerPtr& XMLRPCManager::instance()
{
if (!g_xmlrpc_manager)
{
boost::mutex::scoped_lock lock(g_xmlrpc_manager_mutex);
if (!g_xmlrpc_manager)
{
g_xmlrpc_manager.reset(new XMLRPCManager);
}
}

return g_xmlrpc_manager;
static XMLRPCManagerPtr xmlrpc_manager = boost::make_shared<XMLRPCManager>();
return xmlrpc_manager;
}

XMLRPCManager::XMLRPCManager()
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/impl/tcpros_pubsub.py
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ def create_transport(self, resolved_name, pub_uri, protocol_params):
if type(protocol_params) != list or len(protocol_params) != 3:
return 0, "ERROR: invalid TCPROS parameters", 0
if protocol_params[0] != TCPROS:
return 0, "INTERNAL ERROR: protocol id is not TCPROS: %s"%id, 0
return 0, "INTERNAL ERROR: protocol id is not TCPROS: %s"%protocol_params[0], 0
id, dest_addr, dest_port = protocol_params

sub = rospy.impl.registration.get_topic_manager().get_subscriber_impl(resolved_name)
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/names.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
is_global, is_private
import rosgraph.names

from rospy.exceptions import ROSException
from rospy.exceptions import ROSException, ROSInitException
from rospy.impl.validators import ParameterInvalid

TOPIC_ANYTYPE = ANYTYPE #indicates that a subscriber will connect any datatype given to it
Expand Down
2 changes: 1 addition & 1 deletion clients/rospy/src/rospy/topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -1348,7 +1348,7 @@ def get_topics(self):
@return: list of topic names this node subscribes to/publishes
@rtype: [str]
"""
return self.topics
return self.topics.copy()

def _get_list(self, rmap):
return [[k, v.type] for k, v in rmap.items()]
Expand Down
2 changes: 1 addition & 1 deletion test/test_roscpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
catkin_add_gtest(${PROJECT_NAME}-test_version test_version.cpp)
if(TARGET ${PROJECT_NAME}-test_version)
target_link_libraries(${PROJECT_NAME}-test_version)
target_link_libraries(${PROJECT_NAME}-test_version ${catkin_LIBRARIES})
endif()

catkin_add_gtest(${PROJECT_NAME}-test_header test_header.cpp)
Expand Down
8 changes: 4 additions & 4 deletions test/test_roscpp/test_serialization/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,24 +4,24 @@ endif()

catkin_add_gtest(${PROJECT_NAME}-serialization src/serialization.cpp)
if(TARGET ${PROJECT_NAME}-serialization)
target_link_libraries(${PROJECT_NAME}-serialization ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
target_link_libraries(${PROJECT_NAME}-serialization ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME}-serialization ${${PROJECT_NAME}_EXPORTED_TARGETS})
endif()

catkin_add_gtest(${PROJECT_NAME}-generated_messages src/generated_messages.cpp)
if(TARGET ${PROJECT_NAME}-generated_messages)
target_link_libraries(${PROJECT_NAME}-generated_messages ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
target_link_libraries(${PROJECT_NAME}-generated_messages ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME}-generated_messages ${${PROJECT_NAME}_EXPORTED_TARGETS})
endif()

add_executable(${PROJECT_NAME}-builtin_types EXCLUDE_FROM_ALL src/builtin_types.cpp)
add_dependencies(tests ${PROJECT_NAME}-builtin_types)
target_link_libraries(${PROJECT_NAME}-builtin_types ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
target_link_libraries(${PROJECT_NAME}-builtin_types ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME}-builtin_types ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_rostest(test/builtin_types.test)

add_executable(${PROJECT_NAME}-pre_deserialize EXCLUDE_FROM_ALL src/pre_deserialize.cpp)
add_dependencies(tests ${PROJECT_NAME}-pre_deserialize)
target_link_libraries(${PROJECT_NAME}-pre_deserialize ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
target_link_libraries(${PROJECT_NAME}-pre_deserialize ${GTEST_LIBRARIES} ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME}-pre_deserialize ${${PROJECT_NAME}_EXPORTED_TARGETS})
add_rostest(test/pre_deserialize.test)
1 change: 1 addition & 0 deletions tools/rosbag/include/rosbag/recorder.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ struct ROSBAG_DECL RecorderOptions
std::string node;
unsigned long long min_space;
std::string min_space_str;
ros::TransportHints transport_hints;

std::vector<std::string> topics;
};
Expand Down
12 changes: 11 additions & 1 deletion tools/rosbag/src/record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,9 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
("topic", po::value< std::vector<std::string> >(), "topic to record")
("size", po::value<uint64_t>(), "The maximum size of the bag to record in MB.")
("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.");
("node", po::value<std::string>(), "Record all topics subscribed to by a specific node.")
("tcpnodelay", "Use the TCP_NODELAY transport hint when subscribing to topics.")
("udp", "Use the UDP transport hint when subscribing to topics.");


po::positional_options_description p;
Expand Down Expand Up @@ -238,6 +240,14 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
opts.node = vm["node"].as<std::string>();
std::cout << "Recording from: " << opts.node << std::endl;
}
if (vm.count("tcpnodelay"))
{
opts.transport_hints.tcpNoDelay();
}
if (vm.count("udp"))
{
opts.transport_hints.udp();
}

// Every non-option argument is assumed to be a topic
if (vm.count("topic"))
Expand Down
3 changes: 2 additions & 1 deletion tools/rosbag/src/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ int Recorder::run() {
}

shared_ptr<ros::Subscriber> Recorder::subscribe(string const& topic) {
ROS_INFO("Subscribing to %s", topic.c_str());
ROS_INFO("Subscribing to %s", topic.c_str());

ros::NodeHandle nh;
shared_ptr<int> count(boost::make_shared<int>(options_.limit));
Expand All @@ -223,6 +223,7 @@ shared_ptr<ros::Subscriber> Recorder::subscribe(string const& topic) {
ops.helper = boost::make_shared<ros::SubscriptionCallbackHelperT<
const ros::MessageEvent<topic_tools::ShapeShifter const> &> >(
boost::bind(&Recorder::doQueue, this, _1, topic, sub, count));
ops.transport_hints = options_.transport_hints;
*sub = nh.subscribe(ops);

currently_recording_.insert(topic);
Expand Down
4 changes: 4 additions & 0 deletions tools/rosbag/src/rosbag/rosbag_main.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,8 @@ def record_cmd(argv):
parser.add_option( "--node", dest="node", default=None, type='string',action="store", help="record all topics subscribed to by a specific node")
parser.add_option("-j", "--bz2", dest="compression", default=None, action="store_const", const='bz2', help="use BZ2 compression")
parser.add_option("--lz4", dest="compression", action="store_const", const='lz4', help="use LZ4 compression")
parser.add_option("--tcpnodelay", dest="tcpnodelay", action="store_true", help="Use the TCP_NODELAY transport hint when subscribing to topics.")
parser.add_option("--udp", dest="udp", action="store_true", help="Use the UDP transport hint when subscribing to topics.")

(options, args) = parser.parse_args(argv)

Expand Down Expand Up @@ -128,6 +130,8 @@ def record_cmd(argv):
if options.size: cmd.extend(["--size", str(options.size)])
if options.node:
cmd.extend(["--node", options.node])
if options.tcpnodelay: cmd.extend(["--tcpnodelay"])
if options.udp: cmd.extend(["--udp"])

cmd.extend(args)

Expand Down
3 changes: 3 additions & 0 deletions tools/roslaunch/resources/example-args.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<launch>
<arg name="test_foo" />
</launch>
4 changes: 4 additions & 0 deletions tools/roslaunch/resources/example-pass_all_args.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<arg name="test_foo" default="value_foo" />
<include file="$(find roslaunch)/resources/example-args.launch" pass_all_args="true" />
</launch>
6 changes: 6 additions & 0 deletions tools/roslaunch/src/roslaunch/depends.py
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,12 @@ def _parse_launch(tags, launch_file, file_deps, verbose, context):
else:
launch_tag = dom[0]
sub_context = _parse_subcontext(tag.childNodes, context)
try:
if tag.attributes['pass_all_args']:
sub_context["arg"] = context["arg"]
sub_context["arg"].update(_parse_subcontext(tag.childNodes, context)["arg"])
except KeyError as e:
pass
_parse_launch(launch_tag.childNodes, sub_launch_file, file_deps, verbose, sub_context)
except IOError as e:
raise RoslaunchDepsException("Cannot load roslaunch include '%s' in '%s'"%(sub_launch_file, launch_file))
Expand Down
6 changes: 5 additions & 1 deletion tools/roslaunch/test/unit/test_roslaunch_rlutil.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,4 +84,8 @@ def test_resolve_launch_arguments(self):
self.fail("should have failed")
except roslaunch.RLException:
pass


def test_roslaunch_check_pass_all_args(self):
filename = os.path.join(get_example_path(), 'example-pass_all_args.launch')
error_msg = roslaunch.rlutil.check_roslaunch(filename)
assert error_msg is None
2 changes: 1 addition & 1 deletion tools/rostopic/src/rostopic/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -1137,7 +1137,7 @@ def _sub_rostopic_list(master, pubs, subs, publishers_only, subscribers_only, ve
print(indent+"Subscribed topics:")
for t, ttype, tlist in subs:
if len(tlist) > 1:
print(indent+" * %s [%s] %s subscribers"%(t, ttype, len(llist)))
print(indent+" * %s [%s] %s subscribers"%(t, ttype, len(tlist)))
else:
print(indent+" * %s [%s] 1 subscriber"%(t, ttype))
print('')
Expand Down
4 changes: 3 additions & 1 deletion tools/topic_tools/src/demux.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,9 @@ void in_cb(const boost::shared_ptr<ShapeShifter const>& msg)
ros::Duration(0.5).sleep();
}

// check that we have a valid topic
if (!g_selected->pub) return;

// finally: send out the message over the active publisher
g_selected->pub->publish(msg);
ROS_DEBUG("... and sent it out again!");
Expand Down Expand Up @@ -307,4 +310,3 @@ int main(int argc, char **argv)
g_pubs.clear();
return 0;
}

6 changes: 5 additions & 1 deletion utilities/message_filters/src/message_filters/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,12 +156,16 @@ def getElemBeforeTime(self, stamp):
return None
return older[-1]

def getLastestTime(self):
def getLatestTime(self):
"""Return the newest recorded timestamp."""
if not self.cache_times:
return None
return self.cache_times[-1]

def getLastestTime(self):
"""Return the newest recorded timestamp (equivalent to `getLatestTime()`, but included for backwards compatibility)."""
return self.getLatestTime()

def getOldestTime(self):
"""Return the oldest recorded timestamp."""
if not self.cache_times:
Expand Down
6 changes: 4 additions & 2 deletions utilities/message_filters/test/test_message_filters_cache.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,11 @@ def test_all_funcs(self):
self.assertEqual(s, rospy.Time(3),
"invalid msg return by getElemBeforeTime")

s = cache.getLastestTime()
s = cache.getLatestTime()
self.assertEqual(s, rospy.Time(4),
"invalid stamp return by getLastestTime")
"invalid stamp return by getLatestTime")
self.assertEqual(s, cache.getLastestTime(),
"stamps returned by getLatestTime and getLastestTime don't match")

s = cache.getOldestTime()
self.assertEqual(s, rospy.Time(0),
Expand Down
Loading

0 comments on commit 3017d57

Please sign in to comment.