Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master'
Browse files Browse the repository at this point in the history
Signed-off-by: Miaofei <miaofei@amazon.com>
  • Loading branch information
mm318 committed Apr 16, 2019
2 parents 8d77189 + 1192db9 commit a0dc06a
Show file tree
Hide file tree
Showing 23 changed files with 1,463 additions and 100 deletions.
27 changes: 27 additions & 0 deletions rcl/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,33 @@
Changelog for package rcl
^^^^^^^^^^^^^^^^^^^^^^^^^

0.7.0 (2019-04-14)
------------------
* Added more test cases for graph API + fix bug. (`#404 <https://github.com/ros2/rcl/issues/404>`_)
* Fixed missing include. (`#413 <https://github.com/ros2/rcl/issues/413>`_)
* Updated to use pedantic. (`#412 <https://github.com/ros2/rcl/issues/412>`_)
* Added function to get publisher actual qos settings. (`#406 <https://github.com/ros2/rcl/issues/406>`_)
* Refactored graph API docs. (`#401 <https://github.com/ros2/rcl/issues/401>`_)
* Updated to use ament_target_dependencies where possible. (`#400 <https://github.com/ros2/rcl/issues/400>`_)
* Fixed regression around fully qualified node name. (`#402 <https://github.com/ros2/rcl/issues/402>`_)
* Added function rcl_names_and_types_init. (`#403 <https://github.com/ros2/rcl/issues/403>`_)
* Fixed uninitialize sequence number of client. (`#395 <https://github.com/ros2/rcl/issues/395>`_)
* Added launch along with launch_testing as test dependencies. (`#393 <https://github.com/ros2/rcl/issues/393>`_)
* Set symbol visibility to hidden for rcl. (`#391 <https://github.com/ros2/rcl/issues/391>`_)
* Updated to split test_token to avoid compiler note. (`#392 <https://github.com/ros2/rcl/issues/392>`_)
* Dropped legacy launch API usage. (`#387 <https://github.com/ros2/rcl/issues/387>`_)
* Improved security directory lookup. (`#332 <https://github.com/ros2/rcl/issues/332>`_)
* Enforce non-null argv values on rcl_init(). (`#388 <https://github.com/ros2/rcl/issues/388>`_)
* Removed incorrect argument documentation. (`#361 <https://github.com/ros2/rcl/issues/361>`_)
* Changed error to warning for multiple loggers. (`#384 <https://github.com/ros2/rcl/issues/384>`_)
* Added rcl_node_get_fully_qualified_name. (`#255 <https://github.com/ros2/rcl/issues/255>`_)
* Updated rcl_remap_t to use the PIMPL pattern. (`#377 <https://github.com/ros2/rcl/issues/377>`_)
* Fixed documentation typo. (`#376 <https://github.com/ros2/rcl/issues/376>`_)
* Removed test circumvention now that a bug is fixed in rmw_opensplice. (`#368 <https://github.com/ros2/rcl/issues/368>`_)
* Updated to pass context to wait set, and fini rmw context. (`#373 <https://github.com/ros2/rcl/issues/373>`_)
* Updated to publish logs to Rosout. (`#350 <https://github.com/ros2/rcl/issues/350>`_)
* Contributors: AAlon, Dirk Thomas, Jacob Perron, M. M, Michael Carroll, Michel Hidalgo, Mikael Arguedas, Nick Burek, RARvolt, Ross Desmond, Sachin Suresh Bhat, Shane Loretz, William Woodall, ivanpauno

0.6.4 (2019-01-11)
------------------
* Added method for accessing rmw_context from rcl_context (`#372 <https://github.com/ros2/rcl/issues/372>`_)
Expand Down
26 changes: 26 additions & 0 deletions rcl/include/rcl/publisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -290,6 +290,32 @@ rcl_ret_t
rcl_publish_serialized_message(
const rcl_publisher_t * publisher, const rcl_serialized_message_t * serialized_message);

