Skip to content

Commit 5f73908

Browse files
authored
Implement the pure-virtual functions in the Waitable class. (#548)
* Implement the pure-virtual functions in the Waitable class. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 1026322 commit 5f73908

File tree

1 file changed

+18
-1
lines changed

1 file changed

+18
-1
lines changed

test_rclcpp/test/test_waitable.cpp

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,12 +13,24 @@
1313
// limitations under the License.
1414

1515
#include <chrono>
16+
#include <cstddef>
17+
#include <functional>
1618
#include <future>
1719
#include <memory>
20+
#include <stdexcept>
1821

1922
#include "gtest/gtest.h"
2023

21-
#include "rclcpp/rclcpp.hpp"
24+
#include "rcl/allocator.h"
25+
#include "rcl/time.h"
26+
#include "rcl/timer.h"
27+
28+
#include "rclcpp/callback_group.hpp"
29+
#include "rclcpp/clock.hpp"
30+
#include "rclcpp/contexts/default_context.hpp"
31+
#include "rclcpp/executors.hpp"
32+
#include "rclcpp/node.hpp"
33+
#include "rclcpp/waitable.hpp"
2234

2335
class WaitableWithTimer : public rclcpp::Waitable
2436
{
@@ -87,6 +99,11 @@ class WaitableWithTimer : public rclcpp::Waitable
8799
execute_promise_.set_value(RCL_RET_OK == ret);
88100
}
89101

102+
void set_on_ready_callback(std::function<void(size_t, int)>) override {}
103+
void clear_on_ready_callback() override {}
104+
105+
std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}
106+
90107
std::shared_ptr<rcl_timer_t> timer_;
91108
size_t timer_idx_;
92109
std::promise<bool> execute_promise_;

0 commit comments

Comments
 (0)