Skip to content

Commit

Permalink
Address review comments
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
Barry-Xu-2018 committed Jan 13, 2022
1 parent 836dc49 commit d9ea59d
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
6 changes: 3 additions & 3 deletions rclcpp/topics/minimal_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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}
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <inttypes.h>

#include <chrono>
#include <functional>
#include <cinttypes>
#include <memory>
#include <string>

Expand Down Expand Up @@ -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();
});

Expand Down

0 comments on commit d9ea59d

Please sign in to comment.