Skip to content

Commit

Permalink
Merge pull request #96 from ros2/fix_flaky_services
Browse files Browse the repository at this point in the history
refactor composition test
  • Loading branch information
dirk-thomas authored Dec 19, 2016
2 parents 082776a + 0b45492 commit 02178ac
Show file tree
Hide file tree
Showing 7 changed files with 34 additions and 16 deletions.
6 changes: 4 additions & 2 deletions composition/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,9 @@ if(BUILD_TESTING)
set(CLIENT_LIBRARY $<TARGET_FILE:client_component${target_suffix}>)
set(API_COMPOSITION_EXECUTABLE $<TARGET_FILE:api_composition${target_suffix}>)
set(API_COMPOSITION_CLI_EXECUTABLE $<TARGET_FILE:api_composition_cli${target_suffix}>)
set(EXPECTED_OUTPUT "${CMAKE_CURRENT_SOURCE_DIR}/test/composition")
set(EXPECTED_OUTPUT_ALL "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_all")
set(EXPECTED_OUTPUT_PUBSUB "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_pubsub")
set(EXPECTED_OUTPUT_SRV "${CMAKE_CURRENT_SOURCE_DIR}/test/composition_srv")

configure_file(
test/test_composition.py.in
Expand All @@ -191,7 +193,7 @@ if(BUILD_TESTING)
"${CMAKE_CURRENT_BINARY_DIR}/test_composition${target_suffix}_$<CONFIGURATION>.py"
APPEND_ENV AMENT_PREFIX_PATH=${CMAKE_CURRENT_BINARY_DIR}/test_ament_index/$<CONFIG>
APPEND_LIBRARY_DIRS "${append_library_dirs}"
TIMEOUT 60)
TIMEOUT 90)
endmacro()

set(append_library_dirs "${CMAKE_CURRENT_BINARY_DIR}")
Expand Down
4 changes: 2 additions & 2 deletions composition/src/client_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "composition/client_component.hpp"

#include <cinttypes>
#include <iostream>
#include <memory>

Expand Down Expand Up @@ -78,8 +79,7 @@ bool Client::on_timer()
using ServiceResponseFuture =
rclcpp::client::Client<example_interfaces::srv::AddTwoInts>::SharedFuture;
auto response_received_callback = [](ServiceResponseFuture future) {
printf("Got result: [%s]\n",
std::to_string(future.get()->sum).c_str());
printf("Got result: [%" PRIu64 "]\n", future.get()->sum);
};
auto future_result = client_->async_send_request(request, response_received_callback);

Expand Down
6 changes: 3 additions & 3 deletions composition/src/server_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include "composition/server_component.hpp"

#include <cinttypes>
#include <iostream>
#include <memory>

Expand All @@ -32,9 +33,8 @@ Server::Server()
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response
) -> void
{
printf("Incoming request: [a: %s, b: %s]\n",
std::to_string(request->a).c_str(),
std::to_string(request->b).c_str());
printf("Incoming request: [a: %" PRIu64 ", b: %" PRIu64 "]\n",
request->a, request->b);
std::flush(std::cout);
response->sum = request->a + request->b;
};
Expand Down
File renamed without changes.
1 change: 1 addition & 0 deletions composition/test/composition_pubsub.regex
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
I heard: \[Hello World: \d+\]
1 change: 1 addition & 0 deletions composition/test/composition_srv.regex
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
Got result: \[\d+\]
32 changes: 23 additions & 9 deletions composition/test/test_composition.py.in
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@ from launch_testing import create_handler
def test_manual_composition():
name = 'test_manual_composition'
executable = '@MANUAL_COMPOSITION_EXECUTABLE@'
launch(name, [executable])
output_file = '@EXPECTED_OUTPUT_ALL@'
launch(name, [executable], output_file)


def test_linktime_composition():
Expand All @@ -35,7 +36,8 @@ def test_linktime_composition():
raise SkipTest
name = 'test_linktime_composition'
executable = '@LINKTIME_COMPOSITION_EXECUTABLE@'
launch(name, [executable])
output_file = '@EXPECTED_OUTPUT_ALL@'
launch(name, [executable], output_file)


def test_dlopen_composition():
Expand All @@ -45,10 +47,11 @@ def test_dlopen_composition():
listener_library = '@LISTENER_LIBRARY@'
server_library = '@SERVER_LIBRARY@'
client_library = '@CLIENT_LIBRARY@'
launch(name, [executable, talker_library, listener_library, server_library, client_library])
output_file = '@EXPECTED_OUTPUT_ALL@'
launch(name, [executable, talker_library, listener_library, server_library, client_library], output_file)


def test_api_composition():
def test_api_pubsub_composition():
import sys
name = 'test_api_composition'
executable = '@API_COMPOSITION_EXECUTABLE@'
Expand All @@ -66,7 +69,17 @@ def test_api_composition():
'composition', 'composition::Listener'],
'name': 'load_listener_component',
'exit_handler': exit_on_error_exit_handler,
},
}
]
output_file = '@EXPECTED_OUTPUT_PUBSUB@'
launch(name, [executable], output_file, additional_processes=additional_processes)


def test_api_srv_composition():
import sys
name = 'test_api_composition'
executable = '@API_COMPOSITION_EXECUTABLE@'
additional_processes = [
{
'cmd': [
'@API_COMPOSITION_CLI_EXECUTABLE@',
Expand All @@ -82,14 +95,14 @@ def test_api_composition():
'exit_handler': exit_on_error_exit_handler,
},
]
launch(name, [executable], additional_processes=additional_processes)
output_file = '@EXPECTED_OUTPUT_SRV@'
launch(name, [executable], output_file, additional_processes=additional_processes)


def launch(name, cmd, additional_processes=None):
def launch(name, cmd, output_file, additional_processes=None):
launch_descriptor = LaunchDescriptor()

rmw_implementation = '@rmw_implementation@'
output_file = '@EXPECTED_OUTPUT@'
handler = create_handler(
name, launch_descriptor, output_file,
filtered_rmw_implementation=rmw_implementation)
Expand Down Expand Up @@ -118,4 +131,5 @@ if __name__ == '__main__':
test_manual_composition()
test_linktime_composition()
test_dlopen_composition()
test_api_composition()
test_api_pubsub_composition()
test_api_srv_composition()

0 comments on commit 02178ac

Please sign in to comment.