Fix linting errors

This commit is contained in:
Christophe Bedard 2019-06-05 15:35:46 +02:00
parent 6cce113f04
commit 33f227b772
27 changed files with 668 additions and 563 deletions

View file

@ -1 +1,5 @@
traces/ traces/
# generated files (LTTng)
tp_call.c
tp_call.h

View file

@ -21,13 +21,13 @@ endif()
if(LTTNG_FOUND) if(LTTNG_FOUND)
# Generate necessary LTTng files # Generate necessary LTTng files
# If successful, enable tracing # If successful, enable tracing
add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c ${PROJECT_SOURCE_DIR}/include/tp_call.h
COMMAND lttng-gen-tp tp_call.tp -o ../src/tp_call.c -o ../src/tp_call.h COMMAND lttng-gen-tp tp_call.tp -o tp_call.c -o ../include/tp_call.h
WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/lttng WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/src
DEPENDS ${PROJECT_SOURCE_DIR}/lttng/tp_call.tp DEPENDS ${PROJECT_SOURCE_DIR}/src/tp_call.tp
) )
set(LTTNG_GENERATED set(LTTNG_GENERATED
src/tp_call.h include/tp_call.h
src/tp_call.c src/tp_call.c
) )
set(TRACING_ENABLED TRUE) set(TRACING_ENABLED TRUE)

View file

