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/
# generated files (LTTng)
tp_call.c
tp_call.h

View file

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

View file

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

View file

@ -1,19 +1,21 @@
#ifndef __TRACETOOLS_UTILS_H_
#define __TRACETOOLS_UTILS_H_
#ifndef TRACETOOLS__UTILS_HPP_
#define TRACETOOLS__UTILS_HPP_
#include <stddef.h>
#include <functional>
template<typename T, typename... U>
size_t get_address(std::function<T(U...)> f) {
typedef T(fnType)(U...);
fnType ** fnPointer = f.template target<fnType*>();
// Might be a lambda
if (fnPointer == nullptr) {
return 0;
}
return (size_t)*fnPointer;
template<typename T, typename ... U>
size_t get_address(std::function<T(U...)> f)
{
typedef T (fnType)(U...);
fnType ** fnPointer = f.template target<fnType *>();
// Might be a lambda
if (fnPointer == nullptr) {
return 0;
}
return (size_t)*fnPointer;
}
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>
<description>ROS 2 wrapper for instrumentation</description>
<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="fixed-term.christophe.bourquebedard@de.bosch.com">Christophe Bedard</author>
<license>APLv2</license>
<buildtool_depend>ament_cmake</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)
# include "tp_call.h"
# define CONDITIONAL_TP(...) \
tracepoint(__VA_ARGS__)
tracepoint(__VA_ARGS__)
#else
# define CONDITIONAL_TP(...)
#endif
@ -21,7 +21,10 @@ void TRACEPOINT(
rcl_init,
const void * context)
{
CONDITIONAL_TP(ros2, rcl_init, context);
CONDITIONAL_TP(
ros2,
rcl_init,
context);
}
void TRACEPOINT(
@ -31,7 +34,13 @@ void TRACEPOINT(
const char * node_name,
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(
@ -42,7 +51,14 @@ void TRACEPOINT(
const char * topic_name,
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(
@ -53,15 +69,26 @@ void TRACEPOINT(
const char * topic_name,
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(
rclcpp_subscription_callback_added,
const void * subscription_handle,
const void * callback)
rclcpp_subscription_callback_added,
const void * subscription_handle,
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(
@ -69,14 +96,21 @@ void TRACEPOINT(
const void * callback,
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(
rclcpp_subscription_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback);
CONDITIONAL_TP(
ros2,
rclcpp_subscription_callback_end,
callback);
}
void TRACEPOINT(
@ -86,7 +120,13 @@ void TRACEPOINT(
const void * rmw_service_handle,
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(
@ -94,21 +134,31 @@ void TRACEPOINT(
const void * service_handle,
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(
rclcpp_service_callback_start,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_service_callback_start, callback);
CONDITIONAL_TP(
ros2,
rclcpp_service_callback_start,
callback);
}
void TRACEPOINT(
rclcpp_service_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback);
CONDITIONAL_TP(
ros2,
rclcpp_service_callback_end,
callback);
}
void TRACEPOINT(
@ -118,15 +168,25 @@ void TRACEPOINT(
const void * rmw_client_handle,
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(
rcl_timer_init,
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(
@ -134,21 +194,31 @@ void TRACEPOINT(
const void * timer_handle,
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(
rclcpp_timer_callback_start,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_timer_callback_start, callback);
CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_start,
callback);
}
void TRACEPOINT(
rclcpp_timer_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback);
CONDITIONAL_TP(
ros2,
rclcpp_timer_callback_end,
callback);
}
void TRACEPOINT(
@ -156,5 +226,9 @@ void TRACEPOINT(
const void * callback,
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 <cxxabi.h>
#endif
#include "tracetools/utils.hpp"
const char * get_symbol(void * funptr) {
const char * get_symbol(void * funptr)
{
#define SYMBOL_UNKNOWN "UNKNOWN"
#if defined(WITH_LTTNG) && !defined(_WIN32)
#define SYMBOL_LAMBDA "[lambda]"
if (funptr == 0) {
return SYMBOL_LAMBDA;
}
if (funptr == 0) {
return SYMBOL_LAMBDA;
}
Dl_info info;
if (dladdr(funptr, &info) == 0) {
return SYMBOL_UNKNOWN;
}
Dl_info info;
if (dladdr(funptr, &info) == 0) {
return SYMBOL_UNKNOWN;
}
char * demangled = nullptr;
int status;
demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status);
// Use demangled symbol if possible
const char * demangled_val = (status == 0 ? demangled : info.dli_sname);
return (demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN);
char * demangled = nullptr;
int status;
demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status);
// Use demangled symbol if possible
const char * demangled_val = (status == 0 ? demangled : info.dli_sname);
return demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN;
#else
return SYMBOL_UNKNOWN;
#endif