Merge pull request #167 from ros2/uncrustify_master

update style to match latest uncrustify
This commit is contained in:
Dirk Thomas 2017-09-29 11:12:38 -07:00 committed by GitHub
commit 29a01c3beb
17 changed files with 451 additions and 380 deletions

View file

@ -399,8 +399,8 @@ rcl_set_default_ros_time_source(rcl_time_source_t * process_time_source);
RCL_PUBLIC RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_difference_times(rcl_time_point_t * start, rcl_time_point_t * finish, rcl_difference_times(
rcl_duration_t * delta); rcl_time_point_t * start, rcl_time_point_t * finish, rcl_duration_t * delta);
/// Fill the time point with the current value of the associated clock. /// Fill the time point with the current value of the associated clock.
/** /**
@ -466,8 +466,8 @@ rcl_disable_ros_time_override(rcl_time_source_t * time_source);
RCL_PUBLIC RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_is_enabled_ros_time_override(rcl_time_source_t * time_source, rcl_is_enabled_ros_time_override(
bool * is_enabled); rcl_time_source_t * time_source, bool * is_enabled);
/// Set the current time for this `RCL_ROS_TIME` time source. /// Set the current time for this `RCL_ROS_TIME` time source.
/** /**
@ -485,8 +485,8 @@ rcl_is_enabled_ros_time_override(rcl_time_source_t * time_source,
RCL_PUBLIC RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_set_ros_time_override(rcl_time_source_t * time_source, rcl_set_ros_time_override(
rcl_time_point_value_t time_value); rcl_time_source_t * time_source, rcl_time_point_value_t time_value);
#if __cplusplus #if __cplusplus
} }

View file

@ -35,7 +35,7 @@ extern "C"
#pragma section(".CRT$XCU", read) #pragma section(".CRT$XCU", read)
#define INITIALIZER2_(f, p) \ #define INITIALIZER2_(f, p) \
static void f(void); \ static void f(void); \
__declspec(allocate(".CRT$XCU")) void(*f ## _)(void) = f; \ __declspec(allocate(".CRT$XCU")) void (*f ## _)(void) = f; \
__pragma(comment(linker, "/include:" p #f "_")) \ __pragma(comment(linker, "/include:" p #f "_")) \
static void f(void) static void f(void)
#ifdef _WIN64 #ifdef _WIN64

View file

@ -286,8 +286,8 @@ rcl_set_default_ros_time_source(rcl_time_source_t * process_time_source)
} }
rcl_ret_t rcl_ret_t
rcl_difference_times(rcl_time_point_t * start, rcl_time_point_t * finish, rcl_difference_times(
rcl_duration_t * delta) rcl_time_point_t * start, rcl_time_point_t * finish, rcl_duration_t * delta)
{ {
if (start->time_source->type != finish->time_source->type) { if (start->time_source->type != finish->time_source->type) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG(

View file

@ -20,19 +20,22 @@
*/ */
TEST(TestMemoryTools, test_allocation_checking_tools) { TEST(TestMemoryTools, test_allocation_checking_tools) {
size_t unexpected_mallocs = 0; size_t unexpected_mallocs = 0;
auto on_unexpected_malloc = ([&unexpected_mallocs]() { auto on_unexpected_malloc = (
unexpected_mallocs++; [&unexpected_mallocs]() {
}); unexpected_mallocs++;
});
set_on_unexpected_malloc_callback(on_unexpected_malloc); set_on_unexpected_malloc_callback(on_unexpected_malloc);
size_t unexpected_reallocs = 0; size_t unexpected_reallocs = 0;
auto on_unexpected_realloc = ([&unexpected_reallocs]() { auto on_unexpected_realloc = (
unexpected_reallocs++; [&unexpected_reallocs]() {
}); unexpected_reallocs++;
});
set_on_unexpected_realloc_callback(on_unexpected_realloc); set_on_unexpected_realloc_callback(on_unexpected_realloc);
size_t unexpected_frees = 0; size_t unexpected_frees = 0;
auto on_unexpected_free = ([&unexpected_frees]() { auto on_unexpected_free = (
unexpected_frees++; [&unexpected_frees]() {
}); unexpected_frees++;
});
set_on_unexpected_free_callback(on_unexpected_free); set_on_unexpected_free_callback(on_unexpected_free);
void * mem = nullptr; void * mem = nullptr;
void * remem = nullptr; void * remem = nullptr;

View file

@ -66,12 +66,13 @@ wait_for_client_to_be_ready(
RCUTILS_LOG_ERROR("Error in wait set init: %s", rcl_get_error_string_safe()) RCUTILS_LOG_ERROR("Error in wait set init: %s", rcl_get_error_string_safe())
return false; return false;
} }
auto wait_set_exit = make_scope_exit([&wait_set]() { auto wait_set_exit = make_scope_exit(
if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { [&wait_set]() {
RCUTILS_LOG_ERROR("Error in wait set fini: %s", rcl_get_error_string_safe()) if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) {
throw std::runtime_error("error while waiting for client"); RCUTILS_LOG_ERROR("Error in wait set fini: %s", rcl_get_error_string_safe())
} throw std::runtime_error("error while waiting for client");
}); }
});
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
@ -115,12 +116,13 @@ int main(int argc, char ** argv)
RCUTILS_LOG_ERROR("Error in node init: %s", rcl_get_error_string_safe()) RCUTILS_LOG_ERROR("Error in node init: %s", rcl_get_error_string_safe())
return -1; return -1;
} }
auto node_exit = make_scope_exit([&main_ret, &node]() { auto node_exit = make_scope_exit(
if (rcl_node_fini(&node) != RCL_RET_OK) { [&main_ret, &node]() {
RCUTILS_LOG_ERROR("Error in node fini: %s", rcl_get_error_string_safe()) if (rcl_node_fini(&node) != RCL_RET_OK) {
main_ret = -1; RCUTILS_LOG_ERROR("Error in node fini: %s", rcl_get_error_string_safe())
} main_ret = -1;
}); }
});
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
example_interfaces, AddTwoInts); example_interfaces, AddTwoInts);
@ -134,12 +136,13 @@ int main(int argc, char ** argv)
return -1; return -1;
} }
auto client_exit = make_scope_exit([&client, &main_ret, &node]() { auto client_exit = make_scope_exit(
if (rcl_client_fini(&client, &node)) { [&client, &main_ret, &node]() {
RCUTILS_LOG_ERROR("Error in client fini: %s", rcl_get_error_string_safe()) if (rcl_client_fini(&client, &node)) {
main_ret = -1; RCUTILS_LOG_ERROR("Error in client fini: %s", rcl_get_error_string_safe())
} main_ret = -1;
}); }
});
// Wait until server is available // Wait until server is available
if (!wait_for_server_to_be_available(&node, &client, 1000, 100)) { if (!wait_for_server_to_be_available(&node, &client, 1000, 100)) {

View file

@ -40,12 +40,13 @@ wait_for_service_to_be_ready(
RCUTILS_LOG_ERROR("Error in wait set init: %s", rcl_get_error_string_safe()) RCUTILS_LOG_ERROR("Error in wait set init: %s", rcl_get_error_string_safe())
return false; return false;
} }
auto wait_set_exit = make_scope_exit([&wait_set]() { auto wait_set_exit = make_scope_exit(
if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { [&wait_set]() {
RCUTILS_LOG_ERROR("Error in wait set fini: %s", rcl_get_error_string_safe()) if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) {
throw std::runtime_error("error waiting for service to be ready"); RCUTILS_LOG_ERROR("Error in wait set fini: %s", rcl_get_error_string_safe())
} throw std::runtime_error("error waiting for service to be ready");
}); }
});
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
@ -89,12 +90,13 @@ int main(int argc, char ** argv)
RCUTILS_LOG_ERROR("Error in node init: %s", rcl_get_error_string_safe()) RCUTILS_LOG_ERROR("Error in node init: %s", rcl_get_error_string_safe())
return -1; return -1;
} }
auto node_exit = make_scope_exit([&main_ret, &node]() { auto node_exit = make_scope_exit(
if (rcl_node_fini(&node) != RCL_RET_OK) { [&main_ret, &node]() {
RCUTILS_LOG_ERROR("Error in node fini: %s", rcl_get_error_string_safe()) if (rcl_node_fini(&node) != RCL_RET_OK) {
main_ret = -1; RCUTILS_LOG_ERROR("Error in node fini: %s", rcl_get_error_string_safe())
} main_ret = -1;
}); }
});
const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT(
example_interfaces, AddTwoInts); example_interfaces, AddTwoInts);
@ -108,19 +110,21 @@ int main(int argc, char ** argv)
return -1; return -1;
} }
auto service_exit = make_scope_exit([&main_ret, &service, &node]() { auto service_exit = make_scope_exit(
if (rcl_service_fini(&service, &node)) { [&main_ret, &service, &node]() {
RCUTILS_LOG_ERROR("Error in service fini: %s", rcl_get_error_string_safe()) if (rcl_service_fini(&service, &node)) {
main_ret = -1; RCUTILS_LOG_ERROR("Error in service fini: %s", rcl_get_error_string_safe())
} main_ret = -1;
}); }
});
// Initialize a response. // Initialize a response.
example_interfaces__srv__AddTwoInts_Response service_response; example_interfaces__srv__AddTwoInts_Response service_response;
example_interfaces__srv__AddTwoInts_Response__init(&service_response); example_interfaces__srv__AddTwoInts_Response__init(&service_response);
auto response_exit = make_scope_exit([&service_response]() { auto response_exit = make_scope_exit(
example_interfaces__srv__AddTwoInts_Response__fini(&service_response); [&service_response]() {
}); example_interfaces__srv__AddTwoInts_Response__fini(&service_response);
});
// Block until a client request comes in. // Block until a client request comes in.
@ -132,9 +136,10 @@ int main(int argc, char ** argv)
// Take the pending request. // Take the pending request.
example_interfaces__srv__AddTwoInts_Request service_request; example_interfaces__srv__AddTwoInts_Request service_request;
example_interfaces__srv__AddTwoInts_Request__init(&service_request); example_interfaces__srv__AddTwoInts_Request__init(&service_request);
auto request_exit = make_scope_exit([&service_request]() { auto request_exit = make_scope_exit(
example_interfaces__srv__AddTwoInts_Request__fini(&service_request); [&service_request]() {
}); example_interfaces__srv__AddTwoInts_Request__fini(&service_request);
});
rmw_request_id_t header; rmw_request_id_t header;
// TODO(jacquelinekay) May have to check for timeout error codes // TODO(jacquelinekay) May have to check for timeout error codes
if (rcl_take_request(&service, &header, &service_request) != RCL_RET_OK) { if (rcl_take_request(&service, &header, &service_request) != RCL_RET_OK) {

View file

@ -84,11 +84,12 @@ TEST_F(TestClientFixture, test_client_nominal) {
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0);
auto client_exit = make_scope_exit([&client, this]() { auto client_exit = make_scope_exit(
stop_memory_checking(); [&client, this]() {
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// Initialize the client request. // Initialize the client request.
example_interfaces__srv__AddTwoInts_Request req; example_interfaces__srv__AddTwoInts_Request req;

View file

@ -421,38 +421,39 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
// Create a thread to sleep for a time, then create a publisher, sleep more, then a subscriber, // Create a thread to sleep for a time, then create a publisher, sleep more, then a subscriber,
// sleep more, destroy the subscriber, sleep more, and then destroy the publisher. // sleep more, destroy the subscriber, sleep more, and then destroy the publisher.
std::promise<bool> topic_changes_promise; std::promise<bool> topic_changes_promise;
std::thread topic_thread([this, &topic_changes_promise]() { std::thread topic_thread(
// sleep [this, &topic_changes_promise]() {
std::this_thread::sleep_for(std::chrono::milliseconds(100)); // sleep
// create the publisher std::this_thread::sleep_for(std::chrono::milliseconds(100));
rcl_publisher_t pub = rcl_get_zero_initialized_publisher(); // create the publisher
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options(); rcl_publisher_t pub = rcl_get_zero_initialized_publisher();
rcl_ret_t ret = rcl_publisher_init( rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
&pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), rcl_ret_t ret = rcl_publisher_init(
"/chatter_test_graph_guard_condition_topics", &pub_ops); &pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); "/chatter_test_graph_guard_condition_topics", &pub_ops);
// sleep EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
std::this_thread::sleep_for(std::chrono::milliseconds(100)); // sleep
// create the subscription std::this_thread::sleep_for(std::chrono::milliseconds(100));
rcl_subscription_t sub = rcl_get_zero_initialized_subscription(); // create the subscription
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options(); rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
ret = rcl_subscription_init( rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
&sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String), ret = rcl_subscription_init(
"/chatter_test_graph_guard_condition_topics", &sub_ops); &sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String),
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); "/chatter_test_graph_guard_condition_topics", &sub_ops);
// sleep EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
std::this_thread::sleep_for(std::chrono::milliseconds(100)); // sleep
// destroy the subscription std::this_thread::sleep_for(std::chrono::milliseconds(100));
ret = rcl_subscription_fini(&sub, this->node_ptr); // destroy the subscription
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_subscription_fini(&sub, this->node_ptr);
// sleep EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
std::this_thread::sleep_for(std::chrono::milliseconds(100)); // sleep
// destroy the publication std::this_thread::sleep_for(std::chrono::milliseconds(100));
ret = rcl_publisher_fini(&pub, this->node_ptr); // destroy the publication
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_publisher_fini(&pub, this->node_ptr);
// notify that the thread is done EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
topic_changes_promise.set_value(true); // notify that the thread is done
}); topic_changes_promise.set_value(true);
});
// Wait for the graph state to change, expecting it to do so at least 4 times, // Wait for the graph state to change, expecting it to do so at least 4 times,
// once for each change in the topics thread. // once for each change in the topics thread.
const rcl_guard_condition_t * graph_guard_condition = const rcl_guard_condition_t * graph_guard_condition =
@ -493,11 +494,12 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto client_exit = make_scope_exit([&client, this]() { auto client_exit = make_scope_exit(
stop_memory_checking(); [&client, this]() {
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// Check, knowing there is no service server (created by us at least). // Check, knowing there is no service server (created by us at least).
bool is_available; bool is_available;
ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available); ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available);
@ -561,11 +563,12 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto service_exit = make_scope_exit([&service, this]() { auto service_exit = make_scope_exit(
stop_memory_checking(); [&service, this]() {
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// Wait for and then assert that it is available. // Wait for and then assert that it is available.
wait_for_service_state_to_change(true, is_available); wait_for_service_state_to_change(true, is_available);
ASSERT_TRUE(is_available); ASSERT_TRUE(is_available);

View file

@ -64,11 +64,12 @@ TEST_F(
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
// Setup automatic rcl_shutdown() // Setup automatic rcl_shutdown()
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
stop_memory_checking(); []() {
rcl_ret_t ret = rcl_shutdown(); stop_memory_checking();
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
// Create a zero initialized guard_condition (but not initialized). // Create a zero initialized guard_condition (but not initialized).
rcl_guard_condition_t zero_guard_condition = rcl_get_zero_initialized_guard_condition(); rcl_guard_condition_t zero_guard_condition = rcl_get_zero_initialized_guard_condition();
@ -79,11 +80,12 @@ TEST_F(
ret = rcl_guard_condition_init(&guard_condition, default_options); ret = rcl_guard_condition_init(&guard_condition, default_options);
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
// Setup automatic finalization of guard condition. // Setup automatic finalization of guard condition.
auto rcl_guard_condition_exit = make_scope_exit([&guard_condition]() { auto rcl_guard_condition_exit = make_scope_exit(
stop_memory_checking(); [&guard_condition]() {
rcl_ret_t ret = rcl_guard_condition_fini(&guard_condition); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_guard_condition_fini(&guard_condition);
}); EXPECT_EQ(RCL_RET_OK, ret);
});
// Test rcl_guard_condition_get_options(). // Test rcl_guard_condition_get_options().
const rcl_guard_condition_options_t * actual_options; const rcl_guard_condition_options_t * actual_options;
@ -142,10 +144,11 @@ TEST_F(
// Initialize rcl with rcl_init(). // Initialize rcl with rcl_init().
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
rcl_ret_t ret = rcl_shutdown(); []() {
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
// Try invalid arguments. // Try invalid arguments.
ret = rcl_guard_condition_init(nullptr, default_options); ret = rcl_guard_condition_init(nullptr, default_options);
ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT";

View file

@ -88,31 +88,34 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
// This is the normal check (not windows and windows if not opensplice) // This is the normal check (not windows and windows if not opensplice)
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
} }
auto rcl_invalid_node_exit = make_scope_exit([&invalid_node]() { auto rcl_invalid_node_exit = make_scope_exit(
stop_memory_checking(); [&invalid_node]() {
rcl_ret_t ret = rcl_node_fini(&invalid_node); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_node_fini(&invalid_node);
}); EXPECT_EQ(RCL_RET_OK, ret);
});
ret = rcl_shutdown(); // Shutdown to invalidate the node. ret = rcl_shutdown(); // Shutdown to invalidate the node.
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
stop_memory_checking(); []() {
rcl_ret_t ret = rcl_shutdown(); stop_memory_checking();
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
// Create a zero init node. // Create a zero init node.
rcl_node_t zero_node = rcl_get_zero_initialized_node(); rcl_node_t zero_node = rcl_get_zero_initialized_node();
// Create a normal node. // Create a normal node.
rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_t node = rcl_get_zero_initialized_node();
ret = rcl_node_init(&node, name, namespace_, &default_options); ret = rcl_node_init(&node, name, namespace_, &default_options);
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_node_exit = make_scope_exit([&node]() { auto rcl_node_exit = make_scope_exit(
stop_memory_checking(); [&node]() {
rcl_ret_t ret = rcl_node_fini(&node); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_node_fini(&node);
}); EXPECT_EQ(RCL_RET_OK, ret);
});
// Test rcl_node_is_valid(). // Test rcl_node_is_valid().
bool is_valid; bool is_valid;
is_valid = rcl_node_is_valid(nullptr); is_valid = rcl_node_is_valid(nullptr);
@ -311,10 +314,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle)
// Initialize rcl with rcl_init(). // Initialize rcl with rcl_init().
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
rcl_ret_t ret = rcl_shutdown(); []() {
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
// Try invalid arguments. // Try invalid arguments.
ret = rcl_node_init(nullptr, name, namespace_, &default_options); ret = rcl_node_init(nullptr, name, namespace_, &default_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
@ -401,10 +405,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri
// Initialize rcl with rcl_init(). // Initialize rcl with rcl_init().
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
rcl_ret_t ret = rcl_shutdown(); []() {
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
const char * namespace_ = "/ns"; const char * namespace_ = "/ns";
rcl_node_options_t default_options = rcl_node_get_default_options(); rcl_node_options_t default_options = rcl_node_get_default_options();
@ -461,10 +466,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r
// Initialize rcl with rcl_init(). // Initialize rcl with rcl_init().
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret); ASSERT_EQ(RCL_RET_OK, ret);
auto rcl_shutdown_exit = make_scope_exit([]() { auto rcl_shutdown_exit = make_scope_exit(
rcl_ret_t ret = rcl_shutdown(); []() {
ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_shutdown();
}); ASSERT_EQ(RCL_RET_OK, ret);
});
const char * name = "node"; const char * name = "node";
rcl_node_options_t default_options = rcl_node_get_default_options(); rcl_node_options_t default_options = rcl_node_get_default_options();

View file

@ -93,11 +93,12 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto publisher_exit = make_scope_exit([&publisher, this]() { auto publisher_exit = make_scope_exit(
stop_memory_checking(); [&publisher, this]() {
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0);
std_msgs__msg__Int64 msg; std_msgs__msg__Int64 msg;
std_msgs__msg__Int64__init(&msg); std_msgs__msg__Int64__init(&msg);
@ -118,11 +119,12 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto publisher_exit = make_scope_exit([&publisher, this]() { auto publisher_exit = make_scope_exit(
stop_memory_checking(); [&publisher, this]() {
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
std_msgs__msg__String msg; std_msgs__msg__String msg;
std_msgs__msg__String__init(&msg); std_msgs__msg__String__init(&msg);
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.data, "testing")); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.data, "testing"));

View file

@ -84,11 +84,12 @@ wait_for_service_to_be_ready(
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto wait_set_exit = make_scope_exit([&wait_set]() { auto wait_set_exit = make_scope_exit(
stop_memory_checking(); [&wait_set]() {
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); stop_memory_checking();
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
}); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
@ -128,21 +129,23 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
// Check that the service name matches what we assigned. // Check that the service name matches what we assigned.
EXPECT_EQ(strcmp(rcl_service_get_service_name(&service), expected_topic), 0); EXPECT_EQ(strcmp(rcl_service_get_service_name(&service), expected_topic), 0);
auto service_exit = make_scope_exit([&service, this]() { auto service_exit = make_scope_exit(
stop_memory_checking(); [&service, this]() {
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto client_exit = make_scope_exit([&client, this]() { auto client_exit = make_scope_exit(
stop_memory_checking(); [&client, this]() {
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
@ -171,10 +174,11 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
// Initialize a response. // Initialize a response.
example_interfaces__srv__AddTwoInts_Response service_response; example_interfaces__srv__AddTwoInts_Response service_response;
example_interfaces__srv__AddTwoInts_Response__init(&service_response); example_interfaces__srv__AddTwoInts_Response__init(&service_response);
auto msg_exit = make_scope_exit([&service_response]() { auto msg_exit = make_scope_exit(
stop_memory_checking(); [&service_response]() {
example_interfaces__srv__AddTwoInts_Response__fini(&service_response); stop_memory_checking();
}); example_interfaces__srv__AddTwoInts_Response__fini(&service_response);
});
// Initialize a separate instance of the request and take the pending request. // Initialize a separate instance of the request and take the pending request.
example_interfaces__srv__AddTwoInts_Request service_request; example_interfaces__srv__AddTwoInts_Request service_request;

View file

@ -85,11 +85,12 @@ wait_for_subscription_to_be_ready(
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 0, 0, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 0, 0, 0, 0, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto wait_set_exit = make_scope_exit([&wait_set]() { auto wait_set_exit = make_scope_exit(
stop_memory_checking(); [&wait_set]() {
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); stop_memory_checking();
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
}); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
@ -134,20 +135,22 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto publisher_exit = make_scope_exit([&publisher, this]() { auto publisher_exit = make_scope_exit(
stop_memory_checking(); [&publisher, this]() {
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto subscription_exit = make_scope_exit([&subscription, this]() { auto subscription_exit = make_scope_exit(
stop_memory_checking(); [&subscription, this]() {
rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
EXPECT_EQ(strcmp(rcl_subscription_get_topic_name(&subscription), expected_topic), 0); EXPECT_EQ(strcmp(rcl_subscription_get_topic_name(&subscription), expected_topic), 0);
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
// probably using the count_subscriptions busy wait mechanism // probably using the count_subscriptions busy wait mechanism
@ -167,10 +170,11 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
{ {
std_msgs__msg__Int64 msg; std_msgs__msg__Int64 msg;
std_msgs__msg__Int64__init(&msg); std_msgs__msg__Int64__init(&msg);
auto msg_exit = make_scope_exit([&msg]() { auto msg_exit = make_scope_exit(
stop_memory_checking(); [&msg]() {
std_msgs__msg__Int64__fini(&msg); stop_memory_checking();
}); std_msgs__msg__Int64__fini(&msg);
});
ret = rcl_take(&subscription, &msg, nullptr); ret = rcl_take(&subscription, &msg, nullptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
ASSERT_EQ(42, msg.data); ASSERT_EQ(42, msg.data);
@ -188,20 +192,22 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto publisher_exit = make_scope_exit([&publisher, this]() { auto publisher_exit = make_scope_exit(
stop_memory_checking(); [&publisher, this]() {
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto subscription_exit = make_scope_exit([&subscription, this]() { auto subscription_exit = make_scope_exit(
stop_memory_checking(); [&subscription, this]() {
rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
// probably using the count_subscriptions busy wait mechanism // probably using the count_subscriptions busy wait mechanism
// until then we will sleep for a short period of time // until then we will sleep for a short period of time
@ -221,10 +227,11 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
{ {
std_msgs__msg__String msg; std_msgs__msg__String msg;
std_msgs__msg__String__init(&msg); std_msgs__msg__String__init(&msg);
auto msg_exit = make_scope_exit([&msg]() { auto msg_exit = make_scope_exit(
stop_memory_checking(); [&msg]() {
std_msgs__msg__String__fini(&msg); stop_memory_checking();
}); std_msgs__msg__String__fini(&msg);
});
ret = rcl_take(&subscription, &msg, nullptr); ret = rcl_take(&subscription, &msg, nullptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
ASSERT_EQ(std::string(test_string), std::string(msg.data.data, msg.data.size)); ASSERT_EQ(std::string(test_string), std::string(msg.data.data, msg.data.size));

View file

@ -109,14 +109,15 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) {
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto scope_exit = make_scope_exit([&guard_cond, &wait_set, &timer]() { auto scope_exit = make_scope_exit(
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); [&guard_cond, &wait_set, &timer]() {
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
ret = rcl_wait_set_fini(&wait_set); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_fini(&wait_set);
ret = rcl_timer_fini(&timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_timer_fini(&timer);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
int64_t timeout = -1; int64_t timeout = -1;
std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now();
@ -142,12 +143,13 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) {
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto scope_exit = make_scope_exit([&guard_cond, &wait_set]() { auto scope_exit = make_scope_exit(
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); [&guard_cond, &wait_set]() {
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
ret = rcl_wait_set_fini(&wait_set); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_fini(&wait_set);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
// Time spent during wait should be negligible. // Time spent during wait should be negligible.
int64_t timeout = 0; int64_t timeout = 0;
@ -181,14 +183,15 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) {
ret = rcl_wait_set_add_timer(&wait_set, &canceled_timer); ret = rcl_wait_set_add_timer(&wait_set, &canceled_timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto scope_exit = make_scope_exit([&guard_cond, &wait_set, &canceled_timer]() { auto scope_exit = make_scope_exit(
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); [&guard_cond, &wait_set, &canceled_timer]() {
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
ret = rcl_wait_set_fini(&wait_set); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_fini(&wait_set);
ret = rcl_timer_fini(&canceled_timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_timer_fini(&canceled_timer);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
int64_t timeout = RCL_MS_TO_NS(10); int64_t timeout = RCL_MS_TO_NS(10);
std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now();
@ -292,14 +295,15 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade
test_set.thread_id = 0; test_set.thread_id = 0;
} }
// Setup safe tear-down. // Setup safe tear-down.
auto scope_exit = make_scope_exit([&test_sets]() { auto scope_exit = make_scope_exit(
for (auto & test_set : test_sets) { [&test_sets]() {
rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition); for (auto & test_set : test_sets) {
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition);
ret = rcl_wait_set_fini(&test_set.wait_set); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_fini(&test_set.wait_set);
} EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
}); }
});
// Now kick off all the threads. // Now kick off all the threads.
size_t thread_enumeration = 0; size_t thread_enumeration = 0;
for (auto & test_set : test_sets) { for (auto & test_set : test_sets) {
@ -349,27 +353,29 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) {
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto scope_exit = make_scope_exit([&wait_set, &guard_cond]() { auto scope_exit = make_scope_exit(
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); [&wait_set, &guard_cond]() {
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
ret = rcl_guard_condition_fini(&guard_cond); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_guard_condition_fini(&guard_cond);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
std::promise<rcl_ret_t> p; std::promise<rcl_ret_t> p;
int64_t timeout = -1; int64_t timeout = -1;
std::chrono::nanoseconds trigger_diff; std::chrono::nanoseconds trigger_diff;
std::thread trigger_thread([&p, &guard_cond, &trigger_diff]() { std::thread trigger_thread(
std::chrono::steady_clock::time_point before_trigger = std::chrono::steady_clock::now(); [&p, &guard_cond, &trigger_diff]() {
std::this_thread::sleep_for(std::chrono::milliseconds(10)); std::chrono::steady_clock::time_point before_trigger = std::chrono::steady_clock::now();
rcl_ret_t ret = rcl_trigger_guard_condition(&guard_cond); std::this_thread::sleep_for(std::chrono::milliseconds(10));
std::chrono::steady_clock::time_point after_trigger = std::chrono::steady_clock::now(); rcl_ret_t ret = rcl_trigger_guard_condition(&guard_cond);
trigger_diff = std::chrono::duration_cast<std::chrono::nanoseconds>( std::chrono::steady_clock::time_point after_trigger = std::chrono::steady_clock::now();
after_trigger - before_trigger); trigger_diff = std::chrono::duration_cast<std::chrono::nanoseconds>(
p.set_value(ret); after_trigger - before_trigger);
}); p.set_value(ret);
});
auto f = p.get_future(); auto f = p.get_future();
std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now();

View file

@ -22,7 +22,7 @@ struct ScopeExit
{ {
explicit ScopeExit(Callable callable) explicit ScopeExit(Callable callable)
: callable_(callable) {} : callable_(callable) {}
~ScopeExit() {callable_(); } ~ScopeExit() {callable_();}
private: private:
Callable callable_; Callable callable_;
@ -35,6 +35,6 @@ make_scope_exit(Callable callable)
return ScopeExit<Callable>(callable); return ScopeExit<Callable>(callable);
} }
#define SCOPE_EXIT(code) make_scope_exit([&]() {code; }) #define SCOPE_EXIT(code) make_scope_exit([&]() {code;})
#endif // SCOPE_EXIT_HPP_ #endif // SCOPE_EXIT_HPP_

View file

@ -86,22 +86,24 @@ TEST_F(TestNamespaceFixture, test_client_server) {
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto service_exit = make_scope_exit([&service, this]() { auto service_exit = make_scope_exit(
stop_memory_checking(); [&service, this]() {
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
rcl_client_t unmatched_client = rcl_get_zero_initialized_client(); rcl_client_t unmatched_client = rcl_get_zero_initialized_client();
rcl_client_options_t unmatched_client_options = rcl_client_get_default_options(); rcl_client_options_t unmatched_client_options = rcl_client_get_default_options();
ret = rcl_client_init( ret = rcl_client_init(
&unmatched_client, this->node_ptr, ts, unmatched_client_name, &unmatched_client_options); &unmatched_client, this->node_ptr, ts, unmatched_client_name, &unmatched_client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto unmatched_client_exit = make_scope_exit([&unmatched_client, this]() { auto unmatched_client_exit = make_scope_exit(
stop_memory_checking(); [&unmatched_client, this]() {
rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
bool is_available = false; bool is_available = false;
for (auto i = 0; i < timeout; ++i) { for (auto i = 0; i < timeout; ++i) {
@ -119,11 +121,12 @@ TEST_F(TestNamespaceFixture, test_client_server) {
ret = rcl_client_init( ret = rcl_client_init(
&matched_client, this->node_ptr, ts, matched_client_name, &matched_client_options); &matched_client, this->node_ptr, ts, matched_client_name, &matched_client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
auto matched_client_exit = make_scope_exit([&matched_client, this]() { auto matched_client_exit = make_scope_exit(
stop_memory_checking(); [&matched_client, this]() {
rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr); stop_memory_checking();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr);
}); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
});
is_available = false; is_available = false;
for (auto i = 0; i < timeout; ++i) { for (auto i = 0; i < timeout; ++i) {

View file

@ -37,122 +37,147 @@ rcl_lifecycle_transition_t * empty_transition = NULL;
unsigned int empty_transition_size = 0; unsigned int empty_transition_size = 0;
// Primary States // Primary States
const rcl_lifecycle_state_t rcl_state_unknown = const rcl_lifecycle_state_t rcl_state_unknown = {
{"unknown", lifecycle_msgs__msg__State__PRIMARY_STATE_UNKNOWN, "unknown", lifecycle_msgs__msg__State__PRIMARY_STATE_UNKNOWN, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_unconfigured = const rcl_lifecycle_state_t rcl_state_unconfigured = {
{"unconfigured", lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED, "unconfigured", lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_inactive = const rcl_lifecycle_state_t rcl_state_inactive = {
{"inactive", lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE, "inactive", lifecycle_msgs__msg__State__PRIMARY_STATE_INACTIVE, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_active = const rcl_lifecycle_state_t rcl_state_active = {
{"active", lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE, "active", lifecycle_msgs__msg__State__PRIMARY_STATE_ACTIVE, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_finalized = const rcl_lifecycle_state_t rcl_state_finalized = {
{"finalized", lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED, "finalized", lifecycle_msgs__msg__State__PRIMARY_STATE_FINALIZED, NULL, NULL, 0
NULL, NULL, 0}; };
// Transition States // Transition States
const rcl_lifecycle_state_t rcl_state_configuring = const rcl_lifecycle_state_t rcl_state_configuring = {
{"configuring", lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING, "configuring", lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_cleaningup = const rcl_lifecycle_state_t rcl_state_cleaningup = {
{"cleaningup", lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP, "cleaningup", lifecycle_msgs__msg__State__TRANSITION_STATE_CLEANINGUP, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_shuttingdown = const rcl_lifecycle_state_t rcl_state_shuttingdown = {
{"shuttingdown", lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN, "shuttingdown", lifecycle_msgs__msg__State__TRANSITION_STATE_SHUTTINGDOWN, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_activating = const rcl_lifecycle_state_t rcl_state_activating = {
{"activating", lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING, "activating", lifecycle_msgs__msg__State__TRANSITION_STATE_ACTIVATING, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_deactivating = const rcl_lifecycle_state_t rcl_state_deactivating = {
{"deactivating", lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING, "deactivating", lifecycle_msgs__msg__State__TRANSITION_STATE_DEACTIVATING, NULL, NULL, 0
NULL, NULL, 0}; };
const rcl_lifecycle_state_t rcl_state_errorprocessing = const rcl_lifecycle_state_t rcl_state_errorprocessing = {
{"errorprocessing", lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING, "errorprocessing", lifecycle_msgs__msg__State__TRANSITION_STATE_ERRORPROCESSING, NULL, NULL, 0
NULL, NULL, 0}; };
// Transitions // Transitions
const rcl_lifecycle_transition_t rcl_transition_configure = const rcl_lifecycle_transition_t rcl_transition_configure = {
{"configure", lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE, "configure", lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
&rcl_state_unconfigured, &rcl_state_configuring}; &rcl_state_unconfigured, &rcl_state_configuring
const rcl_lifecycle_transition_t rcl_transition_configure_success = };
{"configure_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS, const rcl_lifecycle_transition_t rcl_transition_configure_success = {
&rcl_state_configuring, &rcl_state_inactive}; "configure_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_SUCCESS,
const rcl_lifecycle_transition_t rcl_transition_configure_failure = &rcl_state_configuring, &rcl_state_inactive
{"configure_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_FAILURE, };
&rcl_state_configuring, &rcl_state_unconfigured}; const rcl_lifecycle_transition_t rcl_transition_configure_failure = {
const rcl_lifecycle_transition_t rcl_transition_configure_error = "configure_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_CONFIGURE_FAILURE,
{"configure_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR, &rcl_state_configuring, &rcl_state_unconfigured
&rcl_state_configuring, &rcl_state_errorprocessing}; };
const rcl_lifecycle_transition_t rcl_transition_configure_error = {
"configure_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR,
&rcl_state_configuring, &rcl_state_errorprocessing
};
const rcl_lifecycle_transition_t rcl_transition_cleanup = const rcl_lifecycle_transition_t rcl_transition_cleanup = {
{"cleanup", lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP, "cleanup", lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP,
&rcl_state_inactive, &rcl_state_cleaningup}; &rcl_state_inactive, &rcl_state_cleaningup
const rcl_lifecycle_transition_t rcl_transition_cleanup_success = };
{"cleanup_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS, const rcl_lifecycle_transition_t rcl_transition_cleanup_success = {
&rcl_state_cleaningup, &rcl_state_unconfigured}; "cleanup_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_SUCCESS,
const rcl_lifecycle_transition_t rcl_transition_cleanup_failure = &rcl_state_cleaningup, &rcl_state_unconfigured
{"cleanup_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_FAILURE, };
&rcl_state_cleaningup, &rcl_state_inactive}; const rcl_lifecycle_transition_t rcl_transition_cleanup_failure = {
const rcl_lifecycle_transition_t rcl_transition_cleanup_error = "cleanup_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_FAILURE,
{"cleanup_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR, &rcl_state_cleaningup, &rcl_state_inactive
&rcl_state_cleaningup, &rcl_state_errorprocessing}; };
const rcl_lifecycle_transition_t rcl_transition_cleanup_error = {
"cleanup_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_CLEANUP_ERROR,
&rcl_state_cleaningup, &rcl_state_errorprocessing
};
const rcl_lifecycle_transition_t rcl_transition_activate = const rcl_lifecycle_transition_t rcl_transition_activate = {
{"activate", lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE, "activate", lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE,
&rcl_state_inactive, &rcl_state_activating}; &rcl_state_inactive, &rcl_state_activating
const rcl_lifecycle_transition_t rcl_transition_activate_success = };
{"activate_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS, const rcl_lifecycle_transition_t rcl_transition_activate_success = {
&rcl_state_activating, &rcl_state_active}; "activate_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_SUCCESS,
const rcl_lifecycle_transition_t rcl_transition_activate_failure = &rcl_state_activating, &rcl_state_active
{"activate_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_FAILURE, };
&rcl_state_activating, &rcl_state_inactive}; const rcl_lifecycle_transition_t rcl_transition_activate_failure = {
const rcl_lifecycle_transition_t rcl_transition_activate_error = "activate_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_FAILURE,
{"activate_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR, &rcl_state_activating, &rcl_state_inactive
&rcl_state_activating, &rcl_state_errorprocessing}; };
const rcl_lifecycle_transition_t rcl_transition_activate_error = {
"activate_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_ACTIVATE_ERROR,
&rcl_state_activating, &rcl_state_errorprocessing
};
const rcl_lifecycle_transition_t rcl_transition_deactivate = const rcl_lifecycle_transition_t rcl_transition_deactivate = {
{"deactivate", lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE, "deactivate", lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE,
&rcl_state_active, &rcl_state_deactivating}; &rcl_state_active, &rcl_state_deactivating
const rcl_lifecycle_transition_t rcl_transition_deactivate_success = };
{"deactivate_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS, const rcl_lifecycle_transition_t rcl_transition_deactivate_success = {
&rcl_state_deactivating, &rcl_state_inactive}; "deactivate_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_SUCCESS,
const rcl_lifecycle_transition_t rcl_transition_deactivate_failure = &rcl_state_deactivating, &rcl_state_inactive
{"deactivate_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_FAILURE, };
&rcl_state_deactivating, &rcl_state_active}; const rcl_lifecycle_transition_t rcl_transition_deactivate_failure = {
const rcl_lifecycle_transition_t rcl_transition_deactivate_error = "deactivate_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_FAILURE,
{"deactivate_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_ERROR, &rcl_state_deactivating, &rcl_state_active
&rcl_state_deactivating, &rcl_state_errorprocessing}; };
const rcl_lifecycle_transition_t rcl_transition_deactivate_error = {
"deactivate_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_DEACTIVATE_ERROR,
&rcl_state_deactivating, &rcl_state_errorprocessing
};
const rcl_lifecycle_transition_t rcl_transition_unconfigured_shutdown = const rcl_lifecycle_transition_t rcl_transition_unconfigured_shutdown = {
{"unconfigured_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN, "unconfigured_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_UNCONFIGURED_SHUTDOWN,
&rcl_state_unconfigured, &rcl_state_shuttingdown}; &rcl_state_unconfigured, &rcl_state_shuttingdown
const rcl_lifecycle_transition_t rcl_transition_inactive_shutdown = };
{"inactive_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_INACTIVE_SHUTDOWN, const rcl_lifecycle_transition_t rcl_transition_inactive_shutdown = {
&rcl_state_inactive, &rcl_state_shuttingdown}; "inactive_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_INACTIVE_SHUTDOWN,
const rcl_lifecycle_transition_t rcl_transition_active_shutdown = &rcl_state_inactive, &rcl_state_shuttingdown
{"active_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_ACTIVE_SHUTDOWN, };
&rcl_state_active, &rcl_state_shuttingdown}; const rcl_lifecycle_transition_t rcl_transition_active_shutdown = {
const rcl_lifecycle_transition_t rcl_transition_shutdown_success = "active_shutdown", lifecycle_msgs__msg__Transition__TRANSITION_ACTIVE_SHUTDOWN,
{"shutdown_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS, &rcl_state_active, &rcl_state_shuttingdown
&rcl_state_shuttingdown, &rcl_state_finalized}; };
const rcl_lifecycle_transition_t rcl_transition_shutdown_failure = const rcl_lifecycle_transition_t rcl_transition_shutdown_success = {
{"shutdown_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_FAILURE, "shutdown_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_SUCCESS,
&rcl_state_shuttingdown, &rcl_state_finalized}; &rcl_state_shuttingdown, &rcl_state_finalized
const rcl_lifecycle_transition_t rcl_transition_shutdown_error = };
{"shutdown_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_ERROR, const rcl_lifecycle_transition_t rcl_transition_shutdown_failure = {
&rcl_state_shuttingdown, &rcl_state_errorprocessing}; "shutdown_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_FAILURE,
&rcl_state_shuttingdown, &rcl_state_finalized
};
const rcl_lifecycle_transition_t rcl_transition_shutdown_error = {
"shutdown_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_SHUTDOWN_ERROR,
&rcl_state_shuttingdown, &rcl_state_errorprocessing
};
const rcl_lifecycle_transition_t rcl_transition_error_success = const rcl_lifecycle_transition_t rcl_transition_error_success = {
{"errorprocessing_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS, "errorprocessing_success", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_SUCCESS,
&rcl_state_errorprocessing, &rcl_state_unconfigured}; &rcl_state_errorprocessing, &rcl_state_unconfigured
const rcl_lifecycle_transition_t rcl_transition_error_failure = };
{"errorprocessing_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_FAILURE, const rcl_lifecycle_transition_t rcl_transition_error_failure = {
&rcl_state_errorprocessing, &rcl_state_finalized}; "errorprocessing_failure", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_FAILURE,
const rcl_lifecycle_transition_t rcl_transition_error_error = &rcl_state_errorprocessing, &rcl_state_finalized
{"errorprocessing_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_ERROR, };
&rcl_state_errorprocessing, &rcl_state_finalized}; const rcl_lifecycle_transition_t rcl_transition_error_error = {
"errorprocessing_error", lifecycle_msgs__msg__Transition__TRANSITION_ON_ERROR_ERROR,
&rcl_state_errorprocessing, &rcl_state_finalized
};
// default implementation as despicted on // default implementation as despicted on
// design.ros2.org // design.ros2.org