Skip to content

Commit

Permalink
correct initialization of rmw_qos_profile_t struct instances
Browse files Browse the repository at this point in the history
Signed-off-by: Miaofei <miaofei@amazon.com>
  • Loading branch information
mm318 committed Apr 14, 2019
1 parent 2476950 commit 369fdd8
Showing 1 changed file with 9 additions and 7 deletions.
16 changes: 9 additions & 7 deletions rclcpp/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,14 @@ class TestPublisherSub : public ::testing::Test
rclcpp::Node::SharedPtr subnode;
};

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

/*
Testing publisher construction and destruction.
*/
Expand All @@ -87,13 +95,7 @@ TEST_F(TestPublisher, construction_and_destruction) {
*/
TEST_F(TestPublisher, intraprocess_with_invalid_qos) {
initialize(rclcpp::NodeOptions().use_intra_process_comms(true));
rmw_qos_profile_t qos = {
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
1,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
false
};
rmw_qos_profile_t qos = invalid_qos_profile();
using rcl_interfaces::msg::IntraProcessMessage;
{
ASSERT_THROW(
Expand Down

0 comments on commit 369fdd8

Please sign in to comment.