Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
pal_statistics::StatisticsRegistry Class Reference

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

#include <pal_statistics.h>

Inheritance diagram for pal_statistics::StatisticsRegistry:
Inheritance graph
[legend]

Classes

struct  EnabledId
 
struct  GeneratedStatistics
 

Public Member Functions

pal_statistics_msgs::Statistics createMsg ()
 createMsg creates a Statistics message from the registered variables, useful for debugging More...
 
bool disable (const IdType &id)
 
bool enable (const IdType &id)
 
void publish ()
 publish Reads the values of all registered variables and publishes them to the topic associated to this object. More...
 
bool publishAsync ()
 publishAsync Capture data and flag it to be published by the publisher thread. Real-Time safe. More...
 
template<typename T >
void publishCustomStatistic (const std::string &name, T value)
 publishCustomStatistic publishes a one-time statistic More...
 
void publishCustomStatistics (const pal_statistics_msgs::Statistics &msg)
 publishCustomStatistic publishes a one-time statistics msg More...
 
IdType registerFunction (const std::string &name, const boost::function< double()> &funct, RegistrationsRAII *bookkeeping=NULL, bool enabled=true)
 registerFunction Adds a function that returns double with the specified name More...
 
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 More...
 
void startPublishThread ()
 startPublishThread creates and starts the publisherThread. The user still has to call publishAsync each time a message must be publisher. More...
 
 StatisticsRegistry (const std::string &topic)
 
void unregisterVariable (const std::string &name, RegistrationsRAII *bookkeeping=NULL)
 
void unregisterVariable (IdType id, RegistrationsRAII *bookkeeping=NULL)
 
virtual ~StatisticsRegistry ()
 

Private Member Functions

void doPublish (bool publish_names_msg=true)
 doPublish publishes the subscribed topics, requires mutex More...
 
 FRIEND_TEST (PalStatisticsTest, stressAsync)
 
void handlePendingDisables (const boost::unique_lock< boost::mutex > &data_lock)
 handlePendingDisables Empties by handling the queue of disabled/enabled ids. More...
 
void publisherThreadCycle ()
 
IdType registerInternal (const std::string &name, VariableHolder &&variable, RegistrationsRAII *bookkeeping, bool enabled)
 
bool setEnabledmpl (const IdType &id, bool enabled)
 
void startPublishThreadImpl ()
 
bool updateMsg (pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &values, bool smart_fill=false)
 updateMsg update names and values, optionally using smartfill to minimize copying More...
 
void updateMsgUnsafe ()
 updateMsgUnsafe Updates the internal message variable without acquiring the mutex Should only be used if the mutex has already been acquired by the thread calling this More...
 

Private Attributes

boost::mutex data_mutex_
 
LockFreeQueue< EnabledIdenabled_ids_
 disabled_ids_ this is used to keep track of enabled/disabled variables in a lock free way More...
 
GeneratedStatistics generated_statistics_
 
RegistrationsRAII internal_stats_raii_
 
std::atomic< bool > interrupt_thread_
 
std::atomic< bool > is_data_ready_
 
double last_async_pub_duration_
 
pal_statistics_msgs::StatisticsNames names_msg_
 
ros::NodeHandle nh_
 
ros::Publisher pub_
 
boost::mutex pub_mutex_
 
ros::Publisher pub_names_
 
ros::Publisher pub_values_
 
unsigned int publish_async_attempts_
 
unsigned int publish_async_failures_
 
boost::shared_ptr< boost::thread > publisher_thread_
 
RegistrationList registration_list_
 
pal_statistics_msgs::StatisticsValues values_msg_
 

Detailed Description

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

Warning
Functions are not real-time safe unless stated.
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.

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

Definition at line 53 of file pal_statistics.h.

Constructor & Destructor Documentation

◆ StatisticsRegistry()

pal_statistics::StatisticsRegistry::StatisticsRegistry ( const std::string &  topic)

Definition at line 14 of file pal_statistics.cpp.

◆ ~StatisticsRegistry()

