Skip to content

Commit

Permalink
Run tests against all RMW implementations.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Aug 7, 2017
1 parent 5cbabbe commit ca33b59
Show file tree
Hide file tree
Showing 7 changed files with 246 additions and 67 deletions.
46 changes: 32 additions & 14 deletions test_communication/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -214,6 +214,30 @@ if(BUILD_TESTING)
)
endforeach()

# test durability publish / subscribe
configure_file(
test/test_durability.py.in
test_durability${suffix}.py.configured
@ONLY
)
file(GENERATE
OUTPUT "test_durability${suffix}_$<CONFIG>.py"
INPUT "${CMAKE_CURRENT_BINARY_DIR}/test_durability${suffix}.py.configured"
)
ament_add_nose_test(test_durability${suffix}
"${CMAKE_CURRENT_BINARY_DIR}/test_durability${suffix}_$<CONFIG>.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/rosidl_generator_py"
PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}"
APPEND_ENV PYTHONPATH="${CMAKE_CURRENT_BINARY_DIR}/rosidl_generator_py:${CMAKE_CURRENT_SOURCE_DIR}:${CMAKE_CURRENT_BINARY_DIR}/../../rclpy"
APPEND_LIBRARY_DIRS "${append_library_dirs}"
TIMEOUT 30
"")
set_tests_properties(
test_durability${suffix}
PROPERTIES DEPENDS
"test_durability_publisher_cpp__${rmw_implementation1};test_durability_subscriber_cpp__${rmw_implementation2}"
)

# test requester / replier
set(SKIP_TEST "")

