Skip to content

Commit

Permalink
Reenable disabled test. (#18)
Browse files Browse the repository at this point in the history
We just had to make sure there was a subscriber so that the conversion
would be attempted, and then things started work.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Dec 21, 2021
1 parent f9107d9 commit de3ad3f
Showing 1 changed file with 18 additions and 12 deletions.
30 changes: 18 additions & 12 deletions rclcpp/test/rclcpp/test_publisher_with_type_adapter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,19 +166,25 @@ TEST_F(TestPublisher, various_creation_signatures) {

/*
* Testing that conversion errors are passed up.
* TODO. This test was removed when implementing non convering intra-proccess
* publishing. It may be fixed and added again later.
*/
// TEST_F(TestPublisher, conversion_exception_is_passed_up) {
// using BadStringTypeAdapter = rclcpp::TypeAdapter<int, rclcpp::msg::String>;
// for (auto is_intra_process : {true, false}) {
// rclcpp::NodeOptions options;
// options.use_intra_process_comms(is_intra_process);
// initialize(options);
// auto pub = node->create_publisher<BadStringTypeAdapter>("topic_name", 1);
// EXPECT_THROW(pub->publish(1), std::runtime_error);
// }
// }
TEST_F(TestPublisher, conversion_exception_is_passed_up) {
using BadStringTypeAdapter = rclcpp::TypeAdapter<int, rclcpp::msg::String>;
for (auto is_intra_process : {true, false}) {
rclcpp::NodeOptions options;
options.use_intra_process_comms(is_intra_process);

auto callback =
[](const rclcpp::msg::String::ConstSharedPtr msg) -> void
{
(void)msg;
};

initialize(options);
auto pub = node->create_publisher<BadStringTypeAdapter>("topic_name", 1);
auto sub = node->create_subscription<rclcpp::msg::String>("topic_name", 1, callback);
EXPECT_THROW(pub->publish(1), std::runtime_error);
}
}

/*
* Testing that publisher sends type adapted types and ROS message types with intra proccess communications.
Expand Down

0 comments on commit de3ad3f

Please sign in to comment.