pal_statistics::StatisticsRegistry::~StatisticsRegistry ( )
virtual

Definition at line 31 of file pal_statistics.cpp.

Member Function Documentation

◆ createMsg()

pal_statistics_msgs::Statistics pal_statistics::StatisticsRegistry::createMsg ( )

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

Returns

Definition at line 183 of file pal_statistics.cpp.

◆ disable()

bool pal_statistics::StatisticsRegistry::disable ( const IdType id)

Definition at line 202 of file pal_statistics.cpp.

◆ doPublish()

void pal_statistics::StatisticsRegistry::doPublish ( bool  publish_names_msg = true)
private

doPublish publishes the subscribed topics, requires mutex

Definition at line 163 of file pal_statistics.cpp.

◆ enable()

bool pal_statistics::StatisticsRegistry::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.

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

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

Definition at line 197 of file pal_statistics.cpp.

◆ FRIEND_TEST()

pal_statistics::StatisticsRegistry::FRIEND_TEST ( PalStatisticsTest  ,
stressAsync   
)
private

◆ handlePendingDisables()

void pal_statistics::StatisticsRegistry::handlePendingDisables ( const boost::unique_lock< boost::mutex > &  data_lock)
private

handlePendingDisables Empties by handling the queue of disabled/enabled ids.

Definition at line 149 of file pal_statistics.cpp.

◆ publish()

void pal_statistics::StatisticsRegistry::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

Definition at line 74 of file pal_statistics.cpp.

◆ publishAsync()

bool pal_statistics::StatisticsRegistry::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

Definition at line 86 of file pal_statistics.cpp.

◆ publishCustomStatistic()

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

publishCustomStatistic publishes a one-time statistic

Definition at line 115 of file pal_statistics.h.

◆ publishCustomStatistics()

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

publishCustomStatistic publishes a one-time statistics msg

Definition at line 129 of file pal_statistics.h.

◆ publisherThreadCycle()

void pal_statistics::StatisticsRegistry::publisherThreadCycle ( )
private

Definition at line 220 of file pal_statistics.cpp.

◆ registerFunction()

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

registerFunction Adds a function that returns double with the specified name

Parameters
bookkeepingsame as in registerVariable

Definition at line 44 of file pal_statistics.cpp.

◆ registerInternal()

IdType pal_statistics::StatisticsRegistry::registerInternal ( const std::string &  name,
VariableHolder &&  variable,
RegistrationsRAII bookkeeping,
bool  enabled 
)
private

Definition at line 125 of file pal_statistics.cpp.

◆ registerVariable()

IdType pal_statistics::StatisticsRegistry::registerVariable ( const std::string &  name,
const double *  variable,
RegistrationsRAII bookkeeping = NULL,
bool  enabled = true 
)
inline

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

Definition at line 64 of file pal_statistics.h.

◆ setEnabledmpl()

bool pal_statistics::StatisticsRegistry::setEnabledmpl ( const IdType id,
bool  enabled 
)
private

Definition at line 140 of file pal_statistics.cpp.

◆ startPublishThread()

void pal_statistics::StatisticsRegistry::startPublishThread ( )

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

Definition at line 115 of file pal_statistics.cpp.

◆ startPublishThreadImpl()

void pal_statistics::StatisticsRegistry::startPublishThreadImpl ( )
private

Definition at line 120 of file pal_statistics.cpp.

◆ unregisterVariable() [1/2]

void pal_statistics::StatisticsRegistry::unregisterVariable ( const std::string &  name,
RegistrationsRAII bookkeeping = NULL 
)

Definition at line 62 of file pal_statistics.cpp.

◆ unregisterVariable() [2/2]

void pal_statistics::StatisticsRegistry::unregisterVariable ( IdType  id,
RegistrationsRAII bookkeeping = NULL 
)

Definition at line 51 of file pal_statistics.cpp.

◆ updateMsg()

