Merge branch '55-update-after-new-intra-process-communication' into 'master'

Resolve "Update after new intra-process communication"

Closes #55

See merge request micro-ROS/ros_tracing/ros2_tracing!108
This commit is contained in:
Christophe Bedard 2019-11-17 20:12:19 +00:00
commit 22c7ce7d23
16 changed files with 386 additions and 332 deletions

View file

@ -100,13 +100,26 @@ TRACEPOINT_EVENT(
TRACEPOINT_EVENT( TRACEPOINT_EVENT(
TRACEPOINT_PROVIDER, TRACEPOINT_PROVIDER,
rclcpp_subscription_callback_added, rclcpp_subscription_init,
TP_ARGS( TP_ARGS(
const void *, subscription_handle_arg, const void *, subscription_handle_arg,
const void *, callback_arg const void *, subscription_arg
), ),
TP_FIELDS( TP_FIELDS(
ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg)
ctf_integer_hex(const void *, subscription, subscription_arg)
)
)
TRACEPOINT_EVENT(
TRACEPOINT_PROVIDER,
rclcpp_subscription_callback_added,
TP_ARGS(
const void *, subscription_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, subscription, subscription_arg)
ctf_integer_hex(const void *, callback, callback_arg) ctf_integer_hex(const void *, callback, callback_arg)
) )
) )

View file

