Skip to content

Commit

Permalink
Remove dummy sentinel
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll authored and wjwwood committed Mar 27, 2024
1 parent 1a7d944 commit 3fdd4ef
Show file tree
Hide file tree
Showing 14 changed files with 0 additions and 76 deletions.
6 changes: 0 additions & 6 deletions rclcpp/include/rclcpp/event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,12 +106,6 @@ class EventHandlerBase : public Waitable
Event,
};

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

RCLCPP_PUBLIC
virtual ~EventHandlerBase();

Expand Down
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,6 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
RCLCPP_PUBLIC
ExecutorNotifyWaitable & operator=(const ExecutorNotifyWaitable & other);

RCLCPP_PUBLIC
void
dummy() override {};

/// Add conditions to the wait set
/**
* \param[inout] wait_set structure that conditions will be added to
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,6 @@ class StaticExecutorEntitiesCollector final
RCLCPP_PUBLIC
~StaticExecutorEntitiesCollector();

RCLCPP_PUBLIC
void
dummy() override {};

/// Initialize StaticExecutorEntitiesCollector
/**
* \param p_wait_set A reference to the wait set to be used in the executor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -101,10 +101,6 @@ class SubscriptionIntraProcess

virtual ~SubscriptionIntraProcess() = default;

RCLCPP_PUBLIC
void
dummy() override {};

RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override
Expand Down
5 changes: 0 additions & 5 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,6 @@ class Waitable
RCLCPP_PUBLIC
virtual ~Waitable() = default;

RCLCPP_PUBLIC
virtual
void
dummy() = 0;

/// Get the number of ready subscriptions
/**
* Returns a value of 0 by default.
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,12 +338,6 @@ class TestWaitable : public rclcpp::Waitable
public:
TestWaitable() = default;

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void
add_to_wait_set(rcl_wait_set_t * wait_set) override
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -230,12 +230,6 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_remove_node_out_of_scope) {
class TestWaitable : public rclcpp::Waitable
{
public:
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return true;}
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,6 @@
class TestWaitable : public rclcpp::Waitable
{
public:
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}
bool is_ready(rcl_wait_set_t *) override {return false;}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,6 @@ static bool test_waitable_result = false;
class TestWaitable : public rclcpp::Waitable
{
public:
// TODO(wjwwood): is this ok? double check that this test doesn't need more
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override
{
if (!test_waitable_result) {
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/test/rclcpp/test_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,6 @@ typedef std::map<rclcpp::CallbackGroup::WeakPtr,
class TestWaitable : public rclcpp::Waitable
{
public:
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}
bool is_ready(rcl_wait_set_t *) override {return true;}
std::shared_ptr<void> take_data() override {return nullptr;}
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/test/rclcpp/wait_set_policies/test_dynamic_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,6 @@ class TestWaitable : public rclcpp::Waitable
TestWaitable()
: is_ready_(false) {}

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/test/rclcpp/wait_set_policies/test_static_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,6 @@ class TestWaitable : public rclcpp::Waitable
TestWaitable()
: is_ready_(false) {}

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,6 @@ class TestWaitable : public rclcpp::Waitable
TestWaitable()
: is_ready_(false), add_to_wait_set_(false) {}

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override
{
if (!add_to_wait_set_) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,6 @@ class TestWaitable : public rclcpp::Waitable
TestWaitable()
: is_ready_(false) {}

// TODO(wjwwood): is this ok? do events continue to stay ready until they are
// taken/checked?
RCLCPP_PUBLIC
void
dummy() override {};

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
Expand Down

0 comments on commit 3fdd4ef

Please sign in to comment.