From d9ea59d6c9d5b1c53bcc6895972d13b1af83c23e Mon Sep 17 00:00:00 2001 From: Barry Xu Date: Thu, 13 Jan 2022 13:11:08 +0800 Subject: [PATCH] Address review comments Signed-off-by: Barry Xu --- rclcpp/topics/minimal_publisher/CMakeLists.txt | 6 +++--- .../member_function_with_wait_for_all_acked.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp/topics/minimal_publisher/CMakeLists.txt b/rclcpp/topics/minimal_publisher/CMakeLists.txt index 86a00778..504411d5 100644 --- a/rclcpp/topics/minimal_publisher/CMakeLists.txt +++ b/rclcpp/topics/minimal_publisher/CMakeLists.txt @@ -26,8 +26,8 @@ ament_target_dependencies(publisher_member_function_with_type_adapter rclcpp std add_executable(publisher_member_function_with_unique_network_flow_endpoints member_function_with_unique_network_flow_endpoints.cpp) ament_target_dependencies(publisher_member_function_with_unique_network_flow_endpoints rclcpp std_msgs) -add_executable(publisher_member_function_with_wait_for_all_acked member_function_with_wait_for_all_acked.cpp) -ament_target_dependencies(publisher_member_function_with_wait_for_all_acked rclcpp std_msgs) +add_executable(publisher_wait_for_all_acked member_function_with_wait_for_all_acked.cpp) +ament_target_dependencies(publisher_wait_for_all_acked rclcpp std_msgs) add_executable(publisher_not_composable not_composable.cpp) ament_target_dependencies(publisher_not_composable rclcpp std_msgs) @@ -37,7 +37,7 @@ install(TARGETS publisher_member_function publisher_member_function_with_type_adapter publisher_member_function_with_unique_network_flow_endpoints - publisher_member_function_with_wait_for_all_acked + publisher_wait_for_all_acked publisher_not_composable DESTINATION lib/${PROJECT_NAME} ) diff --git a/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp b/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp index 7e878d2f..bf5a5c92 100644 --- a/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp +++ b/rclcpp/topics/minimal_publisher/member_function_with_wait_for_all_acked.cpp @@ -11,10 +11,9 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -#include - #include #include +#include #include #include @@ -42,6 +41,7 @@ class MinimalPublisher : public rclcpp::Node using rclcpp::contexts::get_global_default_context; get_global_default_context()->add_pre_shutdown_callback( [this]() { + this->timer_->cancel(); this->wait_for_all_acked(); });