@ -80,12 +80,20 @@ DECLARE_TRACEPOINT(
const char * topic_name, const char * topic_name,
const size_t queue_depth) const size_t queue_depth)
/**
* tp: rclcpp_subscription_init
*/
DECLARE_TRACEPOINT(
rclcpp_subscription_init,
const void * subscription_handle,
const void * subscription)
/** /**
* tp: rclcpp_subscription_callback_added * tp: rclcpp_subscription_callback_added
*/ */
DECLARE_TRACEPOINT( DECLARE_TRACEPOINT(
rclcpp_subscription_callback_added, rclcpp_subscription_callback_added,
const void * subscription_handle, const void * subscription,
const void * callback) const void * callback)
/** /**

View file

@ -19,7 +19,7 @@
#if defined(TRACETOOLS_LTTNG_ENABLED) #if defined(TRACETOOLS_LTTNG_ENABLED)
# include "tracetools/tp_call.h" # include "tracetools/tp_call.h"
# define CONDITIONAL_TP(...) \ # define CONDITIONAL_TP(...) \
tracepoint(__VA_ARGS__) tracepoint(TRACEPOINT_PROVIDER, __VA_ARGS__)
#else #else
# define CONDITIONAL_TP(...) # define CONDITIONAL_TP(...)
#endif #endif
@ -46,7 +46,6 @@ void TRACEPOINT(
const void * context_handle) const void * context_handle)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_init, rcl_init,
context_handle, context_handle,
tracetools_VERSION); tracetools_VERSION);
@ -60,7 +59,6 @@ void TRACEPOINT(
const char * node_namespace) const char * node_namespace)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_node_init, rcl_node_init,
node_handle, node_handle,
rmw_handle, rmw_handle,
@ -77,7 +75,6 @@ void TRACEPOINT(
const size_t queue_depth) const size_t queue_depth)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_publisher_init, rcl_publisher_init,
publisher_handle, publisher_handle,
node_handle, node_handle,
@ -95,7 +92,6 @@ void TRACEPOINT(
const size_t queue_depth) const size_t queue_depth)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_subscription_init, rcl_subscription_init,
subscription_handle, subscription_handle,
node_handle, node_handle,
@ -105,14 +101,24 @@ void TRACEPOINT(
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_subscription_callback_added, rclcpp_subscription_init,
const void * subscription_handle, const void * subscription_handle,
const void * subscription)
{
CONDITIONAL_TP(
rclcpp_subscription_init,
subscription_handle,
subscription);
}
void TRACEPOINT(
rclcpp_subscription_callback_added,
const void * subscription,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rclcpp_subscription_callback_added, rclcpp_subscription_callback_added,
subscription_handle, subscription,
callback); callback);
} }
@ -124,7 +130,6 @@ void TRACEPOINT(
const char * service_name) const char * service_name)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_service_init, rcl_service_init,
service_handle, service_handle,
node_handle, node_handle,
@ -138,7 +143,6 @@ void TRACEPOINT(
const void * callback) const void * callback)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rclcpp_service_callback_added, rclcpp_service_callback_added,
service_handle, service_handle,
callback); callback);
@ -152,7 +156,6 @@ void TRACEPOINT(
const char * service_name) const char * service_name)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_client_init, rcl_client_init,
client_handle, client_handle,
node_handle, node_handle,
@ -166,7 +169,6 @@ void TRACEPOINT(
int64_t period) int64_t period)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rcl_timer_init, rcl_timer_init,
timer_handle, timer_handle,
period); period);
@ -178,7 +180,6 @@ void TRACEPOINT(
const void * callback) const void * callback)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_added, rclcpp_timer_callback_added,
timer_handle, timer_handle,
callback); callback);
@ -190,7 +191,6 @@ void TRACEPOINT(
const char * function_symbol) const char * function_symbol)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
rclcpp_callback_register, rclcpp_callback_register,
callback, callback,
function_symbol); function_symbol);
@ -202,7 +202,6 @@ void TRACEPOINT(
const bool is_intra_process) const bool is_intra_process)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
callback_start, callback_start,
callback, callback,
(is_intra_process ? 1 : 0)); (is_intra_process ? 1 : 0));
@ -213,7 +212,6 @@ void TRACEPOINT(
const void * callback) const void * callback)
{ {
CONDITIONAL_TP( CONDITIONAL_TP(
ros2,
callback_end, callback_end,
callback); callback);
} }

View file

@ -47,15 +47,6 @@ if(BUILD_TESTING)
tracetools tracetools
) )
target_link_libraries(test_publisher "${RDYNAMIC_FLAG}") target_link_libraries(test_publisher "${RDYNAMIC_FLAG}")
add_executable(test_subscription
src/test_subscription.cpp
)
ament_target_dependencies(test_subscription
rclcpp
std_msgs
tracetools
)
target_link_libraries(test_subscription "${RDYNAMIC_FLAG}")
add_executable(test_intra add_executable(test_intra
src/test_intra.cpp src/test_intra.cpp
) )
@ -127,7 +118,6 @@ if(BUILD_TESTING)
test_service test_service
test_service_ping test_service_ping
test_service_pong test_service_pong
test_subscription
test_timer test_timer
DESTINATION lib/${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME}
) )
@ -141,13 +131,12 @@ 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_intra.py test/test_intra.py
test/test_node.py test/test_node.py
test/test_publisher.py test/test_publisher.py
test/test_service.py test/test_service.py
test/test_service_callback.py test/test_service_callback.py
test/test_subscription.py test/test_subscription.py
test/test_subscription_callback.py
test/test_timer.py test/test_timer.py
) )

View file

@ -23,6 +23,7 @@ using namespace std::chrono_literals;
#define NODE_NAME "test_ping" #define NODE_NAME "test_ping"
#define SUB_TOPIC_NAME "pong" #define SUB_TOPIC_NAME "pong"
#define PUB_TOPIC_NAME "ping" #define PUB_TOPIC_NAME "ping"
#define QUEUE_DEPTH 10
class PingNode : public rclcpp::Node class PingNode : public rclcpp::Node
{ {
@ -32,11 +33,11 @@ public:
{ {
sub_ = this->create_subscription<std_msgs::msg::String>( sub_ = this->create_subscription<std_msgs::msg::String>(
SUB_TOPIC_NAME, SUB_TOPIC_NAME,
rclcpp::QoS(10), rclcpp::QoS(QUEUE_DEPTH),
std::bind(&PingNode::callback, this, std::placeholders::_1)); std::bind(&PingNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>( pub_ = this->create_publisher<std_msgs::msg::String>(
PUB_TOPIC_NAME, PUB_TOPIC_NAME,
rclcpp::QoS(10)); rclcpp::QoS(QUEUE_DEPTH));
timer_ = this->create_wall_timer( timer_ = this->create_wall_timer(
500ms, 500ms,
std::bind(&PingNode::timer_callback, this)); std::bind(&PingNode::timer_callback, this));

View file

@ -1,59 +0,0 @@
// Copyright 2019 Robert Bosch GmbH
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#define NODE_NAME "test_subscription"
#define TOPIC_NAME "the_topic"
#define QUEUE_DEPTH 10
class SubNode : public rclcpp::Node
{
public:
explicit SubNode(rclcpp::NodeOptions options)
: Node(NODE_NAME, options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
TOPIC_NAME,
rclcpp::QoS(QUEUE_DEPTH),
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;
}

View file

@ -25,108 +25,122 @@ class TestIntra(TraceTestCase):
session_name_prefix='session-test-intra', session_name_prefix='session-test-intra',
events_ros=[ events_ros=[
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
'ros2:rclcpp_subscription_init',
'ros2:rclcpp_subscription_callback_added', 'ros2:rclcpp_subscription_callback_added',
'ros2:callback_start', 'ros2:callback_start',
'ros2:callback_end', 'ros2:callback_end',
], ],
nodes=['test_intra'] nodes=['test_intra'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. node_init before pub_init) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check sub_init for normal and intraprocess events print('EVENTS: ', self._events)
sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init')
sub_init_normal_events = self.get_events_with_field_value( # Check rcl_subscription_init events
rcl_sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init')
rcl_sub_init_topic_events = self.get_events_with_field_value(
'topic_name', 'topic_name',
'/the_topic', '/the_topic',
sub_init_events) rcl_sub_init_events,
sub_init_intra_events = self.get_events_with_field_value( )
'topic_name', # Only 1 for our given topic
'/the_topic/_intra',
sub_init_events)
self.assertNumEventsEqual( self.assertNumEventsEqual(
sub_init_normal_events, rcl_sub_init_topic_events,
1, 1,
'none or more than 1 sub init event for normal sub') 'none or more than 1 rcl_sub_init event for the topic',
self.assertNumEventsEqual( )
sub_init_intra_events,
1,
'none or more than 1 sub init event for intra sub')
# Get subscription handles for normal & intra subscriptions # Get subscription handle
sub_init_normal_event = sub_init_normal_events[0] rcl_sub_init_topic_event = rcl_sub_init_topic_events[0]
# Note: sub handle linked to "normal" topic is the one actually linked to intra callback sub_handle_intra = self.get_field(rcl_sub_init_topic_event, 'subscription_handle')
sub_handle_intra = self.get_field(sub_init_normal_event, 'subscription_handle')
print(f'sub_handle_intra: {sub_handle_intra}')
# Get corresponding callback handle # Check rclcpp_subscription_init events
# Callback handle rclcpp_sub_init_events = self.get_events_with_name('ros2:rclcpp_subscription_init')
callback_added_events = self.get_events_with_field_value( rclcpp_sub_init_topic_events = self.get_events_with_field_value(
'subscription_handle', 'subscription_handle',
sub_handle_intra, sub_handle_intra,
self.get_events_with_name( rclcpp_sub_init_events,
'ros2:rclcpp_subscription_callback_added')) )
# Should have 2 events for the given subscription handle
# (Subscription and SubscriptionIntraProcess)
self.assertNumEventsEqual( self.assertNumEventsEqual(
callback_added_events, rclcpp_sub_init_topic_events,
1, 2,
'none or more than 1 callback added event') 'number of rclcpp_sub_init events for the topic not equal to 2',
callback_added_event = callback_added_events[0] )
callback_handle_intra = self.get_field(callback_added_event, 'callback')
# Get the 2 subscription pointers
events = rclcpp_sub_init_topic_events
subscription_pointers = [self.get_field(e, 'subscription') for e in events]
# Get the corresponding callback pointers
rclcpp_sub_callback_added_events = self.get_events_with_name(
'ros2:rclcpp_subscription_callback_added',
)
rclcpp_sub_callback_added_topic_events = self.get_events_with_field_value(
'subscription',
subscription_pointers,
rclcpp_sub_callback_added_events,
)
events = rclcpp_sub_callback_added_topic_events
callback_pointers = [self.get_field(e, 'callback') for e in events]
# Get corresponding callback start/end pairs # Get corresponding callback start/end pairs
start_events = self.get_events_with_name('ros2:callback_start') start_events = self.get_events_with_name('ros2:callback_start')
end_events = self.get_events_with_name('ros2:callback_end') end_events = self.get_events_with_name('ros2:callback_end')
# Should still have at least two start:end pairs (1 normal + 1 intra) # Should have at least one start:end pair
self.assertNumEventsGreaterEqual( self.assertNumEventsGreaterEqual(
start_events, start_events,
2, 1,
'does not have at least 2 callback start events') 'does not have at least 1 callback start event')
self.assertNumEventsGreaterEqual( self.assertNumEventsGreaterEqual(
end_events, end_events,
2, 1,
'does not have at least 2 callback end events') 'does not have at least 1 callback end event')
start_events_intra = self.get_events_with_field_value( start_events_topic = self.get_events_with_field_value(
'callback', 'callback',
callback_handle_intra, callback_pointers,
start_events) start_events)
end_events_intra = self.get_events_with_field_value( end_events_topic = self.get_events_with_field_value(
'callback', 'callback',
callback_handle_intra, callback_pointers,
end_events) end_events)
self.assertNumEventsGreaterEqual( self.assertNumEventsGreaterEqual(
start_events_topic,
1,
'no callback_start event found for topic')
self.assertNumEventsGreaterEqual(
end_events_topic,
1,
'no callback_end found event for topic')
# Check for is_intra_process field value of 1/true
start_events_intra = self.get_events_with_field_value(
'is_intra_process',
1,
start_events_topic,
)
# Should have one event
self.assertNumEventsEqual(
start_events_intra, start_events_intra,
1, 1,
'no intra start event') 'none or more than 1 callback_start event for intra-process topic',
self.assertNumEventsGreaterEqual( )
# As a sanity check, make sure its callback pointer has a corresponding callback_end event
callback_pointer_intra = self.get_field(start_events_intra[0], 'callback')
end_events_intra = self.get_events_with_field_value(
'callback',
callback_pointer_intra,
end_events_topic,
)
self.assertNumEventsEqual(
end_events_intra, end_events_intra,
1, 1,
'no intra end event') 'none or more than 1 callback_end event for intra-process topic',
)
# Check is_intra_process field value
start_event_intra = start_events_intra[0]
self.assertFieldEquals(
start_event_intra,
'is_intra_process',
1,
'is_intra_process field value not valid for intra callback')
# Also check that the other callback_start event (normal one) has the right field value
start_events_not_intra = self.get_events_with_field_not_value(
'callback',
callback_handle_intra,
start_events)
self.assertNumEventsGreaterEqual(
start_events_not_intra,
1,
'no normal start event')
start_event_not_intra = start_events_not_intra[0]
self.assertFieldEquals(
start_event_not_intra,
'is_intra_process',
0,
'is_intra_process field value not valid for normal callback')
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -30,12 +30,12 @@ class TestNode(TraceTestCase):
'ros2:rcl_init', 'ros2:rcl_init',
'ros2:rcl_node_init', 'ros2:rcl_node_init',
], ],
nodes=['test_publisher'] nodes=['test_publisher'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. init before node_init) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
rcl_init_events = self.get_events_with_name('ros2:rcl_init') rcl_init_events = self.get_events_with_name('ros2:rcl_init')
@ -56,7 +56,8 @@ class TestNode(TraceTestCase):
for node_name in self._nodes: for node_name in self._nodes:
self.assertTrue( self.assertTrue(
node_name in node_name_fields, node_name in node_name_fields,
f'cannot find node_init event for node name: {node_name} ({node_name_fields})') f'cannot find node_init event for node name: {node_name} ({node_name_fields})',
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -27,19 +27,20 @@ class TestPublisher(TraceTestCase):
'ros2:rcl_node_init', 'ros2:rcl_node_init',
'ros2:rcl_publisher_init', 'ros2:rcl_publisher_init',
], ],
nodes=['test_publisher'] nodes=['test_publisher'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. node_init before pub_init) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
pub_init_events = self.get_events_with_name('ros2:rcl_publisher_init') pub_init_events = self.get_events_with_name('ros2:rcl_publisher_init')
for event in pub_init_events: for event in pub_init_events:
self.assertValidHandle( self.assertValidHandle(
event, event,
['publisher_handle', 'node_handle', 'rmw_publisher_handle']) ['publisher_handle', 'node_handle', 'rmw_publisher_handle'],
)
self.assertValidQueueDepth(event, 'queue_depth') self.assertValidQueueDepth(event, 'queue_depth')
self.assertStringFieldNotEmpty(event, 'topic_name') self.assertStringFieldNotEmpty(event, 'topic_name')
@ -48,11 +49,13 @@ class TestPublisher(TraceTestCase):
test_pub_init_topic_events = self.get_events_with_field_value( test_pub_init_topic_events = self.get_events_with_field_value(
'topic_name', 'topic_name',
'/the_topic', '/the_topic',
test_pub_init_events) test_pub_init_events,
)
self.assertNumEventsEqual( self.assertNumEventsEqual(
test_pub_init_topic_events, test_pub_init_topic_events,
1, 1,
'none or more than 1 pub_init even for test topic') 'none or more than 1 rcl_pub_init even for test topic',
)
# Check queue_depth value # Check queue_depth value
test_pub_init_topic_event = test_pub_init_topic_events[0] test_pub_init_topic_event = test_pub_init_topic_events[0]
@ -60,23 +63,27 @@ class TestPublisher(TraceTestCase):
test_pub_init_topic_event, test_pub_init_topic_event,
'queue_depth', 'queue_depth',
10, 10,
'pub_init event does not have expected queue depth value') 'pub_init event does not have expected queue depth value',
)
# Check that the node handle matches with the node_init event # Check that the node handle matches with the node_init event
node_init_events = self.get_events_with_name('ros2:rcl_node_init') node_init_events = self.get_events_with_name('ros2:rcl_node_init')
test_pub_node_init_events = self.get_events_with_procname( test_pub_node_init_events = self.get_events_with_procname(
'test_publisher', 'test_publisher',
node_init_events) node_init_events,
)
self.assertNumEventsEqual( self.assertNumEventsEqual(
test_pub_node_init_events, test_pub_node_init_events,
1, 1,
'none or more than 1 node_init event') 'none or more than 1 node_init event',
)
test_pub_node_init_event = test_pub_node_init_events[0] test_pub_node_init_event = test_pub_node_init_events[0]
self.assertMatchingField( self.assertMatchingField(
test_pub_node_init_event, test_pub_node_init_event,
'node_handle', 'node_handle',
None, None,
test_pub_init_events) test_pub_init_events,
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -28,20 +28,20 @@ class TestService(TraceTestCase):
'ros2:rcl_service_init', 'ros2:rcl_service_init',
'ros2:rclcpp_service_callback_added', 'ros2:rclcpp_service_callback_added',
], ],
nodes=['test_service'] nodes=['test_service'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. service_init before callback_added) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
srv_init_events = self.get_events_with_name('ros2:rcl_service_init') srv_init_events = self.get_events_with_name('ros2:rcl_service_init')
callback_added_events = self.get_events_with_name('ros2:rclcpp_service_callback_added')
for event in srv_init_events: for event in srv_init_events:
self.assertValidHandle(event, ['service_handle', 'node_handle', 'rmw_service_handle']) self.assertValidHandle(event, ['service_handle', 'node_handle', 'rmw_service_handle'])
self.assertStringFieldNotEmpty(event, 'service_name') self.assertStringFieldNotEmpty(event, 'service_name')
callback_added_events = self.get_events_with_name('ros2:rclcpp_service_callback_added')
for event in callback_added_events: for event in callback_added_events:
self.assertValidHandle(event, ['service_handle', 'callback']) self.assertValidHandle(event, ['service_handle', 'callback'])
@ -50,27 +50,32 @@ class TestService(TraceTestCase):
event_service_names = self.get_events_with_field_value( event_service_names = self.get_events_with_field_value(
'service_name', 'service_name',
'/the_service', '/the_service',
test_srv_init_events) test_srv_init_events,
)
self.assertGreaterEqual( self.assertGreaterEqual(
len(event_service_names), len(event_service_names),
1, 1,
'cannot find test service name') 'cannot find test service name',
)
# Check that the node handle matches the node_init event # Check that the node handle matches the node_init event
node_init_events = self.get_events_with_name('ros2:rcl_node_init') node_init_events = self.get_events_with_name('ros2:rcl_node_init')
test_srv_node_init_events = self.get_events_with_procname( test_srv_node_init_events = self.get_events_with_procname(
'test_service', 'test_service',
node_init_events) node_init_events,
)
self.assertNumEventsEqual( self.assertNumEventsEqual(
test_srv_node_init_events, test_srv_node_init_events,
1, 1,
'none or more than 1 node_init event') 'none or more than 1 rcl_node_init event',
)
test_srv_node_init_event = test_srv_node_init_events[0] test_srv_node_init_event = test_srv_node_init_events[0]
self.assertMatchingField( self.assertMatchingField(
test_srv_node_init_event, test_srv_node_init_event,
'node_handle', 'node_handle',
'ros2:rcl_service_init', 'ros2:rcl_service_init',
test_srv_init_events) test_srv_init_events,
)
# Check that the service handles match # Check that the service handles match
test_event_srv_init = event_service_names[0] test_event_srv_init = event_service_names[0]
@ -78,7 +83,8 @@ class TestService(TraceTestCase):
test_event_srv_init, test_event_srv_init,
'service_handle', 'service_handle',
None, None,
callback_added_events) callback_added_events,
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -27,15 +27,17 @@ class TestServiceCallback(TraceTestCase):
'ros2:callback_start', 'ros2:callback_start',
'ros2:callback_end', 'ros2:callback_end',
], ],
nodes=['test_service_ping', 'test_service_pong'] nodes=['test_service_ping', 'test_service_pong'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. start before end) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
start_events = self.get_events_with_name('ros2:callback_start') start_events = self.get_events_with_name('ros2:callback_start')
end_events = self.get_events_with_name('ros2:callback_end')
for event in start_events: for event in start_events:
self.assertValidHandle(event, 'callback') self.assertValidHandle(event, 'callback')
# Should not be 1 for services (yet) # Should not be 1 for services (yet)
@ -43,24 +45,25 @@ class TestServiceCallback(TraceTestCase):
event, event,
'is_intra_process', 'is_intra_process',
0, 0,
'invalid value for is_intra_process') 'invalid value for is_intra_process',
)
end_events = self.get_events_with_name('ros2:callback_end')
for event in end_events: for event in end_events:
self.assertValidHandle(event, 'callback') self.assertValidHandle(event, 'callback')
# Check that there is at least a start/end pair for each node # Check that there is at least 1 start/end pair for each node
for node in self._nodes: for node in self._nodes:
test_start_events = self.get_events_with_procname(node, start_events) test_start_events = self.get_events_with_procname(node, start_events)
test_end_events = self.get_events_with_procname(node, end_events) test_end_events = self.get_events_with_procname(node, end_events)
self.assertGreater( self.assertGreater(
len(test_start_events), len(test_start_events),
0, 0,
f'no start_callback events for node: {node}') f'no start_callback events for node: {node}',
)
self.assertGreater( self.assertGreater(
len(test_end_events), len(test_end_events),
0, 0,
f'no end_callback events for node: {node}') f'no end_callback events for node: {node}',
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -1,4 +1,5 @@
# Copyright 2019 Robert Bosch GmbH # Copyright 2019 Robert Bosch GmbH
# Copyright 2019 Apex.AI, Inc.
# #
# Licensed under the Apache License, Version 2.0 (the "License"); # Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License. # you may not use this file except in compliance with the License.
@ -22,70 +23,166 @@ class TestSubscription(TraceTestCase):
def __init__(self, *args) -> None: def __init__(self, *args) -> None:
super().__init__( super().__init__(
*args, *args,
session_name_prefix='session-test-subscription-creation', session_name_prefix='session-test-subscription',
events_ros=[ events_ros=[
'ros2:rcl_node_init', 'ros2:rcl_node_init',
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
'ros2:rclcpp_subscription_init',
'ros2:rclcpp_subscription_callback_added', 'ros2:rclcpp_subscription_callback_added',
'ros2:callback_start',
'ros2:callback_end',
], ],
nodes=['test_subscription'] nodes=['test_ping', 'test_pong'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. sub_init before callback_added) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init') rcl_sub_init_events = self.get_events_with_name('ros2:rcl_subscription_init')
for event in sub_init_events: rclcpp_sub_init_events = self.get_events_with_name('ros2:rclcpp_subscription_init')
callback_added_events = self.get_events_with_name(
'ros2:rclcpp_subscription_callback_added',
)
start_events = self.get_events_with_name('ros2:callback_start')
end_events = self.get_events_with_name('ros2:callback_end')
for event in rcl_sub_init_events:
self.assertValidHandle( self.assertValidHandle(
event, event,
['subscription_handle', 'node_handle', 'rmw_subscription_handle']) ['subscription_handle', 'node_handle', 'rmw_subscription_handle'],
)
self.assertValidQueueDepth(event, 'queue_depth') self.assertValidQueueDepth(event, 'queue_depth')
self.assertStringFieldNotEmpty(event, 'topic_name') self.assertStringFieldNotEmpty(event, 'topic_name')
for event in rclcpp_sub_init_events:
callback_added_events = self.get_events_with_name( self.assertValidHandle(
'ros2:rclcpp_subscription_callback_added') event,
['subscription_handle', 'subscription'],
)
for event in callback_added_events: for event in callback_added_events:
self.assertValidHandle(event, ['subscription_handle', 'callback']) self.assertValidHandle(event, ['subscription', 'callback'])
for event in start_events:
self.assertValidHandle(event, 'callback')
is_intra_process_value = self.get_field(event, 'is_intra_process')
self.assertIsInstance(is_intra_process_value, int, 'is_intra_process not int')
self.assertTrue(
is_intra_process_value in [0, 1],
f'invalid value for is_intra_process: {is_intra_process_value}',
)
for event in end_events:
self.assertValidHandle(event, 'callback')
# Check that the test topic name exists # Check that the pong test topic name exists
test_sub_init_events = self.get_events_with_field_value( # Note: using the ping node
test_rcl_sub_init_events = self.get_events_with_field_value(
'topic_name', 'topic_name',
'/the_topic', '/pong',
sub_init_events) rcl_sub_init_events,
self.assertNumEventsEqual(test_sub_init_events, 1, 'cannot find test topic name') )
test_sub_init_event = test_sub_init_events[0] self.assertNumEventsEqual(test_rcl_sub_init_events, 1, 'cannot find test topic name')
test_rcl_sub_init_event = test_rcl_sub_init_events[0]
# Check queue_depth value # Check queue_depth value
self.assertFieldEquals( self.assertFieldEquals(
test_sub_init_event, test_rcl_sub_init_event,
'queue_depth', 'queue_depth',
10, 10,
'sub_init event does not have expected queue depth value') 'sub_init event does not have expected queue depth value',
)
# Check that the node handle matches the node_init event # Check that the node handle matches the node_init event
node_init_events = self.get_events_with_name('ros2:rcl_node_init') node_init_events = self.get_events_with_name('ros2:rcl_node_init')
test_sub_node_init_events = self.get_events_with_procname( test_sub_node_init_events = self.get_events_with_procname(
'test_subscription', 'test_ping',
node_init_events) node_init_events,
)
self.assertNumEventsEqual( self.assertNumEventsEqual(
test_sub_node_init_events, test_sub_node_init_events,
1, 1,
'none or more than 1 node_init event') 'none or more than 1 node_init event',
)
test_sub_node_init_event = test_sub_node_init_events[0] test_sub_node_init_event = test_sub_node_init_events[0]
self.assertMatchingField( self.assertMatchingField(
test_sub_node_init_event, test_sub_node_init_event,
'node_handle', 'node_handle',
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
sub_init_events) rcl_sub_init_events,
)
# Check that subscription handle matches with callback_added event # Check that subscription handle matches between rcl_sub_init and rclcpp_sub_init
self.assertMatchingField( subscription_handle = self.get_field(test_rcl_sub_init_event, 'subscription_handle')
test_sub_init_event, rclcpp_sub_init_matching_events = self.get_events_with_field_value(
'subscription_handle', 'subscription_handle',
None, subscription_handle,
callback_added_events) rclcpp_sub_init_events,
)
# Should only have 1 rclcpp_sub_init event, since intra-process is not enabled
self.assertNumEventsEqual(
rclcpp_sub_init_matching_events,
1,
'none or more than 1 rclcpp_sub_init event for topic',
)
# Check that subscription pointer matches between rclcpp_sub_init and sub_callback_added
rclcpp_sub_init_matching_event = rclcpp_sub_init_matching_events[0]
subscription_pointer = self.get_field(rclcpp_sub_init_matching_event, 'subscription')
callback_added_matching_events = self.get_events_with_field_value(
'subscription',
subscription_pointer,
callback_added_events,
)
self.assertNumEventsEqual(
callback_added_matching_events,
1,
'none or more than 1 rclcpp_sub_callback_added event for topic',
)
# Check that each start:end pair has a common callback handle
ping_events = self.get_events_with_procname('test_ping')
pong_events = self.get_events_with_procname('test_pong')
ping_events_start = self.get_events_with_name('ros2:callback_start', ping_events)
pong_events_start = self.get_events_with_name('ros2:callback_start', pong_events)
for ping_start in ping_events_start:
self.assertMatchingField(
ping_start,
'callback',
'ros2:callback_end',
ping_events,
)
for pong_start in pong_events_start:
self.assertMatchingField(
pong_start,
'callback',
'ros2:callback_end',
pong_events,
)
# Check that callback pointer matches between sub_callback_added and callback_start/end
# There is only one callback for /pong topic in ping node
callback_added_matching_event = callback_added_matching_events[0]
callback_pointer = self.get_field(callback_added_matching_event, 'callback')
callback_start_matching_events = self.get_events_with_field_value(
'callback',
callback_pointer,
ping_events_start,
)
self.assertNumEventsEqual(
callback_start_matching_events,
1,
'none or more than 1 callback_start event for topic callback',
)
ping_events_end = self.get_events_with_name('ros2:callback_end', ping_events)
callback_end_matching_events = self.get_events_with_field_value(
'callback',
callback_pointer,
ping_events_end,
)
self.assertNumEventsEqual(
callback_end_matching_events,
1,
'none or more than 1 callback_end event for topic callback',
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -1,72 +0,0 @@
# Copyright 2019 Robert Bosch GmbH
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import unittest
from tracetools_test.case import TraceTestCase
class TestSubscriptionCallback(TraceTestCase):
def __init__(self, *args) -> None:
super().__init__(
*args,
session_name_prefix='session-test-subscription-callback',
events_ros=[
'ros2:callback_start',
'ros2:callback_end',
],
nodes=['test_ping', 'test_pong']
)
def test_all(self):
# Check events order as set (e.g. start before end)
self.assertEventsOrderSet(self._events_ros)
# Check fields
start_events = self.get_events_with_name('ros2:callback_start')
for event in start_events:
self.assertValidHandle(event, 'callback')
is_intra_process_value = self.get_field(event, 'is_intra_process')
self.assertIsInstance(is_intra_process_value, int, 'is_intra_process not int')
self.assertTrue(
is_intra_process_value in [0, 1],
f'invalid value for is_intra_process: {is_intra_process_value}')
end_events = self.get_events_with_name('ros2:callback_end')
for event in end_events:
self.assertValidHandle(event, 'callback')
# Check that a start:end pair has a common callback handle
# Note: might be unstable if tracing is disabled too early
ping_events = self.get_events_with_procname('test_ping')
pong_events = self.get_events_with_procname('test_pong')
ping_events_start = self.get_events_with_name('ros2:callback_start', ping_events)
pong_events_start = self.get_events_with_name('ros2:callback_start', pong_events)
for ping_start in ping_events_start:
self.assertMatchingField(
ping_start,
'callback',
'ros2:callback_end',
ping_events)
for pong_start in pong_events_start:
self.assertMatchingField(
pong_start,
'callback',
'ros2:callback_end',
pong_events)
if __name__ == '__main__':
unittest.main()

View file

@ -29,12 +29,12 @@ class TestTimer(TraceTestCase):
'ros2:callback_start', 'ros2:callback_start',
'ros2:callback_end', 'ros2:callback_end',
], ],
nodes=['test_timer'] nodes=['test_timer'],
) )
def test_all(self): def test_all(self):
# Check events order as set (e.g. init, callback added, start, end) # Check events as set
self.assertEventsOrderSet(self._events_ros) self.assertEventsSet(self._events_ros)
# Check fields # Check fields
init_events = self.get_events_with_name('ros2:rcl_timer_init') init_events = self.get_events_with_name('ros2:rcl_timer_init')
@ -56,7 +56,8 @@ class TestTimer(TraceTestCase):
event, event,
'is_intra_process', 'is_intra_process',
0, 0,
'invalid value for is_intra_process') 'invalid value for is_intra_process',
)
end_events = self.get_events_with_name('ros2:callback_end') end_events = self.get_events_with_name('ros2:callback_end')
for event in end_events: for event in end_events:
@ -73,7 +74,8 @@ class TestTimer(TraceTestCase):
test_init_event, test_init_event,
'timer_handle', 'timer_handle',
'ros2:rclcpp_timer_callback_added', 'ros2:rclcpp_timer_callback_added',
callback_added_events) callback_added_events,
)
# Check that a callback start:end pair has a common callback handle # Check that a callback start:end pair has a common callback handle
for start_event in start_events: for start_event in start_events:
@ -81,7 +83,8 @@ class TestTimer(TraceTestCase):
start_event, start_event,
'callback', 'callback',
None, None,
end_events) end_events,
)
if __name__ == '__main__': if __name__ == '__main__':

View file

@ -99,15 +99,21 @@ class TraceTestCase(unittest.TestCase):
def tearDown(self): def tearDown(self):
cleanup_trace(self._full_path) cleanup_trace(self._full_path)
def assertEventsOrderSet(self, event_names: List[str]): def assertEventsSet(
self,
event_names: List[str],
) -> None:
""" """
Compare given event names to trace events names as sets. Compare given event names to trace events names as sets.
:param event_names: the list of event names to compare to (as a set) :param event_names: the list of event names to compare to (as a set)
""" """
self.assertSetEqual(set(self._event_names), set(event_names), 'wrong events order') self.assertSetEqual(set(self._event_names), set(event_names), 'wrong events')
def assertProcessNamesExist(self, names: List[str]): def assertProcessNamesExist(
self,
names: List[str],
) -> None:
""" """
Check that the given processes exist. Check that the given processes exist.
@ -119,21 +125,29 @@ class TraceTestCase(unittest.TestCase):
name_trimmed = name[:15] name_trimmed = name[:15]
self.assertTrue(name_trimmed in procnames, 'node name not found in tracepoints') self.assertTrue(name_trimmed in procnames, 'node name not found in tracepoints')
def assertValidHandle(self, event: DictEvent, handle_field_name: Union[str, List[str]]): def assertValidHandle(
self,
event: DictEvent,
handle_field_names: Union[str, List[str]],
) -> None:
""" """
Check that the handle associated with a field name is valid. Check that the handle associated with a field name is valid.
:param event: the event which has a handle field :param event: the event which has a handle field
:param handle_field_name: the field name(s) of the handle to check :param handle_field_names: the handle field name(s) to check
""" """
is_list = isinstance(handle_field_name, list) if not isinstance(handle_field_names, list):
handle_field_names = handle_field_name if is_list else [handle_field_name] handle_field_names = [handle_field_names]
for field_name in handle_field_names: for field_name in handle_field_names:
handle_value = self.get_field(event, field_name) handle_value = self.get_field(event, field_name)
self.assertIsInstance(handle_value, int, 'handle value not int') self.assertIsInstance(handle_value, int, 'handle value not int')
self.assertGreater(handle_value, 0, f'invalid handle value: {field_name}') self.assertGreater(handle_value, 0, f'invalid handle value: {field_name}')
def assertValidQueueDepth(self, event: DictEvent, queue_depth_field_name: str = 'queue_depth'): def assertValidQueueDepth(
self,
event: DictEvent,
queue_depth_field_name: str = 'queue_depth',
) -> None:
""" """
Check that the queue depth value is valid. Check that the queue depth value is valid.
@ -144,7 +158,11 @@ class TraceTestCase(unittest.TestCase):
self.assertIsInstance(queue_depth_value, int, 'invalid queue depth type') self.assertIsInstance(queue_depth_value, int, 'invalid queue depth type')
self.assertGreater(queue_depth_value, 0, 'invalid queue depth') self.assertGreater(queue_depth_value, 0, 'invalid queue depth')
def assertStringFieldNotEmpty(self, event: DictEvent, string_field_name: str): def assertStringFieldNotEmpty(
self,
event: DictEvent,
string_field_name: str,
) -> None:
""" """
Check that a string field is not empty. Check that a string field is not empty.
@ -154,7 +172,11 @@ class TraceTestCase(unittest.TestCase):
string_field = self.get_field(event, string_field_name) string_field = self.get_field(event, string_field_name)
self.assertGreater(len(string_field), 0, 'empty string') self.assertGreater(len(string_field), 0, 'empty string')
def assertEventAfterTimestamp(self, event: DictEvent, timestamp: int): def assertEventAfterTimestamp(
self,
event: DictEvent,
timestamp: int,
) -> None:
""" """
Check that the event happens after the given timestamp. Check that the event happens after the given timestamp.
@ -163,7 +185,11 @@ class TraceTestCase(unittest.TestCase):
""" """
self.assertGreater(get_event_timestamp(event), timestamp, 'event not after timestamp') self.assertGreater(get_event_timestamp(event), timestamp, 'event not after timestamp')
def assertEventOrder(self, first_event: DictEvent, second_event: DictEvent): def assertEventOrder(
self,
first_event: DictEvent,
second_event: DictEvent,
) -> None:
""" """
Check that the first event was generated before the second event. Check that the first event was generated before the second event.
@ -176,8 +202,8 @@ class TraceTestCase(unittest.TestCase):
self, self,
events: List[DictEvent], events: List[DictEvent],
expected_number: int, expected_number: int,
msg: str = 'wrong number of events' msg: str = 'wrong number of events',
): ) -> None:
""" """
Check number of events. Check number of events.
@ -191,8 +217,8 @@ class TraceTestCase(unittest.TestCase):
self, self,
events: List[DictEvent], events: List[DictEvent],
min_expected_number: int, min_expected_number: int,
msg: str = 'wrong number of events' msg: str = 'wrong number of events',
): ) -> None:
""" """
Check that the number of events is greater of equal. Check that the number of events is greater of equal.
@ -207,8 +233,8 @@ class TraceTestCase(unittest.TestCase):
initial_event: DictEvent, initial_event: DictEvent,
field_name: str, field_name: str,
matching_event_name: str = None, matching_event_name: str = None,
events: List[DictEvent] = None events: List[DictEvent] = None,
): ) -> None:
""" """
Check that the value of a field for a given event has a matching event that follows. Check that the value of a field for a given event has a matching event that follows.
@ -247,8 +273,8 @@ class TraceTestCase(unittest.TestCase):
event: DictEvent, event: DictEvent,
field_name: str, field_name: str,
value: Any, value: Any,
msg: str = 'wrong field value' msg: str = 'wrong field value',
): ) -> None:
""" """
Check the value of a field. Check the value of a field.
@ -260,7 +286,11 @@ class TraceTestCase(unittest.TestCase):
actual_value = self.get_field(event, field_name) actual_value = self.get_field(event, field_name)
self.assertEqual(actual_value, value, msg) self.assertEqual(actual_value, value, msg)
def get_field(self, event: DictEvent, field_name: str) -> Any: def get_field(
self,
event: DictEvent,
field_name: str,
) -> Any:
""" """
Get field value; will fail test if not found. Get field value; will fail test if not found.
@ -276,7 +306,10 @@ class TraceTestCase(unittest.TestCase):
else: else:
return value return value
def get_procname(self, event: DictEvent) -> str: def get_procname(
self,
event: DictEvent,
) -> str:
""" """
Get procname. Get procname.
@ -288,7 +321,7 @@ class TraceTestCase(unittest.TestCase):
def get_events_with_name( def get_events_with_name(
self, self,
event_name: str, event_name: str,
events: List[DictEvent] = None events: List[DictEvent] = None,
) -> List[DictEvent]: ) -> List[DictEvent]:
""" """
Get all events with the given name. Get all events with the given name.
@ -304,11 +337,14 @@ class TraceTestCase(unittest.TestCase):
def get_events_with_procname( def get_events_with_procname(
self, self,
procname: str, procname: str,
events: List[DictEvent] = None events: List[DictEvent] = None,
) -> List[DictEvent]: ) -> List[DictEvent]:
""" """
Get all events with the given procname. Get all events with the given procname.
Note: the given procname value will be truncated to the same max length as the procname
field.
:param procname: the procname :param procname: the procname
:param events: the events to check (or `None` to check all events) :param events: the events to check (or `None` to check all events)
:return: the events with the given procname :return: the events with the given procname
@ -320,40 +356,48 @@ class TraceTestCase(unittest.TestCase):
def get_events_with_field_value( def get_events_with_field_value(
self, self,
field_name: str, field_name: str,
field_value: Any, field_values: Any,
events: List[DictEvent] = None events: List[DictEvent] = None,
) -> List[DictEvent]: ) -> List[DictEvent]:
""" """
Get all events with the given field:value. Get all events with the given field:value.
:param field_name: the name of the field to check :param field_name: the name of the field to check
:param field_value: the value of the field to check :param field_values: the value(s) of the field to check
:param events: the events to check (or `None` to check all events) :param events: the events to check (or `None` to check all events)
:return: the events with the given field:value pair :return: the events with the given field:value pair
""" """
if not isinstance(field_values, list):
field_values = [field_values]
if events is None: if events is None:
events = self._events events = self._events
return [e for e in events if get_field(e, field_name, None) == field_value] return [e for e in events if get_field(e, field_name, None) in field_values]
def get_events_with_field_not_value( def get_events_with_field_not_value(
self, self,
field_name: str, field_name: str,
field_value: Any, field_values: Any,
events: List[DictEvent] = None events: List[DictEvent] = None,
) -> List[DictEvent]: ) -> List[DictEvent]:
""" """
Get all events with the given field but not the value. Get all events with the given field but not the value.
:param field_name: the name of the field to check :param field_name: the name of the field to check
:param field_value: the value of the field to check :param field_values: the value(s) of the field to check
:param events: the events to check (or `None` to check all events) :param events: the events to check (or `None` to check all events)
:return: the events with the given field:value pair :return: the events with the given field:value pair
""" """
if not isinstance(field_values, list):
field_values = [field_values]
if events is None: if events is None:
events = self._events events = self._events
return [e for e in events if get_field(e, field_name, None) != field_value] return [e for e in events if get_field(e, field_name, None) not in field_values]
def are_events_ordered(self, first_event: DictEvent, second_event: DictEvent): def are_events_ordered(
self,
first_event: DictEvent,
second_event: DictEvent,
) -> bool:
""" """
Check that the first event was generated before the second event. Check that the first event was generated before the second event.

View file

@ -60,6 +60,7 @@ DEFAULT_EVENTS_ROS = [
'ros2:rcl_node_init', 'ros2:rcl_node_init',
'ros2:rcl_publisher_init', 'ros2:rcl_publisher_init',
'ros2:rcl_subscription_init', 'ros2:rcl_subscription_init',
'ros2:rclcpp_subscription_init',
'ros2:rclcpp_subscription_callback_added', 'ros2:rclcpp_subscription_callback_added',
'ros2:rcl_service_init', 'ros2:rcl_service_init',
'ros2:rclcpp_service_callback_added', 'ros2:rclcpp_service_callback_added',