Skip to content

Commit 198c82c

Browse files
authored
enable simulation clock for timer canceling test. (#2458)
* enable simulation clock for timer canceling test. Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com> * move MainExecutorTypes to test_executors_timer_cancel_behavior.cpp. Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com> --------- Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
1 parent 3e470d5 commit 198c82c

File tree

1 file changed

+28
-6
lines changed

1 file changed

+28
-6
lines changed

rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp

+28-6
Original file line numberDiff line numberDiff line change
@@ -35,14 +35,20 @@ class TimerNode : public rclcpp::Node
3535
public:
3636
explicit TimerNode(std::string subname)
3737
: Node("timer_node", subname)
38+
{
39+
}
40+
41+
void CreateTimer1()
3842
{
3943
timer1_ = rclcpp::create_timer(
4044
this->get_node_base_interface(), get_node_timers_interface(),
4145
get_clock(), 1ms,
4246
std::bind(&TimerNode::Timer1Callback, this));
47+
}
4348

44-
timer2_ =
45-
rclcpp::create_timer(
49+
void CreateTimer2()
50+
{
51+
timer2_ = rclcpp::create_timer(
4652
this->get_node_base_interface(), get_node_timers_interface(),
4753
get_clock(), 1ms,
4854
std::bind(&TimerNode::Timer2Callback, this));
@@ -76,14 +82,14 @@ class TimerNode : public rclcpp::Node
7682
private:
7783
void Timer1Callback()
7884
{
79-
RCLCPP_DEBUG(this->get_logger(), "Timer 1!");
8085
cnt1_++;
86+
RCLCPP_DEBUG(this->get_logger(), "Timer 1! (%d)", cnt1_);
8187
}
8288

8389
void Timer2Callback()
8490
{
85-
RCLCPP_DEBUG(this->get_logger(), "Timer 2!");
8691
cnt2_++;
92+
RCLCPP_DEBUG(this->get_logger(), "Timer 2! (%d)", cnt2_);
8793
}
8894

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

202208
auto set_parameters_results = param_client->set_parameters(
203-
{rclcpp::Parameter("use_sim_time", false)});
209+
{rclcpp::Parameter("use_sim_time", true)});
204210
for (auto & result : set_parameters_results) {
205211
ASSERT_TRUE(result.successful);
206212
}
207213

214+
// Check if the clock type is simulation time
215+
EXPECT_EQ(RCL_ROS_TIME, node->get_clock()->get_clock_type());
216+
217+
// Create timers
218+
this->node->CreateTimer1();
219+
this->node->CreateTimer2();
220+
208221
// Run standalone thread to publish clock time
209222
sim_clock_node = std::make_shared<ClockPublisher>();
210223

@@ -233,7 +246,16 @@ class TestTimerCancelBehavior : public ::testing::Test
233246
T executor;
234247
};
235248

236-
TYPED_TEST_SUITE(TestTimerCancelBehavior, ExecutorTypes, ExecutorTypeNames);
249+
using MainExecutorTypes =
250+
::testing::Types<
251+
rclcpp::executors::SingleThreadedExecutor,
252+
rclcpp::executors::MultiThreadedExecutor,
253+
rclcpp::executors::StaticSingleThreadedExecutor>;
254+
255+
// TODO(@fujitatomoya): this test excludes EventExecutor because it does not
256+
// support simulation time used for this test to relax the racy condition.
257+
// See more details for https://github.com/ros2/rclcpp/issues/2457.
258+
TYPED_TEST_SUITE(TestTimerCancelBehavior, MainExecutorTypes, ExecutorTypeNames);
237259

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

0 commit comments

Comments
 (0)