Add r2r_tracing crate
The crate contains tracepoints; either defined directly or imported from ros2_tracing project (tracetools package).
This commit is contained in:
parent
e6f805b3d3
commit
da1566b342
|
|
@ -7,4 +7,5 @@ members = [
|
|||
"r2r_msg_gen",
|
||||
"r2r_macros",
|
||||
"r2r_rcl",
|
||||
"r2r_tracing",
|
||||
]
|
||||
|
|
|
|||
|
|
@ -0,0 +1,16 @@
|
|||
[package]
|
||||
name = "r2r_tracing"
|
||||
version = "0.9.2"
|
||||
|
||||
edition = "2021"
|
||||
|
||||
# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
|
||||
|
||||
[dependencies]
|
||||
lttng-ust = { git = "https://github.com/skoudmar/lttng-ust-rs.git"}
|
||||
r2r_rcl = { path = "../r2r_rcl", version = "0.9.2" }
|
||||
|
||||
[build-dependencies]
|
||||
lttng-ust-generate = { git = "https://github.com/skoudmar/lttng-ust-rs.git"}
|
||||
bindgen = {version = "0.63.0"}
|
||||
r2r_common = { path = "../r2r_common", version = "0.9.2" }
|
||||
|
|
@ -0,0 +1,64 @@
|
|||
use lttng_ust_generate::{CIntegerType, CTFType, Generator, Provider};
|
||||
use std::{env, path::PathBuf};
|
||||
|
||||
macro_rules! create_tracepoint {
|
||||
($provider:ident::$name:ident($($arg_name:ident: $arg_lttng_type:expr),* $(,)?)) => {
|
||||
$provider.create_class(concat!(stringify!($name), "_class"))
|
||||
$(
|
||||
.add_field(stringify!($arg_name), $arg_lttng_type)
|
||||
)*
|
||||
.instantiate(stringify!($name))
|
||||
};
|
||||
}
|
||||
|
||||
fn main() {
|
||||
generate_rclcpp_tracepoint_bindings();
|
||||
generate_r2r_tracepoints();
|
||||
}
|
||||
|
||||
/// Generate bindings to the rclcpp tracepoints defined in the tracetools ros2 package.
|
||||
fn generate_rclcpp_tracepoint_bindings() {
|
||||
let bindings = r2r_common::setup_bindgen_builder()
|
||||
.header("src/tracetools_wrapper.h")
|
||||
.allowlist_function("ros_trace_rclcpp_.*")
|
||||
.allowlist_function("ros_trace_callback_.*")
|
||||
.generate_comments(true)
|
||||
.generate()
|
||||
.expect("Unable to generate bindings for tracetools");
|
||||
|
||||
println!("cargo:rustc-link-lib=tracetools");
|
||||
|
||||
// Write the bindings to the $OUT_DIR/tracetools_bindings.rs file.
|
||||
let out_path = PathBuf::from(env::var("OUT_DIR").unwrap());
|
||||
bindings
|
||||
.write_to_file(out_path.join("tracetools_bindings.rs"))
|
||||
.expect("Couldn't write tracetools bindings!");
|
||||
}
|
||||
|
||||
fn generate_r2r_tracepoints() {
|
||||
let mut r2r = Provider::new("r2r");
|
||||
|
||||
create_tracepoint!(r2r::spin_start(
|
||||
node_handle: CTFType::IntegerHex(CIntegerType::USize),
|
||||
timeout_s: CTFType::Integer(CIntegerType::U64),
|
||||
timeout_ns: CTFType::Integer(CIntegerType::U32),
|
||||
));
|
||||
create_tracepoint!(r2r::spin_end(
|
||||
node_handle: CTFType::IntegerHex(CIntegerType::USize),
|
||||
));
|
||||
create_tracepoint!(r2r::spin_timeout(
|
||||
node_handle: CTFType::IntegerHex(CIntegerType::USize),
|
||||
));
|
||||
create_tracepoint!(r2r::update_time(
|
||||
subscriber: CTFType::IntegerHex(CIntegerType::USize),
|
||||
time_s: CTFType::Integer(CIntegerType::I32),
|
||||
time_ns: CTFType::Integer(CIntegerType::U32),
|
||||
));
|
||||
|
||||
Generator::default()
|
||||
.generated_lib_name("r2r_tracepoints_r2r")
|
||||
.register_provider(r2r)
|
||||
.output_file_name(PathBuf::from(env::var("OUT_DIR").unwrap()).join("r2r_tracepoints.rs"))
|
||||
.generate()
|
||||
.expect("Unable to generate tracepoint bindings for r2r");
|
||||
}
|
||||
|
|
@ -0,0 +1,15 @@
|
|||
//! Tracepoint provider for the `r2r` crate.
|
||||
|
||||
use lttng_ust::import_tracepoints;
|
||||
|
||||
// Import the tracepoints defined in the build.rs script
|
||||
import_tracepoints!(concat!(env!("OUT_DIR"), "/r2r_tracepoints.rs"), r2r_tracepoints_internal);
|
||||
|
||||
mod tracetools_bindings;
|
||||
|
||||
mod rclcpp_tracepoints;
|
||||
pub use rclcpp_tracepoints::*;
|
||||
|
||||
mod r2r_tracepoints;
|
||||
pub use r2r_tracepoints::*;
|
||||
|
||||
|
|
@ -0,0 +1,26 @@
|
|||
use crate::r2r_tracepoints_internal::r2r as tp;
|
||||
use r2r_rcl::{rcl_node_t, rcl_subscription_t};
|
||||
use std::time::Duration;
|
||||
|
||||
/// The `node` started spinning with given `timeout`.
|
||||
pub fn trace_spin_start(node: *const rcl_node_t, timeout: Duration) {
|
||||
let timeout_s = timeout.as_secs();
|
||||
let timeout_ns = timeout.subsec_nanos();
|
||||
|
||||
tp::spin_start(node as usize, timeout_s, timeout_ns);
|
||||
}
|
||||
|
||||
/// The `node` ended spinning.
|
||||
pub fn trace_spin_end(node: *const rcl_node_t) {
|
||||
tp::spin_end(node as usize);
|
||||
}
|
||||
|
||||
/// The `node`` timeouted while spinning
|
||||
pub fn trace_spin_timeout(node: *const rcl_node_t) {
|
||||
tp::spin_timeout(node as usize);
|
||||
}
|
||||
|
||||
/// `subscriber` received update time message with new time `time_s` seconds and `time_ns` nanoseconds.
|
||||
pub fn trace_update_time(subscriber: *const rcl_subscription_t, time_s: i32, time_ns: u32) {
|
||||
tp::update_time(subscriber as usize, time_s, time_ns);
|
||||
}
|
||||
|
|
@ -0,0 +1,176 @@
|
|||
use crate::tracetools_bindings as tp;
|
||||
use r2r_rcl::{rcl_node_t, rcl_service_t, rcl_subscription_t, rcl_timer_t};
|
||||
use std::{ffi::CString, ptr::null};
|
||||
|
||||
// Documentation of tracepoints is based on github:ros2/ros2_tracing project
|
||||
// TODO: Check that all references and pointers must be stable (not change location)
|
||||
|
||||
const fn ref_to_c_void<T>(t: &T) -> *const std::ffi::c_void {
|
||||
std::ptr::from_ref(t).cast()
|
||||
}
|
||||
|
||||
macro_rules! c_void {
|
||||
($e:ident) => {
|
||||
$e as *const std::ffi::c_void
|
||||
};
|
||||
}
|
||||
|
||||
/// Message publication.
|
||||
///
|
||||
/// Notes the pointer to the `message` being published at the `rclcpp`/`r2r` level.
|
||||
/// The message pointer is NOT dereferenced.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_publish`
|
||||
#[allow(clippy::not_unsafe_ptr_arg_deref)]
|
||||
pub fn trace_publish(message: *const std::ffi::c_void) {
|
||||
unsafe {
|
||||
// first argument documentation:
|
||||
// publisher_handle not used, but kept for API/ABI stability
|
||||
tp::ros_trace_rclcpp_publish(null(), message);
|
||||
}
|
||||
}
|
||||
|
||||
/// Subscription object initialisation.
|
||||
///
|
||||
/// Links the `subscription_handle` from `rcl` to the addresss of rust `subscription` reference.
|
||||
/// There can be more than 1 `subscription` for 1 `subscription_handle`.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_subscription_init`
|
||||
pub fn trace_subscription_init<S>(
|
||||
subscription_handle: *const rcl_subscription_t, subscription: &S,
|
||||
) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_subscription_init(
|
||||
c_void!(subscription_handle),
|
||||
ref_to_c_void(subscription),
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
/// Link a subscription callback identified by `callback_id` to a `subscription` object.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_subscription_callback_added`
|
||||
pub fn trace_subscription_callback_added<S>(subscription: &S, callback_id: usize) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_subscription_callback_added(
|
||||
ref_to_c_void(subscription),
|
||||
c_void!(callback_id),
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
/// Message taking.
|
||||
///
|
||||
/// Notes the **reference** to the `message` being taken at the `rclcpp`/`r2r` level.
|
||||
///
|
||||
/// To trace void pointer to the message use [`trace_take_ptr`].
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_take`
|
||||
pub fn trace_take<M>(message: &M) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_take(ref_to_c_void(message));
|
||||
}
|
||||
}
|
||||
|
||||
/// Message taking.
|
||||
///
|
||||
/// Notes the **void pointer** to the `message` being taken at the `rclcpp`/`r2r` level.
|
||||
/// The message pointer is NOT dereferenced.
|
||||
///
|
||||
/// To trace reference to the message use [`trace_take`].
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_take`
|
||||
#[allow(clippy::not_unsafe_ptr_arg_deref)]
|
||||
pub fn trace_take_ptr(message: *const std::ffi::c_void) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_take(message);
|
||||
}
|
||||
}
|
||||
|
||||
/// Link a service callback identified by `callback_id` to a `service`.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_service_callback_added`
|
||||
pub fn trace_service_callback_added(service: *const rcl_service_t, callback_id: usize) {
|
||||
unsafe { tp::ros_trace_rclcpp_service_callback_added(c_void!(service), c_void!(callback_id)) }
|
||||
}
|
||||
|
||||
/// Link a timer callback identified by `callback_id` to its `rcl_timer_t` handle.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_timer_callback_added`
|
||||
pub fn trace_timer_callback_added(timer: *const rcl_timer_t, callback_id: usize) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_timer_callback_added(c_void!(timer), c_void!(callback_id));
|
||||
}
|
||||
}
|
||||
|
||||
/// Link a `timer` to a `node`.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_timer_link_node`
|
||||
pub fn trace_timer_link_node(timer: *const rcl_timer_t, node: *const rcl_node_t) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_timer_link_node(c_void!(timer), c_void!(node));
|
||||
}
|
||||
}
|
||||
|
||||
/// Register a demangled `function_symbol` with a `callback_id`.
|
||||
///
|
||||
/// Tracepoint: `ros2::callback_register`
|
||||
pub fn trace_callback_register(callback_id: usize, function_symbol: &str) {
|
||||
let function_symbol = CString::new(function_symbol)
|
||||
.expect("r2r tracing: Cannot convert function_symbol to CString");
|
||||
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_callback_register(c_void!(callback_id), function_symbol.as_ptr());
|
||||
}
|
||||
}
|
||||
|
||||
/// Start of a callback
|
||||
///
|
||||
/// If this callback is done via intra-process set `is_intra_process` to `true`.
|
||||
///
|
||||
/// Tracepoint: `ros2::callback_start`
|
||||
pub fn trace_callback_start(callback_id: usize, is_intra_process: bool) {
|
||||
unsafe {
|
||||
tp::ros_trace_callback_start(c_void!(callback_id), is_intra_process);
|
||||
}
|
||||
}
|
||||
|
||||
/// End of a callback.
|
||||
///
|
||||
/// Tracepoint: `ros2::callback_end`
|
||||
pub fn trace_callback_end(callback_id: usize) {
|
||||
unsafe {
|
||||
tp::ros_trace_callback_end(c_void!(callback_id));
|
||||
}
|
||||
}
|
||||
|
||||
/// Notes the start time of the executor phase that gets the next executable that's ready.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_executor_get_next_ready`
|
||||
pub fn trace_executor_get_next_ready() {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_executor_get_next_ready();
|
||||
}
|
||||
}
|
||||
|
||||
/// Notes the start time of the executor phase that waits for work and notes the `timeout` value.
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_executor_wait_for_work`
|
||||
pub fn trace_executor_wait_for_work(timeout: i64) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_executor_wait_for_work(timeout);
|
||||
}
|
||||
}
|
||||
|
||||
/// Executable execution.
|
||||
///
|
||||
/// Notes an executable being executed using its `rcl_handle`, which can be a:
|
||||
/// * timer
|
||||
/// * subscription
|
||||
///
|
||||
/// Tracepoint: `ros2::rclcpp_executor_execute`
|
||||
pub fn trace_executor_execute<H>(rcl_handle: *const H) {
|
||||
unsafe {
|
||||
tp::ros_trace_rclcpp_executor_execute(c_void!(rcl_handle));
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,6 @@
|
|||
#![allow(non_upper_case_globals)]
|
||||
#![allow(non_camel_case_types)]
|
||||
#![allow(non_snake_case)]
|
||||
#![allow(unused)]
|
||||
|
||||
include!(concat!(env!("OUT_DIR"), "/tracetools_bindings.rs"));
|
||||
|
|
@ -0,0 +1 @@
|
|||
#include <tracetools/tracetools.h>
|
||||
Loading…
Reference in New Issue