/// Manually assert that this Publisher is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC)
/**
* If the rmw Liveliness policy is set to RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC, the creator of
* this publisher may manually call `assert_liveliness` at some point in time to signal to the rest
* of the system that this Node is still alive.
* This function must be called at least as often as the qos_profile's liveliness_lease_duration
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] publisher handle to the publisher that needs liveliness to be asserted
* \return `RCL_RET_OK` if the liveliness assertion was completed successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_PUBLISHER_INVALID` if the publisher is invalid, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_publisher_assert_liveliness(const rcl_publisher_t * publisher);

/// Get the topic name for the publisher.
/**
* This function returns the publisher's internal topic name string.
Expand Down
2 changes: 1 addition & 1 deletion rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rcl</name>
<version>0.6.4</version>
<version>0.7.0</version>
<description>The ROS client library common implementation.
This package contains an API which builds on the ROS middleware API and is optionally built upon by the other ROS client libraries.
</description>
Expand Down
10 changes: 6 additions & 4 deletions rcl/src/rcl/graph.c
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ rcl_get_publisher_names_and_types_by_node(
if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -80,7 +80,7 @@ rcl_get_subscriber_names_and_types_by_node(
if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -117,7 +117,7 @@ rcl_get_service_names_and_types_by_node(
if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT);
Expand Down Expand Up @@ -152,7 +152,7 @@ rcl_get_topic_names_and_types(
if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; // error already set
}
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret;
rmw_ret = rmw_names_and_types_check_zero(topic_names_and_types);
Expand All @@ -178,6 +178,7 @@ rcl_get_service_names_and_types(
if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; // error already set
}
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret;
rmw_ret = rmw_names_and_types_check_zero(service_names_and_types);
Expand All @@ -200,6 +201,7 @@ rcl_names_and_types_init(
rcl_allocator_t * allocator)
{
RCL_CHECK_ARGUMENT_FOR_NULL(names_and_types, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR(allocator, return RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret = rmw_names_and_types_init(names_and_types, size, allocator);
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
}
Expand Down
13 changes: 13 additions & 0 deletions rcl/src/rcl/publisher.c
Original file line number Diff line number Diff line change
Expand Up @@ -270,6 +270,19 @@ rcl_publish_serialized_message(
return RCL_RET_OK;
}

rcl_ret_t
rcl_publisher_assert_liveliness(const rcl_publisher_t * publisher)
{
if (!rcl_publisher_is_valid(publisher)) {
return RCL_RET_PUBLISHER_INVALID; // error already set
}
if (rmw_publisher_assert_liveliness(publisher->impl->rmw_handle) != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR;
}
return RCL_RET_OK;
}

const char *
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher)
{
Expand Down
2 changes: 1 addition & 1 deletion rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ function(test_target_function)
# TODO(mm318): why rmw_connext tests run much slower than rmw_fastrtps and rmw_opensplice tests
elseif(rmw_implementation STREQUAL "rmw_connext_cpp")
message(STATUS "Increasing test_graph${target_suffix} test timeout.")
set(AMENT_GTEST_ARGS TIMEOUT 90)
set(AMENT_GTEST_ARGS TIMEOUT 180)
endif()
rcl_add_custom_gtest(test_graph${target_suffix}
SRCS rcl/test_graph.cpp
Expand Down
4 changes: 2 additions & 2 deletions rcl/test/rcl/test_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ constexpr seconds DEADLINE_PERIOD_IN_S(1);
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

class CLASSNAME (TestEventFixture, RMW_IMPLEMENTATION) : public ::testing::Test
class CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION) : public ::testing::Test
{
public:
void SetUp()
Expand Down Expand Up @@ -220,7 +220,7 @@ wait_for_msgs_and_events(

rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, num_subscriptions, 0, 0, 0, 0, num_events,
context, rcl_get_default_allocator());
context, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
Expand Down
80 changes: 36 additions & 44 deletions rcl/test/rcl/test_get_actual_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,35 @@ TEST_P_RMW(TestGetActualQoS, test_publisher_get_qos_settings) {
rcl_reset_error();
}

static constexpr rmw_qos_profile_t non_default_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
profile.depth = 1000;
profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
profile.avoid_ros_namespace_conventions = true;
return profile;
}

static constexpr rmw_qos_profile_t expected_fastrtps_default_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

static constexpr rmw_qos_profile_t expected_system_default_qos_profile()
{
rmw_qos_profile_t profile = rmw_qos_profile_default;
profile.depth = 1;
profile.liveliness = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
return profile;
}

std::vector<TestParameters>
get_parameters()
{
Expand All @@ -164,28 +193,8 @@ get_parameters()
Test with non-default settings.
*/
{
{
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
1000,
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
RMW_QOS_LIFESPAN_DEFAULT,
true
},
{
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
1000,
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
RMW_QOS_LIFESPAN_DEFAULT,
true
},
non_default_qos_profile(),
non_default_qos_profile(),
"publisher_non_default_qos"
}
});
Expand All @@ -195,42 +204,25 @@ get_parameters()
if (rmw_implementation_str == "rmw_fastrtps_cpp" ||
rmw_implementation_str == "rmw_fastrtps_dynamic_cpp")
{
rmw_qos_profile_t expected_system_default_qos = {
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
1,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
RMW_QOS_LIFESPAN_DEFAULT,
false};
rmw_qos_profile_t expected_system_default_qos = expected_fastrtps_default_qos_profile();
parameters.push_back({
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
} else {
if (rmw_implementation_str == "rmw_connext_cpp" ||
rmw_implementation_str == "rmw_connext_dynamic_cpp" ||
rmw_implementation_str == "rmw_opensplice_cpp")
rmw_implementation_str == "rmw_connext_dynamic_cpp" ||
rmw_implementation_str == "rmw_opensplice_cpp")
{
rmw_qos_profile_t expected_system_default_qos = {
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
1,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
RMW_QOS_LIFESPAN_DEFAULT,
false};
rmw_qos_profile_t expected_system_default_qos = expected_system_default_qos_profile();
parameters.push_back({
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
}
}
#endif

return parameters;
}

Expand Down
Loading

0 comments on commit a0dc06a

Please sign in to comment.