Add subscription creation test
This commit is contained in:
parent
6caaa51764
commit
cc8187e55b
5 changed files with 111 additions and 2 deletions
|
@ -23,8 +23,17 @@ if(BUILD_TESTING)
|
||||||
rclcpp
|
rclcpp
|
||||||
std_msgs
|
std_msgs
|
||||||
)
|
)
|
||||||
|
add_executable(test_subscription
|
||||||
|
test/test_subscription.cpp
|
||||||
|
)
|
||||||
|
ament_target_dependencies(test_subscription
|
||||||
|
rclcpp
|
||||||
|
std_msgs
|
||||||
|
)
|
||||||
|
|
||||||
install(TARGETS
|
install(TARGETS
|
||||||
test_publisher
|
test_publisher
|
||||||
|
test_subscription
|
||||||
DESTINATION lib/${PROJECT_NAME}
|
DESTINATION lib/${PROJECT_NAME}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -33,6 +42,7 @@ if(BUILD_TESTING)
|
||||||
# Run each test in its own pytest invocation
|
# Run each test in its own pytest invocation
|
||||||
set(_tracetools_test_pytest_tests
|
set(_tracetools_test_pytest_tests
|
||||||
test/test_publisher.py
|
test/test_publisher.py
|
||||||
|
test/test_subscription.py
|
||||||
)
|
)
|
||||||
|
|
||||||
foreach(_test_path ${_tracetools_test_pytest_tests})
|
foreach(_test_path ${_tracetools_test_pytest_tests})
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
class PubNode : public rclcpp::Node
|
class PubNode : public rclcpp::Node
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
PubNode() : Node("pub_node")
|
PubNode(rclcpp::NodeOptions options) : Node("pub_node", options)
|
||||||
{
|
{
|
||||||
pub_ = this->create_publisher<std_msgs::msg::String>(
|
pub_ = this->create_publisher<std_msgs::msg::String>(
|
||||||
"the_topic",
|
"the_topic",
|
||||||
|
@ -21,7 +21,7 @@ int main(int argc, char* argv[])
|
||||||
rclcpp::init(argc, argv);
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
rclcpp::executors::SingleThreadedExecutor exec;
|
rclcpp::executors::SingleThreadedExecutor exec;
|
||||||
auto pub_node = std::make_shared<PubNode>();
|
auto pub_node = std::make_shared<PubNode>(rclcpp::NodeOptions());
|
||||||
exec.add_node(pub_node);
|
exec.add_node(pub_node);
|
||||||
|
|
||||||
printf("spinning once\n");
|
printf("spinning once\n");
|
||||||
|
|
|
@ -51,5 +51,6 @@ class TestPublisher(unittest.TestCase):
|
||||||
|
|
||||||
shutil.rmtree(path)
|
shutil.rmtree(path)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
unittest.main()
|
unittest.main()
|
||||||
|
|
41
tracetools_test/test/test_subscription.cpp
Normal file
41
tracetools_test/test/test_subscription.cpp
Normal file
|
@ -0,0 +1,41 @@
|
||||||
|
#include <memory>
|
||||||
|
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
#include "std_msgs/msg/string.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
class SubNode : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
SubNode(rclcpp::NodeOptions options) : Node("sub_node", options)
|
||||||
|
{
|
||||||
|
sub_ = this->create_subscription<std_msgs::msg::String>(
|
||||||
|
"the_topic",
|
||||||
|
rclcpp::QoS(10),
|
||||||
|
std::bind(&SubNode::callback, this, std::placeholders::_1));
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void callback(const std_msgs::msg::String::SharedPtr msg)
|
||||||
|
{
|
||||||
|
// Nothing
|
||||||
|
(void)msg;
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char* argv[])
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
|
rclcpp::executors::SingleThreadedExecutor exec;
|
||||||
|
auto sub_node = std::make_shared<SubNode>(rclcpp::NodeOptions());
|
||||||
|
exec.add_node(sub_node);
|
||||||
|
|
||||||
|
printf("spinning once\n");
|
||||||
|
exec.spin_once();
|
||||||
|
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
57
tracetools_test/test/test_subscription.py
Normal file
57
tracetools_test/test/test_subscription.py
Normal file
|
@ -0,0 +1,57 @@
|
||||||
|
import time
|
||||||
|
import shutil
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch import LaunchIntrospector
|
||||||
|
from launch import LaunchService
|
||||||
|
|
||||||
|
from launch_ros import get_default_launch_description
|
||||||
|
import launch_ros.actions
|
||||||
|
import unittest
|
||||||
|
from tracetools_analysis.test.utils import get_trace_event_names
|
||||||
|
from tracetools_trace.tools.lttng import (
|
||||||
|
lttng_setup,
|
||||||
|
lttng_start,
|
||||||
|
lttng_stop,
|
||||||
|
lttng_destroy,
|
||||||
|
)
|
||||||
|
|
||||||
|
PKG = 'tracetools_test'
|
||||||
|
|
||||||
|
subscription_creation_events = [
|
||||||
|
'ros2:rcl_subscription_init',
|
||||||
|
'ros2:rclcpp_subscription_callback_added',
|
||||||
|
]
|
||||||
|
|
||||||
|
class TestSubscription(unittest.TestCase):
|
||||||
|
|
||||||
|
def test_creation(self):
|
||||||
|
session_name = f'session-test-subscription-creation-{time.strftime("%Y%m%d%H%M%S")}'
|
||||||
|
path = '/tmp/' + session_name
|
||||||
|
print(f'trace directory: {path}')
|
||||||
|
|
||||||
|
lttng_setup(session_name, path, ros_events=subscription_creation_events, kernel_events=None)
|
||||||
|
lttng_start(session_name)
|
||||||
|
|
||||||
|
ld = LaunchDescription([
|
||||||
|
launch_ros.actions.Node(
|
||||||
|
package=PKG, node_executable='test_subscription', output='screen'),
|
||||||
|
])
|
||||||
|
ls = LaunchService()
|
||||||
|
ls.include_launch_description(get_default_launch_description())
|
||||||
|
ls.include_launch_description(ld)
|
||||||
|
|
||||||
|
exit_code = ls.run()
|
||||||
|
self.assertEqual(exit_code, 0)
|
||||||
|
|
||||||
|
lttng_stop(session_name)
|
||||||
|
lttng_destroy(session_name)
|
||||||
|
|
||||||
|
trace_events = get_trace_event_names(path)
|
||||||
|
print(f'trace_events: {trace_events}')
|
||||||
|
self.assertListEqual(subscription_creation_events, list(trace_events))
|
||||||
|
|
||||||
|
shutil.rmtree(path)
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
unittest.main()
|
Loading…
Add table
Add a link
Reference in a new issue