Go to the documentation of this file.
16 pub_ =
nh_.
advertise<pal_statistics_msgs::Statistics>(topic +
"/full", 10000);
45 const boost::function<
double()> &funct,
58 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
69 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
76 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
80 boost::unique_lock<boost::mutex> pub_lock(
pub_mutex_);
94 ROS_WARN_STREAM_ONCE(
"Called publishAsync but publisher thread has not been started, THIS IS NOT RT safe. You should start it yourself.");
99 boost::unique_lock<boost::mutex> data_lock(
data_mutex_, boost::adopt_lock);
117 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
130 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
151 if (!data_lock.owns_lock() || data_lock.mutex() != &
data_mutex_)
153 throw ros::Exception(
"Called handlePendingDisables without proper lock");
173 if (publish_names_msg)
185 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
189 pal_statistics_msgs::StatisticsNames names;
190 pal_statistics_msgs::StatisticsValues values;
193 gen_sts.
update(names, values);
208 pal_statistics_msgs::StatisticsValues &values,
232 boost::unique_lock<boost::mutex> data_lock(
data_mutex_);
238 boost::unique_lock<boost::mutex> pub_lock(
pub_mutex_);
249 const pal_statistics_msgs::StatisticsNames &names,
250 const pal_statistics_msgs::StatisticsValues &values)
252 msg_.header = values.header;
256 for (
size_t i = 0; i < values.values.size(); ++i)
258 msg_.statistics[i].value = values.values[i];
263 msg_.statistics.clear();
264 for (
size_t i = 0; i < names.names.size(); ++i)
266 pal_statistics_msgs::Statistic
s;
267 s.name = names.names[i];
268 s.value = values.values[i];
269 msg_.statistics.push_back(
s);
RegistrationsRAII internal_stats_raii_
bool enable(const IdType &id)
void startPublishThreadImpl()
void publish()
publish Reads the values of all registered variables and publishes them to the topic associated to th...
bool disable(const IdType &id)
void setEnabled(const IdType &id, bool enabled)
IdType customRegister(StatisticsRegistry ®istry, const std::string &name, const T *variable, RegistrationsRAII *bookkeeping=NULL, bool enabled=true)
Default implementation that accepts anything variable that can be casted to a double.
bool publishAsync()
publishAsync Capture data and flag it to be published by the publisher thread. Real-Time safe.
void doPublish(bool publish_names_msg=true)
doPublish publishes the subscribed topics, requires mutex
bool remove(const std::string &name)
StatisticsRegistry(const std::string &topic)
bool setEnabledmpl(const IdType &id, bool enabled)
void unregisterVariable(const IdType &id)
void startPublishThread()
startPublishThread creates and starts the publisherThread. The user still has to call publishAsync ea...
unsigned int publish_async_failures_
void unregisterVariable(const std::string &name, RegistrationsRAII *bookkeeping=NULL)
pal_statistics_msgs::Statistics msg_
This message is generated using an updated StatiticsNames and StatisticsValues.
ros::Publisher pub_values_
double last_async_pub_duration_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
#define ROS_WARN_STREAM_ONCE(args)
GeneratedStatistics generated_statistics_
void add(Registration &®istration)
The Registration class is a handle to a registered variable, when out of scope unregisters the variab...
pal_statistics_msgs::Statistics createMsg()
createMsg creates a Statistics message from the registered variables, useful for debugging
unsigned int overwritten_data_count_
std::atomic< bool > is_data_ready_
pal_statistics_msgs::StatisticsNames names_msg_
unsigned int last_names_version_
virtual ~StatisticsRegistry()
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
void publisherThreadCycle()
#define ROS_INFO_STREAM(args)
void update(const pal_statistics_msgs::StatisticsNames &names, const pal_statistics_msgs::StatisticsValues &values)
pal_statistics_msgs::StatisticsValues values_msg_
bool smartFillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &values)
smartFillMsg Attempts to minimize the amount of string copies
void handlePendingDisables(const boost::unique_lock< boost::mutex > &data_lock)
handlePendingDisables Empties by handling the queue of disabled/enabled ids.
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
ros::Publisher pub_names_
void fillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &value)
fills message with the last captured values.
unsigned int publish_async_attempts_
LockFreeQueue< EnabledId > enabled_ids_
disabled_ids_ this is used to keep track of enabled/disabled variables in a lock free way
int registerVariable(const std::string &name, VariableHolder &&holder, bool enabled=true)
std::atomic< bool > interrupt_thread_
bool hasPendingData() const
boost::shared_ptr< boost::thread > publisher_thread_
uint32_t getNumSubscribers() const
IdType registerInternal(const std::string &name, VariableHolder &&variable, RegistrationsRAII *bookkeeping, bool enabled)
The RegistrationsRAII class holds handles to registered variables and when it is destroyed,...
RegistrationList registration_list_