Add timer test
This commit is contained in:
parent
d198de3958
commit
d6fec8171c
3 changed files with 91 additions and 0 deletions
|
@ -44,12 +44,20 @@ if(BUILD_TESTING)
|
|||
rclcpp
|
||||
std_msgs
|
||||
)
|
||||
add_executable(test_timer
|
||||
src/test_timer.cpp
|
||||
)
|
||||
ament_target_dependencies(test_timer
|
||||
rclcpp
|
||||
std_msgs
|
||||
)
|
||||
|
||||
install(TARGETS
|
||||
test_publisher
|
||||
test_subscription
|
||||
test_ping
|
||||
test_pong
|
||||
test_timer
|
||||
DESTINATION lib/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
|
@ -61,6 +69,7 @@ if(BUILD_TESTING)
|
|||
test/test_publisher.py
|
||||
test/test_subscription.py
|
||||
test/test_subscription_callback.py
|
||||
test/test_timer.py
|
||||
)
|
||||
|
||||
foreach(_test_path ${_tracetools_test_pytest_tests})
|
||||
|
|
47
tracetools_test/src/test_timer.cpp
Normal file
47
tracetools_test/src/test_timer.cpp
Normal file
|
@ -0,0 +1,47 @@
|
|||
#include <chrono>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
|
||||
class TimerNode : public rclcpp::Node
|
||||
{
|
||||
public:
|
||||
TimerNode(rclcpp::NodeOptions options) : Node("timer_node", options)
|
||||
{
|
||||
is_done_ = false;
|
||||
timer_ = this->create_wall_timer(
|
||||
1ms,
|
||||
std::bind(&TimerNode::timer_callback, this));
|
||||
}
|
||||
|
||||
private:
|
||||
void timer_callback()
|
||||
{
|
||||
if (is_done_) {
|
||||
rclcpp::shutdown();
|
||||
} else {
|
||||
is_done_ = true;
|
||||
}
|
||||
}
|
||||
|
||||
rclcpp::TimerBase::SharedPtr timer_;
|
||||
bool is_done_;
|
||||
};
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
|
||||
rclcpp::executors::SingleThreadedExecutor exec;
|
||||
auto timer_node = std::make_shared<TimerNode>(rclcpp::NodeOptions());
|
||||
exec.add_node(timer_node);
|
||||
|
||||
printf("spinning\n");
|
||||
exec.spin();
|
||||
|
||||
// Will actually be called inside the timer's callback
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
35
tracetools_test/test/test_timer.py
Normal file
35
tracetools_test/test/test_timer.py
Normal file
|
@ -0,0 +1,35 @@
|
|||
import unittest
|
||||
from tracetools_test.utils import (
|
||||
get_trace_event_names,
|
||||
run_and_trace,
|
||||
cleanup_trace,
|
||||
)
|
||||
|
||||
PKG = 'tracetools_test'
|
||||
|
||||
timer_events = [
|
||||
'ros2:rcl_timer_init',
|
||||
'ros2:rclcpp_timer_callback_added',
|
||||
'ros2:rclcpp_timer_callback_start',
|
||||
'ros2:rclcpp_timer_callback_end',
|
||||
]
|
||||
|
||||
class TestTimer(unittest.TestCase):
|
||||
|
||||
def test_all(self):
|
||||
session_name_prefix = 'session-test-timer-all'
|
||||
base_path = '/tmp'
|
||||
test_nodes = ['test_timer']
|
||||
|
||||
exit_code, full_path = run_and_trace(base_path, session_name_prefix, timer_events, None, PKG, test_nodes)
|
||||
self.assertEqual(exit_code, 0)
|
||||
|
||||
trace_events = get_trace_event_names(full_path)
|
||||
print(f'trace_events: {trace_events}')
|
||||
self.assertSetEqual(set(timer_events), trace_events)
|
||||
|
||||
cleanup_trace(full_path)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
unittest.main()
|
Loading…
Add table
Add a link
Reference in a new issue