Skip to content

Commit

Permalink
address feedback regarding formatting issues
Browse files Browse the repository at this point in the history
Signed-off-by: Miaofei <[email protected]>
  • Loading branch information
mm318 committed Apr 17, 2019
1 parent 83d2d54 commit c522296
Show file tree
Hide file tree
Showing 6 changed files with 41 additions and 40 deletions.
2 changes: 0 additions & 2 deletions rcl/include/rcl/event.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ extern "C"
#include "rcl/subscription.h"
#include "rcl/visibility_control.h"


typedef enum rcl_publisher_event_type_t
{
RCL_PUBLISHER_OFFERED_DEADLINE_MISSED,
Expand All @@ -52,7 +51,6 @@ typedef struct rcl_event_t
struct rcl_event_impl_t * impl;
} rcl_event_t;


/// Return a rcl_event_t struct with members set to `NULL`.
/**
* Should be called to get a null rcl_event_t before passing to
Expand Down
1 change: 0 additions & 1 deletion rcl/include/rcl/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,6 @@ typedef rmw_ret_t rcl_ret_t;
/// Failed to take an event from the event handle
#define RCL_RET_EVENT_TAKE_FAILED 2001


/// typedef for rmw_serialized_message_t;
typedef rmw_serialized_message_t rcl_serialized_message_t;

Expand Down
4 changes: 3 additions & 1 deletion rcl/src/rcl/event.c
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ rcl_publisher_event_init(
const rcl_publisher_event_type_t event_type)
{
rcl_ret_t ret = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(event, RCL_RET_EVENT_INVALID);
// Check publisher and allocator first, so allocator can be used with errors.
RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = &publisher->impl->options.allocator;
Expand Down Expand Up @@ -92,6 +93,7 @@ rcl_subscription_event_init(
const rcl_subscription_event_type_t event_type)
{
rcl_ret_t ret = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(event, RCL_RET_EVENT_INVALID);
// Check subscription and allocator first, so allocator can be used with errors.
RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = &subscription->impl->options.allocator;
Expand Down Expand Up @@ -130,7 +132,7 @@ rcl_take_event(
void * event_info)
{
bool taken = false;
RCL_CHECK_ARGUMENT_FOR_NULL(event, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(event, RCL_RET_EVENT_INVALID);
RCL_CHECK_ARGUMENT_FOR_NULL(event_info, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t ret = rmw_take_event(&event->impl->rmw_handle, event_info, &taken);
if (RMW_RET_OK != ret) {
Expand Down
1 change: 0 additions & 1 deletion rcl/src/rcl/subscription_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

#include "rcl/subscription.h"


typedef struct rcl_subscription_impl_t
{
rcl_subscription_options_t options;
Expand Down
67 changes: 35 additions & 32 deletions rcl/test/rcl/test_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,12 +45,12 @@ class CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION) : public ::testing::Test
public:
void SetUp()
{
is_opensplice =
std::string(rmw_get_implementation_identifier()).find("rmw_opensplice") == 0;
is_fastrtps =
std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") == 0;
is_opensplice = (std::string(rmw_get_implementation_identifier()).find("rmw_opensplice") == 0);
is_fastrtps = (std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") == 0);

// TODO(mm318): Revisit once FastRTPS supports these QoS policies
is_unsupported = is_fastrtps;

rcl_ret_t ret;
{
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
Expand Down Expand Up @@ -195,7 +195,9 @@ class CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION) : public ::testing::Test
rcl_event_t publisher_event;
rcl_subscription_t subscription;
rcl_event_t subscription_event;
bool is_unsupported, is_opensplice, is_fastrtps;
bool is_fastrtps;
bool is_opensplice;
bool is_unsupported;
const char * topic = "rcl_test_publisher_subscription_events";
const rosidl_message_type_support_t * ts;
};
Expand All @@ -207,13 +209,13 @@ wait_for_msgs_and_events(
rcl_event_t * publisher_event,
rcl_context_t * context,
int64_t period_ms,
bool & msg_ready,
bool & subscription_event_ready,
bool & publisher_event_ready)
bool * msg_ready,
bool * subscription_event_ready,
bool * publisher_event_ready)
{
msg_ready = false;
subscription_event_ready = false;
publisher_event_ready = false;
*msg_ready = false;
*subscription_event_ready = false;
*publisher_event_ready = false;

int num_subscriptions = (nullptr == subscription ? 0 : 1);
int num_events = (nullptr == subscription_event ? 0 : 1) + (nullptr == publisher_event ? 0 : 1);
Expand Down Expand Up @@ -251,15 +253,15 @@ wait_for_msgs_and_events(

for (size_t i = 0; i < wait_set.size_of_subscriptions; ++i) {
if (wait_set.subscriptions[i] && wait_set.subscriptions[i] == subscription) {
msg_ready = true;
*msg_ready = true;
}
}
for (size_t i = 0; i < wait_set.size_of_events; ++i) {
if (nullptr != wait_set.events[i]) {
if (wait_set.events[i] == subscription_event) {
subscription_event_ready = true;
*subscription_event_ready = true;
} else if (wait_set.events[i] == publisher_event) {
publisher_event_ready = true;
*publisher_event_ready = true;
}
}
}
Expand All @@ -273,18 +275,18 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_unsupported_lifespa
rmw_time_t lifespan {1, 0};
rmw_time_t lease_duration {1, 0};
rmw_qos_liveliness_policy_t liveliness_policy = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized subscriber lifespan when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized publisher lifespan when unsupported";

lifespan = {0, 1};
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized subscriber lifespan when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized publisher lifespan when unsupported";
}
Expand All @@ -296,21 +298,21 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_unsupported_livelin
rmw_time_t lifespan {0, 0};
rmw_time_t lease_duration {0, 0};
rmw_qos_liveliness_policy_t liveliness_policy = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE;
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) <<
"Initialized subscriber RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) <<
"Initialized publisher RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE when unsupported";

liveliness_policy = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) <<
"Initialized subscriber RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) <<
"Initialized publisher RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC when unsupported";
Expand All @@ -323,18 +325,18 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_unsupported_unsuppo
rmw_time_t lifespan {0, 0};
rmw_time_t lease_duration {0, 0};
rmw_qos_liveliness_policy_t liveliness_policy = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized subscriber deadline when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized publisher deadline when unsupported";

deadline = {0, 1};
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_subscriber(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized subscriber deadline when unsupported";
EXPECT_EQ(RMW_RET_ERROR,
EXPECT_EQ(RCL_RET_ERROR,
setup_publisher(deadline, lifespan, lease_duration,
liveliness_policy)) << "Initialized publisher deadline when unsupported";
}
Expand Down Expand Up @@ -374,7 +376,7 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_pubsub_liveliness_k
// wait for events
bool msg_ready, subscription_event_ready, publisher_event_ready;
ASSERT_EQ(wait_for_msgs_and_events(&subscription, &subscription_event, nullptr,
context_ptr, 1000, msg_ready, subscription_event_ready, publisher_event_ready), RCL_RET_OK);
context_ptr, 1000, &msg_ready, &subscription_event_ready, &publisher_event_ready), RCL_RET_OK);

// test that the message published to topic is as expected
EXPECT_TRUE(msg_ready);
Expand All @@ -396,11 +398,12 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_pubsub_liveliness_k
ret = rcl_take_event(&subscription_event, &liveliness_status);
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(liveliness_status.alive_count, 0);
int32_t alive_count_changed = 0;
// TODO(ross-desmond): Connext and OpenSplice seem to be counting liveliness changes differently
if (is_opensplice) {
alive_count_changed = 2;
EXPECT_EQ(liveliness_status.alive_count_change, 2);
} else {
EXPECT_EQ(liveliness_status.alive_count_change, 0);
}
EXPECT_EQ(liveliness_status.alive_count_change, alive_count_changed);
EXPECT_EQ(liveliness_status.not_alive_count, 0);
EXPECT_EQ(liveliness_status.not_alive_count_change, 0);
}
Expand Down Expand Up @@ -443,7 +446,7 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_pubsub_deadline_mis
// wait for lease duration to expire
std::this_thread::sleep_for(DEADLINE_PERIOD_IN_S + milliseconds(500));
ASSERT_EQ(wait_for_msgs_and_events(&subscription, &subscription_event, &publisher_event,
context_ptr, 1000, msg_ready, subscription_event_ready, publisher_event_ready), RCL_RET_OK);
context_ptr, 1000, &msg_ready, &subscription_event_ready, &publisher_event_ready), RCL_RET_OK);
// test that the message published to topic is as expected
EXPECT_TRUE(msg_ready);
{
Expand Down Expand Up @@ -507,7 +510,7 @@ TEST_F(CLASSNAME(TestEventFixture, RMW_IMPLEMENTATION), test_pubsub_no_deadline_
// wait for events
bool msg_ready, subscription_event_ready, publisher_event_ready;
ASSERT_EQ(wait_for_msgs_and_events(&subscription, &subscription_event, &publisher_event,
context_ptr, 1000, msg_ready, subscription_event_ready, publisher_event_ready), RCL_RET_OK);
context_ptr, 1000, &msg_ready, &subscription_event_ready, &publisher_event_ready), RCL_RET_OK);
// test that the message published to topic is as expected
EXPECT_TRUE(msg_ready);
{
Expand Down
6 changes: 3 additions & 3 deletions rcl/test/rcl/test_get_actual_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,9 +216,9 @@ get_parameters()
{
rmw_qos_profile_t expected_system_default_qos = expected_system_default_qos_profile();
parameters.push_back({
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
rmw_qos_profile_system_default,
expected_system_default_qos,
"publisher_system_default_qos"});
}
}
#endif
Expand Down

0 comments on commit c522296

Please sign in to comment.