Class RttExecutor

Inheritance Relationships

Base Type

  • public rclcpp::Executor

Class Documentation

class RttExecutor : public rclcpp::Executor

Instrumented executor that syncs Executor::spin functions with rttest_spin.

Public Functions

inline RttExecutor(const rclcpp::ExecutorOptions &options = rclcpp::ExecutorOptions())

Constructor.

Extends default Executor constructor.

inline virtual ~RttExecutor()

Default destructor.

inline bool is_running() const

Return true if the executor is currently spinning.

inline bool set_rtt_results_message(pendulum_msgs::msg::RttestResults &msg) const

Fill in an RttestResults message with data from the executor.

The RttestResults message contains the latest latency, mean latency over time, the minimum and maximum seen latencies, the number of major and minor pagefaults, and the current time.

inline void spin()

Wrap executor::spin into rttest_spin.

Public Members

rttest_results results

For storing accumulated performance statistics.

bool results_available = {false}

Whether results are currently available.

bool running

True if the executor is spinning.

bool rttest_ready

True if rttest has initialized and hasn’t been stopped yet.

int64_t last_sample

The most recent sample, used for statistics.

Public Static Functions

static inline void *loop_callback(void *arg)

Core component of the executor. Do a little bit of work and update extra state.

Protected Attributes

timespec start_time_

Absolute timestamp at which the first data point was collected in rttest.