@ -1,12 +1,12 @@
#ifndef __TRACETOOLS_TRACETOOLS_H_ #ifndef TRACETOOLS__TRACETOOLS_H_
#define __TRACETOOLS_TRACETOOLS_H_ #define TRACETOOLS__TRACETOOLS_H_
#include <stdint.h> #include <stdint.h>
#include <string.h> #include <string.h>
#include <stdbool.h> #include <stdbool.h>
#define TRACEPOINT(event_name, ...) \ #define TRACEPOINT(event_name, ...) \
(ros_trace_##event_name)(__VA_ARGS__) (ros_trace_ ## event_name)(__VA_ARGS__)
#ifdef __cplusplus #ifdef __cplusplus
extern "C" extern "C"
@ -128,7 +128,7 @@ void TRACEPOINT(
void TRACEPOINT( void TRACEPOINT(
rcl_timer_init, rcl_timer_init,
const void * timer_handle, const void * timer_handle,
long period); int64_t period);
/** /**
* tp: rclcpp_timer_callback_added * tp: rclcpp_timer_callback_added
@ -164,4 +164,4 @@ void TRACEPOINT(
} }
#endif #endif
#endif /* __TRACETOOLS_TRACETOOLS_H_ */ #endif /* TRACETOOLS__TRACETOOLS_H_ */

View file

@ -1,19 +1,21 @@
#ifndef __TRACETOOLS_UTILS_H_ #ifndef TRACETOOLS__UTILS_HPP_
#define __TRACETOOLS_UTILS_H_ #define TRACETOOLS__UTILS_HPP_
#include <stddef.h> #include <stddef.h>
#include <functional>
template<typename T, typename... U> template<typename T, typename ... U>
size_t get_address(std::function<T(U...)> f) { size_t get_address(std::function<T(U...)> f)
typedef T(fnType)(U...); {
fnType ** fnPointer = f.template target<fnType*>(); typedef T (fnType)(U...);
// Might be a lambda fnType ** fnPointer = f.template target<fnType *>();
if (fnPointer == nullptr) { // Might be a lambda
return 0; if (fnPointer == nullptr) {
} return 0;
return (size_t)*fnPointer; }
return (size_t)*fnPointer;
} }
const char * get_symbol(void * funptr); const char * get_symbol(void * funptr);
#endif /* __TRACETOOLS_UTILS_H_ */ #endif // TRACETOOLS__UTILS_HPP_

View file

@ -1,234 +0,0 @@
#include <stdint.h>
TRACEPOINT_EVENT(
ros2,
rcl_init,
TP_ARGS(
const void *, context_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, context, context_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_node_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, rmw_handle_arg,
const char *, node_name_arg,
const char *, namespace_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg)
ctf_string(node_name, node_name_arg)
ctf_string(namespace, namespace_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_publisher_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, rmw_handle_arg,
const void *, publisher_handle_arg,
const char *, topic_name_arg,
const size_t, depth_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg)
ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg)
ctf_string(topic_name, topic_name_arg)
ctf_integer(const size_t, depth, depth_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_subscription_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, subscription_handle_arg,
const void *, rmw_subscription_handle_arg,
const char *, topic_name_arg,
const size_t, depth_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg)
ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg)
ctf_string(topic_name, topic_name_arg)
ctf_integer(const size_t, depth, depth_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_added,
TP_ARGS(
const void *, subscription_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_start,
TP_ARGS(
const void *, callback_arg,
int, is_intra_process_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
ctf_integer(int, is_intra_process, is_intra_process_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_service_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, service_handle_arg,
const void *, rmw_service_handle_arg,
const char *, service_name_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, service_handle, service_handle_arg)
ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg)
ctf_string(service_name, service_name_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_added,
TP_ARGS(
const void *, service_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, service_handle, service_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_start,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_client_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, client_handle_arg,
const void *, rmw_client_handle_arg,
const char *, service_name_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, client_handle, client_handle_arg)
ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg)
ctf_string(service_name, service_name_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_timer_init,
TP_ARGS(
const void *, timer_handle_arg,
long, period_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, timer_handle, timer_handle_arg)
ctf_integer(long, period, period_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_added,
TP_ARGS(
const void *, timer_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, timer_handle, timer_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_start,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_callback_register,
TP_ARGS(
const void *, callback_arg,
const char *, symbol_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
ctf_string(symbol, symbol_arg)
)
)

View file

@ -5,9 +5,9 @@
<version>0.0.1</version> <version>0.0.1</version>
<description>ROS 2 wrapper for instrumentation</description> <description>ROS 2 wrapper for instrumentation</description>
<maintainer email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</maintainer> <maintainer email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</maintainer>
<license>APLv2</license>
<author email="ingo.luetkebohle@de.bosch.com">Ingo Luetkebohle</author> <author email="ingo.luetkebohle@de.bosch.com">Ingo Luetkebohle</author>
<author email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</author> <author email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</author>
<license>APLv2</license>
<buildtool_depend>ament_cmake</buildtool_depend> <buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>pkg-config</buildtool_depend> <buildtool_depend>pkg-config</buildtool_depend>

View file

@ -1,3 +0,0 @@
# generated files (LTTng)
tp_call.c
tp_call.h

234
tracetools/src/tp_call.tp Normal file
View file

@ -0,0 +1,234 @@
#include <stdint.h>
TRACEPOINT_EVENT(
ros2,
rcl_init,
TP_ARGS(
const void *, context_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, context, context_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_node_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, rmw_handle_arg,
const char *, node_name_arg,
const char *, namespace_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg)
ctf_string(node_name, node_name_arg)
ctf_string(namespace, namespace_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_publisher_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, rmw_handle_arg,
const void *, publisher_handle_arg,
const char *, topic_name_arg,
const size_t, depth_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg)
ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg)
ctf_string(topic_name, topic_name_arg)
ctf_integer(const size_t, depth, depth_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_subscription_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, subscription_handle_arg,
const void *, rmw_subscription_handle_arg,
const char *, topic_name_arg,
const size_t, depth_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg)
ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg)
ctf_string(topic_name, topic_name_arg)
ctf_integer(const size_t, depth, depth_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_added,
TP_ARGS(
const void *, subscription_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_start,
TP_ARGS(
const void *, callback_arg,
int, is_intra_process_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
ctf_integer(int, is_intra_process, is_intra_process_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_subscription_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_service_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, service_handle_arg,
const void *, rmw_service_handle_arg,
const char *, service_name_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, service_handle, service_handle_arg)
ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg)
ctf_string(service_name, service_name_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_added,
TP_ARGS(
const void *, service_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, service_handle, service_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_start,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_service_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_client_init,
TP_ARGS(
const void *, node_handle_arg,
const void *, client_handle_arg,
const void *, rmw_client_handle_arg,
const char *, service_name_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, node_handle, node_handle_arg)
ctf_integer_hex(const void *, client_handle, client_handle_arg)
ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg)
ctf_string(service_name, service_name_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rcl_timer_init,
TP_ARGS(
const void *, timer_handle_arg,
int64_t, period_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, timer_handle, timer_handle_arg)
ctf_integer(int64_t, period, period_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_added,
TP_ARGS(
const void *, timer_handle_arg,
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, timer_handle, timer_handle_arg)
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_start,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_timer_callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)
TRACEPOINT_EVENT(
ros2,
rclcpp_callback_register,
TP_ARGS(
const void *, callback_arg,
const char *, symbol_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
ctf_string(symbol, symbol_arg)
)
)

View file

@ -3,7 +3,7 @@
#if defined(WITH_LTTNG) && !defined(_WIN32) #if defined(WITH_LTTNG) && !defined(_WIN32)
# include "tp_call.h" # include "tp_call.h"
# define CONDITIONAL_TP(...) \ # define CONDITIONAL_TP(...) \
tracepoint(__VA_ARGS__) tracepoint(__VA_ARGS__)
#else #else
# define CONDITIONAL_TP(...) # define CONDITIONAL_TP(...)
#endif #endif
@ -21,7 +21,10 @@ void TRACEPOINT(
rcl_init, rcl_init,
const void * context) const void * context)
{ {
CONDITIONAL_TP(ros2, rcl_init, context); CONDITIONAL_TP(
ros2,
rcl_init,
context);
} }
void TRACEPOINT( void TRACEPOINT(
@ -31,7 +34,13 @@ void TRACEPOINT(
const char * node_name, const char * node_name,
const char * node_namespace) const char * node_namespace)
{ {
CONDITIONAL_TP(ros2, rcl_node_init, node_handle, rmw_handle, node_name, node_namespace); CONDITIONAL_TP(
ros2,
rcl_node_init,
node_handle,
rmw_handle,
node_name,
node_namespace);
} }
void TRACEPOINT( void TRACEPOINT(
@ -42,7 +51,14 @@ void TRACEPOINT(
const char * topic_name, const char * topic_name,
const size_t depth) const size_t depth)
{ {
CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, publisher_handle, rmw_publisher_handle, topic_name, depth); CONDITIONAL_TP(
ros2,
rcl_publisher_init,
node_handle,
publisher_handle,
rmw_publisher_handle,
topic_name,
depth);
} }
void TRACEPOINT( void TRACEPOINT(
@ -53,15 +69,26 @@ void TRACEPOINT(
const char * topic_name, const char * topic_name,
const size_t depth) const size_t depth)
{ {
CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, subscription_handle, rmw_subscription_handle, topic_name, depth); CONDITIONAL_TP(
ros2,
rcl_subscription_init,
node_handle,
subscription_handle,
rmw_subscription_handle,
topic_name,
depth);
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_subscription_callback_added, rclcpp_subscription_callback_added,
const void * subscription_handle, const void * subscription_handle,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_added, subscription_handle, callback); CONDITIONAL_TP(
ros2,
rclcpp_subscription_callback_added,
subscription_handle,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
@ -69,14 +96,21 @@ void TRACEPOINT(
const void * callback, const void * callback,
const bool is_intra_process) const bool is_intra_process)
{ {
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0)); CONDITIONAL_TP(
ros2,
rclcpp_subscription_callback_start,
callback,
(is_intra_process ? 1 : 0));
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_subscription_callback_end, rclcpp_subscription_callback_end,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback); CONDITIONAL_TP(
ros2,
rclcpp_subscription_callback_end,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
@ -86,7 +120,13 @@ void TRACEPOINT(
const void * rmw_service_handle, const void * rmw_service_handle,
const char * service_name) const char * service_name)
{ {
CONDITIONAL_TP(ros2, rcl_service_init, node_handle, service_handle, rmw_service_handle, service_name); CONDITIONAL_TP(
ros2,
rcl_service_init,
node_handle,
service_handle,
rmw_service_handle,
service_name);
} }
void TRACEPOINT( void TRACEPOINT(
@ -94,21 +134,31 @@ void TRACEPOINT(
const void * service_handle, const void * service_handle,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service_handle, callback); CONDITIONAL_TP(
ros2,
rclcpp_service_callback_added,
service_handle,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_service_callback_start, rclcpp_service_callback_start,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_service_callback_start, callback); CONDITIONAL_TP(
ros2,
rclcpp_service_callback_start,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_service_callback_end, rclcpp_service_callback_end,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback); CONDITIONAL_TP(
ros2,
rclcpp_service_callback_end,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
@ -118,15 +168,25 @@ void TRACEPOINT(
const void * rmw_client_handle, const void * rmw_client_handle,
const char * service_name) const char * service_name)
{ {
CONDITIONAL_TP(ros2, rcl_client_init, node_handle, client_handle, rmw_client_handle, service_name); CONDITIONAL_TP(
ros2,
rcl_client_init,
node_handle,
client_handle,
rmw_client_handle,
service_name);
} }
void TRACEPOINT( void TRACEPOINT(
rcl_timer_init, rcl_timer_init,
const void * timer_handle, const void * timer_handle,
long period) int64_t period)
{ {
CONDITIONAL_TP(ros2, rcl_timer_init, timer_handle, period); CONDITIONAL_TP(
ros2,
rcl_timer_init,
timer_handle,
period);
} }
void TRACEPOINT( void TRACEPOINT(
@ -134,21 +194,31 @@ void TRACEPOINT(
const void * timer_handle, const void * timer_handle,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_timer_callback_added, timer_handle, callback); CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_added,
timer_handle,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_timer_callback_start, rclcpp_timer_callback_start,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_timer_callback_start, callback); CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_start,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
rclcpp_timer_callback_end, rclcpp_timer_callback_end,
const void * callback) const void * callback)
{ {
CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback); CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_end,
callback);
} }
void TRACEPOINT( void TRACEPOINT(
@ -156,5 +226,9 @@ void TRACEPOINT(
const void * callback, const void * callback,
const char * function_symbol) const char * function_symbol)
{ {
CONDITIONAL_TP(ros2, rclcpp_callback_register, callback, function_symbol); CONDITIONAL_TP(
ros2,
rclcpp_callback_register,
callback,
function_symbol);
} }

View file

@ -2,26 +2,28 @@
#include <dlfcn.h> #include <dlfcn.h>
#include <cxxabi.h> #include <cxxabi.h>
#endif #endif
#include "tracetools/utils.hpp"
const char * get_symbol(void * funptr) { const char * get_symbol(void * funptr)
{
#define SYMBOL_UNKNOWN "UNKNOWN" #define SYMBOL_UNKNOWN "UNKNOWN"
#if defined(WITH_LTTNG) && !defined(_WIN32) #if defined(WITH_LTTNG) && !defined(_WIN32)
#define SYMBOL_LAMBDA "[lambda]" #define SYMBOL_LAMBDA "[lambda]"
if (funptr == 0) { if (funptr == 0) {
return SYMBOL_LAMBDA; return SYMBOL_LAMBDA;
} }
Dl_info info; Dl_info info;
if (dladdr(funptr, &info) == 0) { if (dladdr(funptr, &info) == 0) {
return SYMBOL_UNKNOWN; return SYMBOL_UNKNOWN;
} }
char * demangled = nullptr; char * demangled = nullptr;
int status; int status;
demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status); demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status);
// Use demangled symbol if possible // Use demangled symbol if possible
const char * demangled_val = (status == 0 ? demangled : info.dli_sname); const char * demangled_val = (status == 0 ? demangled : info.dli_sname);
return (demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN); return demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN;
#else #else
return SYMBOL_UNKNOWN; return SYMBOL_UNKNOWN;
#endif #endif

View file

@ -5,8 +5,8 @@
<version>0.0.1</version> <version>0.0.1</version>
<description>Separate test package for tracetools</description> <description>Separate test package for tracetools</description>
<maintainer email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</maintainer> <maintainer email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</maintainer>
<author email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</author>
<license>APLv2</license> <license>APLv2</license>
<author email="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</author>
<buildtool_depend>ament_cmake</buildtool_depend> <buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>pkg-config</buildtool_depend> <buildtool_depend>pkg-config</buildtool_depend>

View file

@ -6,56 +6,55 @@
using namespace std::chrono_literals; using namespace std::chrono_literals;
class PingNode : public rclcpp::Node class PingNode : public rclcpp::Node
{ {
public: public:
PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) explicit PingNode(rclcpp::NodeOptions options)
{ : Node("ping_node", options)
sub_ = this->create_subscription<std_msgs::msg::String>( {
"pong", sub_ = this->create_subscription<std_msgs::msg::String>(
rclcpp::QoS(10), "pong",
std::bind(&PingNode::callback, this, std::placeholders::_1)); rclcpp::QoS(10),
pub_ = this->create_publisher<std_msgs::msg::String>( std::bind(&PingNode::callback, this, std::placeholders::_1));
"ping", pub_ = this->create_publisher<std_msgs::msg::String>(
rclcpp::QoS(10)); "ping",
timer_ = this->create_wall_timer( rclcpp::QoS(10));
500ms, timer_ = this->create_wall_timer(
std::bind(&PingNode::timer_callback, this)); 500ms,
} std::bind(&PingNode::timer_callback, this));
}
private: private:
void callback(const std_msgs::msg::String::SharedPtr msg) void callback(const std_msgs::msg::String::SharedPtr msg)
{ {
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
rclcpp::shutdown(); rclcpp::shutdown();
} }
void timer_callback() void timer_callback()
{ {
auto msg = std::make_shared<std_msgs::msg::String>(); auto msg = std::make_shared<std_msgs::msg::String>();
msg->data = "some random ping string"; msg->data = "some random ping string";
pub_->publish(*msg); pub_->publish(*msg);
} }
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions()); auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions());
exec.add_node(ping_node); exec.add_node(ping_node);
printf("spinning\n"); printf("spinning\n");
exec.spin(); exec.spin();
// Will actually be called inside the node's callback // Will actually be called inside the node's callback
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -3,47 +3,47 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp" #include "std_msgs/msg/string.hpp"
class PongNode : public rclcpp::Node class PongNode : public rclcpp::Node
{ {
public: public:
PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) explicit PongNode(rclcpp::NodeOptions options)
{ : Node("pong_node", options)
sub_ = this->create_subscription<std_msgs::msg::String>( {
"ping", sub_ = this->create_subscription<std_msgs::msg::String>(
rclcpp::QoS(10), "ping",
std::bind(&PongNode::callback, this, std::placeholders::_1)); rclcpp::QoS(10),
pub_ = this->create_publisher<std_msgs::msg::String>( std::bind(&PongNode::callback, this, std::placeholders::_1));
"pong", pub_ = this->create_publisher<std_msgs::msg::String>(
rclcpp::QoS(10)); "pong",
} rclcpp::QoS(10));
}
private: private:
void callback(const std_msgs::msg::String::SharedPtr msg) void callback(const std_msgs::msg::String::SharedPtr msg)
{ {
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
auto next_msg = std::make_shared<std_msgs::msg::String>(); auto next_msg = std::make_shared<std_msgs::msg::String>();
next_msg->data = "some random pong string"; next_msg->data = "some random pong string";
pub_->publish(*next_msg); pub_->publish(*next_msg);
rclcpp::shutdown(); rclcpp::shutdown();
} }
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions()); auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node); exec.add_node(pong_node);
printf("spinning\n"); printf("spinning\n");
exec.spin(); exec.spin();
// Will actually be called inside the node's callback // Will actually be called inside the node's callback
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -1,32 +1,34 @@
#include <memory>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp" #include "std_msgs/msg/string.hpp"
class PubNode : public rclcpp::Node class PubNode : public rclcpp::Node
{ {
public: public:
PubNode(rclcpp::NodeOptions options) : Node("pub_node", options) explicit PubNode(rclcpp::NodeOptions options)
{ : Node("pub_node", options)
pub_ = this->create_publisher<std_msgs::msg::String>( {
"the_topic", pub_ = this->create_publisher<std_msgs::msg::String>(
rclcpp::QoS(10)); "the_topic",
} rclcpp::QoS(10));
}
private: private:
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_; rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
}; };
int main(int argc, char* argv[]) 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>(rclcpp::NodeOptions()); 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");
exec.spin_once(); exec.spin_once();
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -6,43 +6,45 @@
class ServiceNode : public rclcpp::Node class ServiceNode : public rclcpp::Node
{ {
public: public:
ServiceNode(rclcpp::NodeOptions options) : Node("service_node", options) explicit ServiceNode(rclcpp::NodeOptions options)
{ : Node("service_node", options)
srv_ = this->create_service<std_srvs::srv::Empty>( {
"service", srv_ = this->create_service<std_srvs::srv::Empty>(
std::bind(&ServiceNode::service_callback, "service",
this, std::bind(
std::placeholders::_1, &ServiceNode::service_callback,
std::placeholders::_2, this,
std::placeholders::_3)); std::placeholders::_1,
} std::placeholders::_2,
std::placeholders::_3));
}
private: private:
void service_callback( void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request, const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response) const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{ {
// Nothing // Nothing
(void)request_header; (void)request_header;
(void)request; (void)request;
(void)response; (void)response;
} }
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_; rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto service_node = std::make_shared<ServiceNode>(rclcpp::NodeOptions()); auto service_node = std::make_shared<ServiceNode>(rclcpp::NodeOptions());
exec.add_node(service_node); exec.add_node(service_node);
printf("spinning once\n"); printf("spinning once\n");
exec.spin_once(); exec.spin_once();
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -6,63 +6,63 @@
using namespace std::chrono_literals; using namespace std::chrono_literals;
class PingNode : public rclcpp::Node class PingNode : public rclcpp::Node
{ {
public: public:
PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) explicit PingNode(rclcpp::NodeOptions options)
{ : Node("ping_node", options)
srv_ = this->create_service<std_srvs::srv::Empty>( {
"pong", srv_ = this->create_service<std_srvs::srv::Empty>(
std::bind(&PingNode::service_callback, "pong",
this, std::bind(
std::placeholders::_1, &PingNode::service_callback,
std::placeholders::_2, this,
std::placeholders::_3)); std::placeholders::_1,
client_ = this->create_client<std_srvs::srv::Empty>( std::placeholders::_2,
"ping"); std::placeholders::_3));
timer_ = this->create_wall_timer( client_ = this->create_client<std_srvs::srv::Empty>(
500ms, "ping");
std::bind(&PingNode::timer_callback, this)); timer_ = this->create_wall_timer(
} 500ms,
std::bind(&PingNode::timer_callback, this));
}
private: private:
void service_callback( void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request, const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response) const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{ {
(void)request_header; (void)request_header;
(void)request; (void)request;
(void)response; (void)response;
RCLCPP_INFO(this->get_logger(), "got request"); RCLCPP_INFO(this->get_logger(), "got request");
rclcpp::shutdown(); rclcpp::shutdown();
} }
void timer_callback() void timer_callback()
{ {
auto req = std::make_shared<std_srvs::srv::Empty::Request>(); auto req = std::make_shared<std_srvs::srv::Empty::Request>();
client_->async_send_request(req); client_->async_send_request(req);
} }
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_; rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_; rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions()); auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions());
exec.add_node(ping_node); exec.add_node(ping_node);
printf("spinning\n"); printf("spinning\n");
exec.spin(); exec.spin();
// Will actually be called inside the node's service callback // Will actually be called inside the node's service callback
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -3,55 +3,54 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp" #include "std_srvs/srv/empty.hpp"
class PongNode : public rclcpp::Node class PongNode : public rclcpp::Node
{ {
public: public:
PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) explicit PongNode(rclcpp::NodeOptions options)
{ : Node("pong_node", options)
srv_ = this->create_service<std_srvs::srv::Empty>( {
"ping", srv_ = this->create_service<std_srvs::srv::Empty>(
std::bind(&PongNode::service_callback, "ping",
this, std::bind(
std::placeholders::_1, &PongNode::service_callback,
std::placeholders::_2, this,
std::placeholders::_3)); std::placeholders::_1,
client_ = this->create_client<std_srvs::srv::Empty>( std::placeholders::_2,
"pong"); std::placeholders::_3));
} client_ = this->create_client<std_srvs::srv::Empty>("pong");
}
private: private:
void service_callback( void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request, const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response) const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{ {
(void)request_header; (void)request_header;
(void)request; (void)request;
(void)response; (void)response;
RCLCPP_INFO(this->get_logger(), "got request"); RCLCPP_INFO(this->get_logger(), "got request");
auto req = std::make_shared<std_srvs::srv::Empty::Request>(); auto req = std::make_shared<std_srvs::srv::Empty::Request>();
client_->async_send_request(req); client_->async_send_request(req);
rclcpp::shutdown(); rclcpp::shutdown();
} }
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_; rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_; rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions()); auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node); exec.add_node(pong_node);
printf("spinning\n"); printf("spinning\n");
exec.spin(); exec.spin();
// Will actually be called inside the node's service callback // Will actually be called inside the node's service callback
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -3,39 +3,39 @@
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp" #include "std_msgs/msg/string.hpp"
class SubNode : public rclcpp::Node class SubNode : public rclcpp::Node
{ {
public: public:
SubNode(rclcpp::NodeOptions options) : Node("sub_node", options) explicit SubNode(rclcpp::NodeOptions options)
{ : Node("sub_node", options)
sub_ = this->create_subscription<std_msgs::msg::String>( {
"the_topic", sub_ = this->create_subscription<std_msgs::msg::String>(
rclcpp::QoS(10), "the_topic",
std::bind(&SubNode::callback, this, std::placeholders::_1)); rclcpp::QoS(10),
} std::bind(&SubNode::callback, this, std::placeholders::_1));
}
private: private:
void callback(const std_msgs::msg::String::SharedPtr msg) void callback(const std_msgs::msg::String::SharedPtr msg)
{ {
// Nothing // Nothing
(void)msg; (void)msg;
} }
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_; rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto sub_node = std::make_shared<SubNode>(rclcpp::NodeOptions()); auto sub_node = std::make_shared<SubNode>(rclcpp::NodeOptions());
exec.add_node(sub_node); exec.add_node(sub_node);
printf("spinning once\n"); printf("spinning once\n");
exec.spin_once(); exec.spin_once();
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -1,47 +1,48 @@
#include <memory>
#include <chrono> #include <chrono>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals; using namespace std::chrono_literals;
class TimerNode : public rclcpp::Node class TimerNode : public rclcpp::Node
{ {
public: public:
TimerNode(rclcpp::NodeOptions options) : Node("timer_node", options) explicit TimerNode(rclcpp::NodeOptions options)
{ : Node("timer_node", options)
is_done_ = false; {
timer_ = this->create_wall_timer( is_done_ = false;
1ms, timer_ = this->create_wall_timer(
std::bind(&TimerNode::timer_callback, this)); 1ms,
} std::bind(&TimerNode::timer_callback, this));
}
private: private:
void timer_callback() void timer_callback()
{ {
if (is_done_) { if (is_done_) {
rclcpp::shutdown(); rclcpp::shutdown();
} else { } else {
is_done_ = true; is_done_ = true;
}
} }
}
rclcpp::TimerBase::SharedPtr timer_; rclcpp::TimerBase::SharedPtr timer_;
bool is_done_; bool is_done_;
}; };
int main(int argc, char* argv[]) int main(int argc, char * argv[])
{ {
rclcpp::init(argc, argv); rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec; rclcpp::executors::SingleThreadedExecutor exec;
auto timer_node = std::make_shared<TimerNode>(rclcpp::NodeOptions()); auto timer_node = std::make_shared<TimerNode>(rclcpp::NodeOptions());
exec.add_node(timer_node); exec.add_node(timer_node);
printf("spinning\n"); printf("spinning\n");
exec.spin(); exec.spin();
// Will actually be called inside the timer's callback // Will actually be called inside the timer's callback
rclcpp::shutdown(); rclcpp::shutdown();
return 0; return 0;
} }

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -12,6 +13,7 @@ node_creation_events = [
'ros2:rcl_node_init', 'ros2:rcl_node_init',
] ]
class TestNode(unittest.TestCase): class TestNode(unittest.TestCase):
def test_creation(self): def test_creation(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -11,6 +12,7 @@ publisher_creation_events = [
'ros2:rcl_publisher_init', 'ros2:rcl_publisher_init',
] ]
class TestPublisher(unittest.TestCase): class TestPublisher(unittest.TestCase):
def test_creation(self): def test_creation(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -12,6 +13,7 @@ service_creation_events = [
'ros2:rclcpp_service_callback_added', 'ros2:rclcpp_service_callback_added',
] ]
class TestService(unittest.TestCase): class TestService(unittest.TestCase):
def test_creation(self): def test_creation(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -12,6 +13,7 @@ service_callback_events = [
'ros2:rclcpp_service_callback_end', 'ros2:rclcpp_service_callback_end',
] ]
class TestServiceCallback(unittest.TestCase): class TestServiceCallback(unittest.TestCase):
def test_callback(self): def test_callback(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -12,6 +13,7 @@ subscription_creation_events = [
'ros2:rclcpp_subscription_callback_added', 'ros2:rclcpp_subscription_callback_added',
] ]
class TestSubscription(unittest.TestCase): class TestSubscription(unittest.TestCase):
def test_creation(self): def test_creation(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -12,6 +13,7 @@ subscription_callback_events = [
'ros2:rclcpp_subscription_callback_end', 'ros2:rclcpp_subscription_callback_end',
] ]
class TestSubscriptionCallback(unittest.TestCase): class TestSubscriptionCallback(unittest.TestCase):
def test_callback(self): def test_callback(self):

View file

@ -1,8 +1,9 @@
import unittest import unittest
from tracetools_test.utils import ( from tracetools_test.utils import (
cleanup_trace,
get_trace_event_names, get_trace_event_names,
run_and_trace, run_and_trace,
cleanup_trace,
) )
BASE_PATH = '/tmp' BASE_PATH = '/tmp'
@ -14,6 +15,7 @@ timer_events = [
'ros2:rclcpp_timer_callback_end', 'ros2:rclcpp_timer_callback_end',
] ]
class TestTimer(unittest.TestCase): class TestTimer(unittest.TestCase):
def test_all(self): def test_all(self):

View file

@ -1,23 +1,30 @@
# Utils for tracetools_test # Utils for tracetools_test
import time
import shutil import shutil
import subprocess import time
import babeltrace import babeltrace
from launch import LaunchDescription from launch import LaunchDescription
from launch import LaunchService from launch import LaunchService
from launch_ros import get_default_launch_description from launch_ros import get_default_launch_description
import launch_ros.actions import launch_ros.actions
from tracetools_trace.tools.lttng import ( from tracetools_trace.tools.lttng import (
lttng_destroy,
lttng_setup, lttng_setup,
lttng_start, lttng_start,
lttng_stop, lttng_stop,
lttng_destroy,
) )
def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_names):
def run_and_trace(base_path,
session_name_prefix,
ros_events,
kernel_events,
package_name,
node_names):
""" """
Run a node while tracing Run a node while tracing.
:param base_path (str): the base path where to put the trace directory :param base_path (str): the base path where to put the trace directory
:param session_name_prefix (str): the session name prefix for the trace directory :param session_name_prefix (str): the session name prefix for the trace directory
:param ros_events (list(str)): the list of ROS UST events to enable :param ros_events (list(str)): the list of ROS UST events to enable
@ -53,7 +60,8 @@ def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, pac
def cleanup_trace(full_path): def cleanup_trace(full_path):
""" """
Cleanup trace data Cleanup trace data.
:param full_path (str): the full path to the main trace directory :param full_path (str): the full path to the main trace directory
""" """
shutil.rmtree(full_path) shutil.rmtree(full_path)
@ -61,7 +69,8 @@ def cleanup_trace(full_path):
def get_trace_event_names(trace_directory): def get_trace_event_names(trace_directory):
""" """
Get a set of event names in a trace Get a set of event names in a trace.
:param trace_directory (str): the path to the main/top trace directory :param trace_directory (str): the path to the main/top trace directory
:return: event names (set(str)) :return: event names (set(str))
""" """