Skip to content

Commit

Permalink
Make more of the Waitable API abstract (#2593)
Browse files Browse the repository at this point in the history
* Make Waitable::{is_ready,add_to_wait_set,execute} abstract APIs.

I initially started looking at this because clang was complaining
that "all paths through this function will call itself".  And it
is correct; if an implementation does not override these methods,
and they are every called, they will go into an infinite loop
calling themselves.

However, while looking at it it seemed to me that these were really
part of the API that a concrete implementation of Waitable needed
to implement.  It is fine if an implementation doesn't want to do
anything (like the tests), but all of the "real" users in the codebase
override these.

Thus, remove the implementations here and make these pure virtual
functions that all subclasses must implement.

* Remove some more "empty" implementations.

In particular, these are implementations in the Waitable
class that only throw exceptions.  Rather than do this,
make these APIs pure virtual so all downstream classes
have to implement them.  All of the current users (except
for tests) do anyway, and it makes the API much cleaner.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 2, 2024
1 parent 45adf65 commit c468967
Show file tree
Hide file tree
Showing 9 changed files with 47 additions and 79 deletions.
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
add_to_wait_set(rcl_wait_set_t & wait_set);
add_to_wait_set(rcl_wait_set_t & wait_set) = 0;

/// Check if the Waitable is ready.
/**
Expand All @@ -124,7 +124,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
bool
is_ready(const rcl_wait_set_t & wait_set);
is_ready(const rcl_wait_set_t & wait_set) = 0;

/// Take the data so that it can be consumed with `execute`.
/**
Expand Down Expand Up @@ -176,7 +176,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
std::shared_ptr<void>
take_data_by_entity_id(size_t id);
take_data_by_entity_id(size_t id) = 0;

/// Execute data that is passed in.
/**
Expand All @@ -203,7 +203,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
execute(const std::shared_ptr<void> & data);
execute(const std::shared_ptr<void> & data) = 0;

/// Exchange the "in use by wait set" state for this timer.
/**
Expand Down Expand Up @@ -246,7 +246,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
set_on_ready_callback(std::function<void(size_t, int)> callback);
set_on_ready_callback(std::function<void(size_t, int)> callback) = 0;

/// Unset any callback registered via set_on_ready_callback.
/**
Expand All @@ -256,7 +256,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
clear_on_ready_callback();
clear_on_ready_callback() = 0;

private:
std::atomic<bool> in_use_by_wait_set_{false};
Expand Down
46 changes: 0 additions & 46 deletions rclcpp/src/rclcpp/waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,54 +54,8 @@ Waitable::get_number_of_ready_guard_conditions()
return 0u;
}

std::shared_ptr<void>
Waitable::take_data_by_entity_id(size_t id)
{
(void)id;
throw std::runtime_error(
"Custom waitables should override take_data_by_entity_id "
"if they want to use it.");
}

bool
Waitable::exchange_in_use_by_wait_set_state(bool in_use_state)
{
return in_use_by_wait_set_.exchange(in_use_state);
}

void
Waitable::set_on_ready_callback(std::function<void(size_t, int)> callback)
{
(void)callback;

throw std::runtime_error(
"Custom waitables should override set_on_ready_callback "
"if they want to use it.");
}

void
Waitable::clear_on_ready_callback()
{
throw std::runtime_error(
"Custom waitables should override clear_on_ready_callback if they "
"want to use it and make sure to call it on the waitable destructor.");
}

bool
Waitable::is_ready(const rcl_wait_set_t & wait_set)
{
return this->is_ready(wait_set);
}

void
Waitable::add_to_wait_set(rcl_wait_set_t & wait_set)
{
this->add_to_wait_set(wait_set);
}

void
Waitable::execute(const std::shared_ptr<void> & data)
{
// note this const cast is only required to support a deprecated function
this->execute(const_cast<std::shared_ptr<void> &>(data));
}
12 changes: 6 additions & 6 deletions rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,13 @@ class TestWaitable : public rclcpp::Waitable
void add_to_wait_set(rcl_wait_set_t &) override {}
bool is_ready(const rcl_wait_set_t &) override {return false;}

std::shared_ptr<void>
take_data() override
{
return nullptr;
}

std::shared_ptr<void> take_data() override {return nullptr;}
void execute(const std::shared_ptr<void> &) override {}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}
};

class TestNodeWaitables : public ::testing::Test
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/test/rclcpp/strategies/test_allocator_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,13 +51,13 @@ class TestWaitable : public rclcpp::Waitable
return test_waitable_result;
}

std::shared_ptr<void>
take_data() override
{
return nullptr;
}

std::shared_ptr<void> take_data() override {return nullptr;}
void execute(const std::shared_ptr<void> &) override {}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}
};

struct RclWaitSetSizes
Expand Down
5 changes: 5 additions & 0 deletions rclcpp/test/rclcpp/test_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,11 @@ class TestWaitable : public rclcpp::Waitable

std::shared_ptr<void> take_data() override {return nullptr;}
void execute(const std::shared_ptr<void> &) override {}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}
};

class TestMemoryStrategy : public ::testing::Test
Expand Down
10 changes: 6 additions & 4 deletions rclcpp/test/rclcpp/wait_set_policies/test_dynamic_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,18 @@ class TestWaitable : public rclcpp::Waitable
: is_ready_(false) {}

void add_to_wait_set(rcl_wait_set_t &) override {}

bool is_ready(const rcl_wait_set_t &) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(const std::shared_ptr<void> &) override {}
void execute(const std::shared_ptr<void> &) override {}

void set_is_ready(bool value) {is_ready_ = value;}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}

private:
bool is_ready_;
};
Expand Down
10 changes: 6 additions & 4 deletions rclcpp/test/rclcpp/wait_set_policies/test_static_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,18 @@ class TestWaitable : public rclcpp::Waitable
: is_ready_(false) {}

void add_to_wait_set(rcl_wait_set_t &) override {}

bool is_ready(const rcl_wait_set_t &) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(const std::shared_ptr<void> &) override {}
void execute(const std::shared_ptr<void> &) override {}

void set_is_ready(bool value) {is_ready_ = value;}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}

private:
bool is_ready_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,14 +61,17 @@ class TestWaitable : public rclcpp::Waitable
bool is_ready(const rcl_wait_set_t &) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(const std::shared_ptr<void> & data) override {(void)data;}
void execute(const std::shared_ptr<void> &) override {}

void set_is_ready(bool value) {is_ready_ = value;}

void set_add_to_wait_set(bool value) {add_to_wait_set_ = value;}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}

private:
bool is_ready_;
bool add_to_wait_set_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,16 +52,18 @@ class TestWaitable : public rclcpp::Waitable
: is_ready_(false) {}

void add_to_wait_set(rcl_wait_set_t &) override {}

bool is_ready(const rcl_wait_set_t &) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(const std::shared_ptr<void> &) override {}
void execute(const std::shared_ptr<void> &) override {}

void set_is_ready(bool value) {is_ready_ = value;}

void set_on_ready_callback(std::function<void(size_t, int)>) override {}
void clear_on_ready_callback() override {}

std::shared_ptr<void> take_data_by_entity_id(size_t) override {return nullptr;}

private:
bool is_ready_;
};
Expand Down

0 comments on commit c468967

Please sign in to comment.