Expand Down Expand Up @@ -292,17 +316,21 @@ if(BUILD_TESTING)
if(_client_library1 STREQUAL "rclpy")
set(TEST_PUBLISHER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/publisher_py.py")
set(TEST_REQUESTER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/requester_py.py")
set(TEST_DURABILITY_PUBLISHER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/publisher_durability_py.py")
elseif(_client_library1 STREQUAL "rclcpp")
set(TEST_PUBLISHER_EXECUTABLE "$<TARGET_FILE:test_publisher_cpp>")
set(TEST_REQUESTER_EXECUTABLE "$<TARGET_FILE:test_requester_cpp>")
set(TEST_DURABILITY_PUBLISHER_EXECUTABLE "$<TARGET_FILE:test_durability_publisher_cpp>")
endif()

if(_client_library2 STREQUAL "rclpy")
set(TEST_SUBSCRIBER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/subscriber_py.py")
set(TEST_REPLIER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/replier_py.py")
set(TEST_DURABILITY_SUBSCRIBER_EXECUTABLE "${CMAKE_CURRENT_SOURCE_DIR}/test/subscriber_durability_py.py")
elseif(_client_library2 STREQUAL "rclcpp")
set(TEST_SUBSCRIBER_EXECUTABLE "$<TARGET_FILE:test_subscriber_cpp>")
set(TEST_REPLIER_EXECUTABLE "$<TARGET_FILE:test_replier_cpp>")
set(TEST_DURABILITY_SUBSCRIBER_EXECUTABLE "$<TARGET_FILE:test_durability_subscriber_cpp>")
endif()
endmacro()

Expand Down Expand Up @@ -478,10 +506,10 @@ if(BUILD_TESTING)
custom_executable(test_subscriber_cpp
"test/test_subscriber.cpp")
# executables qos_publisher / qos_subscriber
custom_executable(test_qos_publisher_cpp
"test/test_qos_publisher.cpp")
custom_executable(test_qos_subscriber_cpp
"test/test_qos_subscriber.cpp")
custom_executable(test_durability_publisher_cpp
"test/test_durability_publisher.cpp")
custom_executable(test_durability_subscriber_cpp
"test/test_durability_subscriber.cpp")
# executables requester / replier
custom_executable(test_requester_cpp
"test/test_requester.cpp")
Expand All @@ -493,16 +521,6 @@ if(BUILD_TESTING)
custom_executable(test_secure_subscriber_cpp
"test/test_secure_subscriber.cpp")

# Launch file for QoS tests
set(TEST_QOS_PUBLISHER_EXECUTABLE "$<TARGET_FILE:test_qos_publisher_cpp>")
set(TEST_QOS_SUBSCRIBER_EXECUTABLE "$<TARGET_FILE:test_qos_subscriber_cpp>")
set(TEST_QOS_RMW ${rmw_implementation})
configure_file(
test/test_qos.py.in
test_qos_cpp${test_suffix}.py.configured
@ONLY
)

macro(targets)
custom_test_c(test_messages_c
"test/test_messages_c.cpp")
Expand Down
72 changes: 72 additions & 0 deletions test_communication/test/publisher_durability_py.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import argparse
import importlib
import os
import sys
import time

# this is needed to allow import of test_communication messages
sys.path.insert(0, os.getcwd())


def talker(number_of_cycles):
from message_fixtures import get_msg_primitives
import rclpy
from rclpy.qos import QoSDurabilityPolicy

message_pkg = 'test_communication'
module = importlib.import_module(message_pkg + '.msg')
msg_mod = getattr(module, 'Primitives')

rclpy.init(args=[])

node = rclpy.create_node('talker')

custom_qos_profile = rclpy.qos.qos_profile_default
custom_qos_profile.durability = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL

chatter_pub = node.create_publisher(
msg_mod, 'test_durability_message_primitives', qos_profile=custom_qos_profile)

cycle_count = 0
print('talker: beginning loop')
msgs = get_msg_primitives()
while rclpy.ok() and cycle_count < number_of_cycles:
msg_count = 0
for msg in msgs:
chatter_pub.publish(msg)
msg_count += 1
print('publishing message #%d' % msg_count)
time.sleep(0.01)
cycle_count += 1
time.sleep(0.1)
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('-n', '--number_of_cycles', type=int, default=100,
help='number of sending attempts')
args = parser.parse_args()
try:
talker(
number_of_cycles=args.number_of_cycles)
except KeyboardInterrupt:
print('talker stopped cleanly')
except BaseException:
print('exception in talker:', file=sys.stderr)
raise
90 changes: 90 additions & 0 deletions test_communication/test/subscriber_durability_py.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
# Copyright 2016 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import functools
import importlib
import os
import sys

# this is needed to allow import of test_communication messages
sys.path.insert(0, os.getcwd())


def listener_cb(msg, received_messages, expected_msgs):
known_msg = False
for exp in expected_msgs:
if msg.__repr__() == exp.__repr__():
print('received message #{} of {}'.format(
expected_msgs.index(exp) + 1, len(expected_msgs)))
known_msg = True
already_received = False
for rmsg in received_messages:
if rmsg.__repr__() == msg.__repr__():
already_received = True
break

if not already_received:
received_messages.append(msg)
break
if known_msg is False:
raise RuntimeError('received unexpected message %r' % msg)


def listener():
from message_fixtures import get_msg_primitives
import rclpy
from rclpy.qos import QoSDurabilityPolicy

message_pkg = 'test_communication'
module = importlib.import_module(message_pkg + '.msg')
msg_mod = getattr(module, 'Primitives')

rclpy.init(args=[])

node = rclpy.create_node('listener')

received_messages = []
expected_msgs = get_msg_primitives()

chatter_callback = functools.partial(
listener_cb, received_messages=received_messages, expected_msgs=expected_msgs)

custom_qos_profile = rclpy.qos.qos_profile_default
custom_qos_profile.durability = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL

node.create_subscription(
msg_mod, 'test_durability_message_primitives', chatter_callback,
qos_profile=custom_qos_profile)

spin_count = 1
print('subscriber: beginning loop')
while (rclpy.ok() and len(received_messages) != len(expected_msgs)):
rclpy.spin_once(node)
spin_count += 1
print('spin_count: ' + str(spin_count))
node.destroy_node()
rclpy.shutdown()

assert len(received_messages) == len(expected_msgs),\
'Should have received {} {} messages from talker'.format(len(expected_msgs), 'Primitive')


if __name__ == '__main__':
try:
listener()
except KeyboardInterrupt:
print('subscriber stopped cleanly')
except BaseException:
print('exception in subscriber:', file=sys.stderr)
raise
44 changes: 44 additions & 0 deletions test_communication/test/test_durability.py.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
import os
import sys

from launch import LaunchDescriptor
from launch.exit_handler import primary_exit_handler
from launch.launcher import DefaultLauncher


def test_qos():
ld = LaunchDescriptor()
publisher_cmd = ['@TEST_DURABILITY_PUBLISHER_EXECUTABLE@']
subscriber_cmd = ['@TEST_DURABILITY_SUBSCRIBER_EXECUTABLE@']

if '@TEST_PUBLISHER_RCL@' == 'rclpy':
publisher_cmd.insert(0, sys.executable)
if '@TEST_SUBSCRIBER_RCL@' == 'rclpy':
subscriber_cmd.insert(0, sys.executable)

publisher_env = dict(os.environ)
publisher_env['RMW_IMPLEMENTATION'] = '@PUBLISHER_RMW@'
ld.add_process(
cmd=publisher_cmd,
name='test_durability_publisher',
env=publisher_env,
)

subscriber_env = dict(os.environ)
subscriber_env['RMW_IMPLEMENTATION'] = '@SUBSCRIBER_RMW@'
ld.add_process(
cmd=subscriber_cmd,
name='test_durability_subscriber',
exit_handler=primary_exit_handler,
env=subscriber_env,
)

launcher = DefaultLauncher()
launcher.add_launch_descriptor(ld)
rc = launcher.launch()

assert rc == 0, 'The requester did not receive any replies'


if __name__ == '__main__':
test_qos()
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,9 @@
#include <chrono>
#include <iostream>
#include <string>
#include <vector>

#include <rclcpp/rclcpp.hpp>
#include "rclcpp/rclcpp.hpp"

#include "message_fixtures.hpp"

Expand All @@ -30,10 +31,10 @@ typename rclcpp::publisher::Publisher<T>::SharedPtr publish(

rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = messages.size();
custom_qos_profile.durability = RMW_QOS_POLICY_TRANSIENT_LOCAL_DURABILITY;
custom_qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;

auto publisher = node->create_publisher<T>(
std::string("test_qos_message_primitives"), custom_qos_profile);
std::string("test_durability_message_primitives"), custom_qos_profile);

rclcpp::WallRate time_between_cycles(1);
rclcpp::WallRate time_between_messages(10);
Expand Down Expand Up @@ -67,10 +68,5 @@ int main(int argc, char ** argv)

auto publisher = publish<test_communication::msg::Primitives>(node, get_messages_primitives(), 1);

// Wait for a while before exiting
std::chrono::seconds wait_time(50);

std::this_thread::sleep_for(wait_time);

return 0;
}
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,9 @@
#include <iostream>
#include <stdexcept>
#include <string>
#include <vector>

#include <rclcpp/rclcpp.hpp>
#include "rclcpp/rclcpp.hpp"

#include "message_fixtures.hpp"

Expand Down Expand Up @@ -65,10 +66,10 @@ rclcpp::subscription::SubscriptionBase::SharedPtr subscribe(

rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = expected_messages.size();
custom_qos_profile.durability = RMW_QOS_POLICY_TRANSIENT_LOCAL_DURABILITY;
custom_qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;

auto subscriber = node->create_subscription<T>(
std::string("test_qos_message_primitives"), custom_qos_profile, callback);
std::string("test_durability_message_primitives"), callback, custom_qos_profile);
return subscriber;
}

Expand All @@ -85,13 +86,6 @@ int main(int argc, char ** argv)

auto messages = get_messages_primitives();

std::cout << "Wait for 20 seconds before subscribing" << std::endl;

// Wait for a while before subscribing
std::chrono::seconds wait_time(10);

std::this_thread::sleep_for(wait_time);

std::cout << "Create subscriber" << std::endl;

subscriber = subscribe<test_communication::msg::Primitives>(
Expand Down
Loading

0 comments on commit ca33b59

Please sign in to comment.