Class StatisticsRegistry

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< StatisticsRegistry >

Class Documentation

class StatisticsRegistry : public std::enable_shared_from_this<StatisticsRegistry>

The StatisticsRegistry class reads the value of registered variables and publishes them on the specified topic.

If you are using repeated names, it’s better to use the Id of the registered variables or the RegistratonRAII for unregister/disable

Warning

Functions are not real-time safe unless stated.

Warning

Registering and enabling more than one variable with the same name is not supported. Multiple variables with the same name can be registered, only if there’s only one of them enabled at any time.

Public Functions

StatisticsRegistry(rclcpp::node_interfaces::NodeParametersInterface::SharedPtr parameters_interface, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_interface, const rclcpp::node_interfaces::NodeClockInterface::SharedPtr &clock_interface, const std::string &topic)
StatisticsRegistry(const std::shared_ptr<rclcpp::Node> &node, const std::string &topic)
StatisticsRegistry(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, const std::string &topic)
virtual ~StatisticsRegistry()
IdType registerVariable(const std::string &name, const double *variable, RegistrationsRAII *bookkeeping = NULL, bool enabled = true)

registerVariable Specialization for double*, the most common case, to avoid going through a boost function call to read the variable

IdType registerFunction(const std::string &name, const std::function<double()> &funct, RegistrationsRAII *bookkeeping = NULL, bool enabled = true)

registerFunction Adds a function that returns double with the specified name

Parameters:

bookkeeping – same as in registerVariable

void unregisterVariable(const std::string &name, RegistrationsRAII *bookkeeping = NULL)
void unregisterVariable(IdType id, RegistrationsRAII *bookkeeping = NULL)
void publish()

publish Reads the values of all registered variables and publishes them to the topic associated to this object.

Warning

This function may lock if another thread is adding/removing registered variables, it may allocate memory, use publishAsync if you need RT safety

bool publishAsync()

publishAsync Capture data and flag it to be published by the publisher thread. Real-Time safe.

Warning

If the mutex cannot be acquired, data will not be captured. Should only happen if other threads are registering/unregistering or publishing variables.

Returns:

true if mutex and data could be acquired, false otherwise

void startPublishThread()

startPublishThread creates and starts the publisherThread. The user still has to call publishAsync each time a message must be publisher.

pal_statistics_msgs::msg::Statistics createMsg()

createMsg creates a Statistics message from the registered variables, useful for debugging

Returns:

template<typename T>
inline void publishCustomStatistic(const std::string &name, T value)

publishCustomStatistic publishes a one-time statistic

inline void publishCustomStatistics(const pal_statistics_msgs::msg::Statistics &msg)

publishCustomStatistic publishes a one-time statistics msg

bool enable(const IdType &id)

These functions disable/enable the publication of one or more variables

They are RT safe and thread safe. They guarantee that on the next publish (or publishAsync) call, the specified variables will or will not be read and published.

If you need a deterministic way of preventing a variable from being published, you need to unregister it, but it is not RT safe.

Warning

If a publish is being executed while this function is being run, it will not take into account these modifications.

bool disable(const IdType &id)

Protected Functions

void joinPublisherThread()

Friends

friend class ::PalStatisticsTestHelperClass