diff --git a/test_rclcpp/test/test_waitable.cpp b/test_rclcpp/test/test_waitable.cpp index 5c74e1e9..b4085941 100644 --- a/test_rclcpp/test/test_waitable.cpp +++ b/test_rclcpp/test/test_waitable.cpp @@ -13,12 +13,24 @@ // limitations under the License. #include +#include +#include #include #include +#include #include "gtest/gtest.h" -#include "rclcpp/rclcpp.hpp" +#include "rcl/allocator.h" +#include "rcl/time.h" +#include "rcl/timer.h" + +#include "rclcpp/callback_group.hpp" +#include "rclcpp/clock.hpp" +#include "rclcpp/contexts/default_context.hpp" +#include "rclcpp/executors.hpp" +#include "rclcpp/node.hpp" +#include "rclcpp/waitable.hpp" class WaitableWithTimer : public rclcpp::Waitable { @@ -87,6 +99,11 @@ class WaitableWithTimer : public rclcpp::Waitable execute_promise_.set_value(RCL_RET_OK == ret); } + void set_on_ready_callback(std::function) override {} + void clear_on_ready_callback() override {} + + std::shared_ptr take_data_by_entity_id(size_t) override {return nullptr;} + std::shared_ptr timer_; size_t timer_idx_; std::promise execute_promise_;