Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adjust for new rclcpp::Rate API #516

Merged
merged 1 commit into from
Aug 31, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
37 changes: 23 additions & 14 deletions test_communication/test/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,21 +33,30 @@ void publish(

auto publisher = node->create_publisher<T>(std::string("test/message/") + message_type, qos);

rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
try {
rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
++cycle_index;
cycle_rate.sleep();
}
} catch (const std::exception & ex) {
// It is expected to get into invalid context during the sleep, since rclcpp::shutdown()
// might be called earlier (e.g. when running *AfterShutdown case)
if (ex.what() != std::string("context cannot be slept with because it's invalid")) {
printf("ERROR: got unexpected exception: %s\n", ex.what());
throw ex;
}
++cycle_index;
cycle_rate.sleep();
}

auto end = std::chrono::steady_clock::now();
Expand Down
37 changes: 23 additions & 14 deletions test_communication/test/test_publisher_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,21 +38,30 @@ void publish(

auto publisher = node->create_publisher<T>(std::string("test/message/") + message_type, qos);

rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
try {
rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
++cycle_index;
cycle_rate.sleep();
}
} catch (const std::exception & ex) {
// It is expected to get into invalid context during the sleep, since rclcpp::shutdown()
// might be called earlier (e.g. by subscribe() routine or when running *AfterShutdown case)
if (ex.what() != std::string("context cannot be slept with because it's invalid")) {
printf("ERROR: got unexpected exception: %s\n", ex.what());
throw ex;
}
++cycle_index;
cycle_rate.sleep();
}
}

Expand Down
37 changes: 23 additions & 14 deletions test_security/test/test_secure_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,21 +32,30 @@ int8_t attempt_publish(

auto publisher = node->create_publisher<T>(topic_name, messages.size());

rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
try {
rclcpp::WallRate cycle_rate(10);
rclcpp::WallRate message_rate(100);
size_t cycle_index = 0;
// publish all messages up to number_of_cycles times, longer sleep between each cycle
while (rclcpp::ok() && cycle_index < number_of_cycles) {
size_t message_index = 0;
// publish all messages one by one, shorter sleep between each message
while (rclcpp::ok() && message_index < messages.size()) {
printf("publishing message #%zu\n", message_index + 1);
publisher->publish(*messages[message_index]);
++message_index;
message_rate.sleep();
}
++cycle_index;
cycle_rate.sleep();
}
} catch (const std::exception & ex) {
// It is expected to get into invalid context during the sleep, since rclcpp::shutdown()
// might be called earlier (e.g. when running *AfterShutdown case)
if (ex.what() != std::string("context cannot be slept with because it's invalid")) {
printf("ERROR: got unexpected exception: %s\n", ex.what());
throw ex;
}
++cycle_index;
cycle_rate.sleep();
}

auto end = std::chrono::steady_clock::now();
Expand Down