bool pal_statistics::StatisticsRegistry::updateMsg ( pal_statistics_msgs::StatisticsNames &  names,
pal_statistics_msgs::StatisticsValues &  values,
bool  smart_fill = false 
)
private

updateMsg update names and values, optionally using smartfill to minimize copying

Returns
true if a smartfill was performed

Definition at line 207 of file pal_statistics.cpp.

◆ updateMsgUnsafe()

void pal_statistics::StatisticsRegistry::updateMsgUnsafe ( )
private

updateMsgUnsafe Updates the internal message variable without acquiring the mutex Should only be used if the mutex has already been acquired by the thread calling this

Member Data Documentation

◆ data_mutex_

boost::mutex pal_statistics::StatisticsRegistry::data_mutex_
private

Definition at line 185 of file pal_statistics.h.

◆ enabled_ids_

LockFreeQueue<EnabledId> pal_statistics::StatisticsRegistry::enabled_ids_
private

disabled_ids_ this is used to keep track of enabled/disabled variables in a lock free way

enable/disable need to write, but they cannot be locked, and cannot be skipped if they fail to acquire a mutex. Therefore they write to a lockfree structure. This structure is processed in the next publish or publishAsync that has the write lock and can modify shared structures.

Definition at line 205 of file pal_statistics.h.

◆ generated_statistics_

GeneratedStatistics pal_statistics::StatisticsRegistry::generated_statistics_
private

Definition at line 233 of file pal_statistics.h.

◆ internal_stats_raii_

RegistrationsRAII pal_statistics::StatisticsRegistry::internal_stats_raii_
private

Definition at line 238 of file pal_statistics.h.

◆ interrupt_thread_

std::atomic<bool> pal_statistics::StatisticsRegistry::interrupt_thread_
private

Definition at line 215 of file pal_statistics.h.

◆ is_data_ready_

std::atomic<bool> pal_statistics::StatisticsRegistry::is_data_ready_
private

Definition at line 214 of file pal_statistics.h.

◆ last_async_pub_duration_

double pal_statistics::StatisticsRegistry::last_async_pub_duration_
private

Definition at line 237 of file pal_statistics.h.

◆ names_msg_

pal_statistics_msgs::StatisticsNames pal_statistics::StatisticsRegistry::names_msg_
private

Definition at line 231 of file pal_statistics.h.

◆ nh_

ros::NodeHandle pal_statistics::StatisticsRegistry::nh_
private

Definition at line 183 of file pal_statistics.h.

◆ pub_

ros::Publisher pal_statistics::StatisticsRegistry::pub_
private

Definition at line 210 of file pal_statistics.h.

◆ pub_mutex_

boost::mutex pal_statistics::StatisticsRegistry::pub_mutex_
private

Definition at line 209 of file pal_statistics.h.

◆ pub_names_

ros::Publisher pal_statistics::StatisticsRegistry::pub_names_
private

Definition at line 211 of file pal_statistics.h.

◆ pub_values_

ros::Publisher pal_statistics::StatisticsRegistry::pub_values_
private

Definition at line 212 of file pal_statistics.h.

◆ publish_async_attempts_

unsigned int pal_statistics::StatisticsRegistry::publish_async_attempts_
private

Definition at line 235 of file pal_statistics.h.

◆ publish_async_failures_

unsigned int pal_statistics::StatisticsRegistry::publish_async_failures_
private

Definition at line 236 of file pal_statistics.h.

◆ publisher_thread_

boost::shared_ptr<boost::thread> pal_statistics::StatisticsRegistry::publisher_thread_
private

Definition at line 216 of file pal_statistics.h.

◆ registration_list_

RegistrationList pal_statistics::StatisticsRegistry::registration_list_
private

Definition at line 186 of file pal_statistics.h.

◆ values_msg_

pal_statistics_msgs::StatisticsValues pal_statistics::StatisticsRegistry::values_msg_
private

Definition at line 232 of file pal_statistics.h.


The documentation for this class was generated from the following files:


pal_statistics
Author(s):
autogenerated on Fri Aug 2 2024 08:29:35