Skip to content

Commit

Permalink
Fix other issues with connext
Browse files Browse the repository at this point in the history
Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Oct 13, 2020
1 parent b5b0922 commit 44cc568
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 3 deletions.
3 changes: 2 additions & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,8 @@ if(TARGET test_node_interfaces__node_clock)
target_link_libraries(test_node_interfaces__node_clock ${PROJECT_NAME})
endif()
ament_add_gtest(test_node_interfaces__node_graph
rclcpp/node_interfaces/test_node_graph.cpp)
rclcpp/node_interfaces/test_node_graph.cpp
TIMEOUT 120)
if(TARGET test_node_interfaces__node_graph)
ament_target_dependencies(
test_node_interfaces__node_graph
Expand Down
15 changes: 13 additions & 2 deletions rclcpp/test/rclcpp/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,6 +278,9 @@ TEST_F(TestPublisher, serialized_message_publish) {
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10, options);

rclcpp::SerializedMessage serialized_msg;
// Mock successful rcl publish because the serialized_msg above is poorly formed
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_OK);
EXPECT_NO_THROW(publisher->publish(serialized_msg));

EXPECT_NO_THROW(publisher->publish(serialized_msg.get_rcl_serialized_message()));
Expand Down Expand Up @@ -415,14 +418,22 @@ TEST_F(TestPublisher, inter_process_publish_failures) {
EXPECT_THROW(publisher->publish(msg), rclcpp::exceptions::RCLError);
}

rclcpp::SerializedMessage serialized_msg;
EXPECT_NO_THROW(publisher->publish(serialized_msg));
{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_serialized_message` is entirely
// defined in a header. Also, this one requires mocking because the serialized_msg is poorly
// formed and this just tests rclcpp functionality.
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_OK);
rclcpp::SerializedMessage serialized_msg;
EXPECT_NO_THROW(publisher->publish(serialized_msg));
}

{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_serialized_message` is entirely
// defined in a header
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_ERROR);
rclcpp::SerializedMessage serialized_msg;
EXPECT_THROW(publisher->publish(serialized_msg), rclcpp::exceptions::RCLError);
}

Expand Down
8 changes: 8 additions & 0 deletions rclcpp_lifecycle/test/test_lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -374,8 +374,16 @@ TEST_F(TestLifecycleServiceClient, get_service_names_and_types_by_node)
EXPECT_THROW(
node_graph->get_service_names_and_types_by_node("not_a_node", "not_absolute_namespace"),
std::runtime_error);
auto start = std::chrono::steady_clock::now();
auto service_names_and_types1 = node_graph->get_service_names_and_types_by_node("client1", "/");
auto service_names_and_types2 = node_graph->get_service_names_and_types_by_node("client2", "/");
while (0 == service_names_and_types1.size() &&
service_names_and_types1.size() != service_names_and_types2.size() &&
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(1))
{
service_names_and_types1 = node_graph->get_service_names_and_types_by_node("client1", "/");
service_names_and_types2 = node_graph->get_service_names_and_types_by_node("client2", "/");
}
EXPECT_EQ(service_names_and_types1.size(), service_names_and_types2.size());
}

Expand Down

0 comments on commit 44cc568

Please sign in to comment.