Skip to content

Commit

Permalink
enable simulation clock for timer canceling test.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Mar 20, 2024
1 parent 1c350d0 commit 8498c1c
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 6 deletions.
6 changes: 6 additions & 0 deletions rclcpp/test/rclcpp/executors/executor_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,12 @@ using ExecutorTypes =
rclcpp::executors::StaticSingleThreadedExecutor,
rclcpp::experimental::executors::EventsExecutor>;

using MainExecutorTypes =
::testing::Types<
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::StaticSingleThreadedExecutor>;

class ExecutorTypeNames
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,20 @@ class TimerNode : public rclcpp::Node
public:
explicit TimerNode(std::string subname)
: Node("timer_node", subname)
{
}

void CreateTimer1()
{
timer1_ = rclcpp::create_timer(
this->get_node_base_interface(), get_node_timers_interface(),
get_clock(), 1ms,
std::bind(&TimerNode::Timer1Callback, this));
}

timer2_ =
rclcpp::create_timer(
void CreateTimer2()
{
timer2_ = rclcpp::create_timer(
this->get_node_base_interface(), get_node_timers_interface(),
get_clock(), 1ms,
std::bind(&TimerNode::Timer2Callback, this));
Expand Down Expand Up @@ -76,14 +82,14 @@ class TimerNode : public rclcpp::Node
private:
void Timer1Callback()
{
RCLCPP_DEBUG(this->get_logger(), "Timer 1!");
cnt1_++;
RCLCPP_DEBUG(this->get_logger(), "Timer 1! (%d)", cnt1_);
}

void Timer2Callback()
{
RCLCPP_DEBUG(this->get_logger(), "Timer 2!");
cnt2_++;
RCLCPP_DEBUG(this->get_logger(), "Timer 2! (%d)", cnt2_);
}

rclcpp::TimerBase::SharedPtr timer1_;
Expand Down Expand Up @@ -200,11 +206,18 @@ class TestTimerCancelBehavior : public ::testing::Test
ASSERT_TRUE(param_client->wait_for_service(5s));

auto set_parameters_results = param_client->set_parameters(
{rclcpp::Parameter("use_sim_time", false)});
{rclcpp::Parameter("use_sim_time", true)});
for (auto & result : set_parameters_results) {
ASSERT_TRUE(result.successful);
}

// Check if the clock type is simulation time
EXPECT_EQ(RCL_ROS_TIME, node->get_clock()->get_clock_type());

// Create timers
this->node->CreateTimer1();
this->node->CreateTimer2();

// Run standalone thread to publish clock time
sim_clock_node = std::make_shared<ClockPublisher>();

Expand Down Expand Up @@ -233,7 +246,10 @@ class TestTimerCancelBehavior : public ::testing::Test
T executor;
};

TYPED_TEST_SUITE(TestTimerCancelBehavior, ExecutorTypes, ExecutorTypeNames);
// TODO(@fujitatomoya): this test excludes EventExecutor because it does not
// support simulation time used for this test to relax the racy condition.
// See more details for https://github.com/ros2/rclcpp/issues/2457.
TYPED_TEST_SUITE(TestTimerCancelBehavior, MainExecutorTypes, ExecutorTypeNames);

TYPED_TEST(TestTimerCancelBehavior, testTimer1CancelledWithExecutorSpin) {
// Validate that cancelling one timer yields no change in behavior for other
Expand Down

0 comments on commit 8498c1c

Please sign in to comment.