pal_statistics_utils.cpp
Go to the documentation of this file.
1 /*
2  @file
3 
4  @author victor
5 
6  @copyright (c) 2018 PAL Robotics SL. All Rights Reserved
7 */
10 
11 namespace pal_statistics
12 {
13 
14 Registration::Registration(const std::string &name, IdType id, const boost::weak_ptr<StatisticsRegistry> &obj)
15  : name_(name), id_(id), obj_(obj)
16 {
17 }
18 
19 //Registration::Registration(const Registration &&other)
20 //{
21 // name_ = std::move(other.name_);
22 // id_ = std::move(other.id_);
23 // obj_ = std::move(other.obj_);
24 //}
25 
27 {
29  if (lock.get())
30  lock->unregisterVariable(id_);
31 }
32 
33 RegistrationList::RegistrationList(size_t internal_buffer_capacity)
34  : last_id_(0), names_version_(0), buffer_size_(internal_buffer_capacity), all_enabled_(true), registrations_changed_(true)
35 {
37 }
38 
40 {
41  for (size_t i = 0; i < ids_.size(); ++i)
42  {
43  if (ids_[i] == id)
44  {
45  deleteElement(i);
46  break;
47  }
48  }
49 }
50 
51 void RegistrationList::setEnabled(const IdType &id, bool enabled)
52 {
54  for (size_t i = 0; i < ids_.size(); ++i)
55  {
56  if (ids_[i] == id)
57  {
58  enabled_[i] = enabled;
59  all_enabled_ = all_enabled_ && enabled;
60  break;
61  }
62  }
63 }
64 
65 void RegistrationList::unregisterVariable(const std::string &name)
66 {
67  size_t count = name_id_.left.count(name);
68  if (count > 1)
69  {
71  "You asked to unregister "
72  << name
73  << " but there are multiple variables registered with that name. This can have undefined behaviour, unregistering all");
74  }
75  if (count == 0)
76  {
77  ROS_ERROR_STREAM("Tried to unregister variable " << name << " but it is not registered.");
78  return;
79  }
80  auto it = name_id_.left.find(name);
81  while (it != name_id_.left.end())
82  {
83  unregisterVariable(it->second);
84  it = name_id_.left.find(name);
85  }
86 }
87 
89 {
92 
93  auto &last_values_stamped = last_values_buffer_.push_back();
94  auto &last_values = last_values_stamped.first;
95  last_values_stamped.second = ros::Time::now();
96  assert(last_values.names.capacity() >= ids_.size());
97  assert(last_values.values.capacity() >= ids_.size());
98 
99  // This is for optimization, majority of the time everything is enabled and this runs 40% faster
100  if (all_enabled_)
101  {
102  last_values.names = ids_;
103  size_t ref_size = references_.size();
104  for (size_t i = 0; i < ref_size; ++i)
105  {
106  // Should never allocate memory because its capacity is able to hold all
107  // variables
108  last_values.values[i] = references_[i].getValue();
109  }
110  last_values.values.resize(ref_size);
111  }
112  else
113  {
114  last_values.names.clear();
115  last_values.values.clear();
116  // We know it doesn't change from another thread, and makes the condition check 50% faster
117  size_t id_size = ids_.size();
118  for (size_t i = 0; i < id_size; ++i)
119  {
120  if (enabled_[i])
121  {
122  // Should never allocate memory because its capacity is able to hold all
123  // variables
124  last_values.names.emplace_back(ids_[i]);
125  last_values.values.emplace_back(references_[i].getValue());
126 
127  }
128  }
129  }
130 }
131 
132 void RegistrationList::fillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &value)
133 {
134  names.names.clear();
135  names.names.resize(last_values_buffer_.front().first.names.size());
136  for (size_t i = 0; i < last_values_buffer_.front().first.names.size(); ++i)
137  {
138  const IdType &id = last_values_buffer_.front().first.names[i];
139  assert(name_id_.right.find(id) != name_id_.right.end());
140  names.names[i] = name_id_.right.find(id)->second;;
141  }
142  names.header.stamp = last_values_buffer_.front().second;
143  value.header = names.header;
144  names.names_version = ++names_version_;
145  value.names_version = names.names_version;
146 
147  // Even though we're going to swap it later, we should have the same capacity
148  // because the RT part assumes it has enough capacity
149  value.values.reserve(last_values_buffer_.front().first.values.capacity());
150  // Swap for efficiency since we're going to pop it anyway
151  value.values.swap(last_values_buffer_.front().first.values);
153 }
154 
155 bool RegistrationList::smartFillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &values)
156 {
157  if (names.names.empty() || registrations_changed_)
158  {
159  fillMsg(names, values);
160  registrations_changed_ = false;
161  all_enabled_ = true;
162  for (size_t i = 0; i < enabled_.size(); ++i)
163  {
165  }
166  return false;
167  }
168 
169  assert(names.names.size() == last_values_buffer_.front().first.names.size());
170  assert(values.values.size() == last_values_buffer_.front().first.values.size());
171  assert(values.values.capacity() == last_values_buffer_.front().first.values.capacity());
172  assert(names.names_version == names_version_);
173  assert(values.names_version == names_version_);
174 
175  values.header.stamp = last_values_buffer_.front().second;
176  values.values.swap(last_values_buffer_.front().first.values);
178  return true;
179 }
180 
182 {
183  return ids_.size();
184 }
185 
187 {
188  return last_values_buffer_.size() > 0;
189 }
190 
192 {
193  IdType id = ids_[index];
194  if (name_id_.right.count(id) == 0)
195  ROS_ERROR_STREAM("Didn't find index " << index << " in <name, index> multimap");
196 
197  name_id_.right.erase(id);
198 
199  // Faster way of removing an object of a vector if we don't care about the
200  // internal ordering. We just care that they all have the same order
201  std::swap(names_[index], names_.back());
202  names_.resize(names_.size() - 1);
203  std::swap(ids_[index], ids_.back());
204  ids_.resize(ids_.size() - 1);
205  std::swap(references_[index], references_.back());
206  references_.resize(references_.size() - 1);
207  enabled_.swap(enabled_[index], enabled_.back());
208  enabled_.resize(enabled_.size() - 1);
209 
211 }
212 
214 {
215  registrations_changed_ = true;
217 }
218 
219 int RegistrationList::registerVariable(const std::string &name, VariableHolder &&holder, bool enabled)
220 {
222 
223  bool needs_more_capacity = (names_.size() == names_.capacity());
224  int id = last_id_++;
225  name_id_.left.insert(std::make_pair(name, id));
226  names_.push_back(name);
227  ids_.push_back(id);
228  references_.push_back(std::move(holder));
229  enabled_.push_back(enabled);
230  // reserve memory for values
231  if (needs_more_capacity )
232  {
233  // Reset last_values_buffer_ size to be able to contain buffer_size_ copies
234  // of the last values vector with the same capacity as the names vector
235  // But the buffer's number of elements is set to 0
237  LastValuesStamped(NameValues(names_.capacity()),
238  ros::Time(0)));
239  }
240  return id;
241 }
242 std::vector<Registration>::iterator RegistrationsRAII::find(const std::string &name)
243 {
244  for (auto it = registrations_.begin(); it != registrations_.end(); ++it)
245  {
246  if ((*it).name_ == name)
247  {
248  return it;
249  }
250  }
251  throw std::runtime_error("Unable to find registration with name " + name);
252 }
253 
254 std::vector<Registration>::iterator RegistrationsRAII::find(IdType id)
255 {
256  for (auto it = registrations_.begin(); it != registrations_.end(); ++it)
257  {
258  if ((*it).id_ == id)
259  {
260  return it;
261  }
262  }
263  throw std::runtime_error("Unable to find registration with id " + std::to_string(id));
264 }
265 
266 
268 {
269 
270 }
271 
273 {
274  boost::unique_lock<boost::mutex> guard(mutex_);
275  registrations_.push_back(std::move(registration));
276 }
277 
278 bool RegistrationsRAII::remove(const std::string &name)
279 {
280  boost::unique_lock<boost::mutex> guard(mutex_);
281  try
282  {
283  registrations_.erase(find(name));
284  }
285  catch (...)
286  {
287  return false;
288  }
289  return true;
290 }
291 
292 
294 {
295  boost::unique_lock<boost::mutex> guard(mutex_);
296  try
297  {
298  registrations_.erase(find(id));
299  }
300  catch (...)
301  {
302  return false;
303  }
304  return true;
305 }
306 
308 {
309  registrations_.clear();
310 }
311 
312 bool RegistrationsRAII::enable(const std::string &name)
313 {
314  Registration&reg = *find(name);
315  return reg.obj_.lock()->enable(reg.id_);
316 }
317 
319 {
320  Registration&reg = *find(id);
321  return reg.obj_.lock()->enable(reg.id_);
322 }
323 
325 {
326  bool result = true;
327  for (auto it = registrations_.begin(); it != registrations_.end(); ++it)
328  {
329  result &= (*it).obj_.lock()->enable((*it).id_);
330  }
331  return result;
332 }
333 
334 bool RegistrationsRAII::disable(const std::string &name)
335 {
336  Registration&reg = *find(name);
337  return reg.obj_.lock()->disable(reg.id_);
338 }
339 
341 {
342  Registration&reg = *find(id);
343  return reg.obj_.lock()->disable(reg.id_);
344 }
345 
347 {
348  bool result = true;
349  for (auto it = registrations_.begin(); it != registrations_.end(); ++it)
350  {
351  result |= (*it).obj_.lock()->disable((*it).id_);
352  }
353  return result;
354 }
355 }
pal_statistics::RegistrationList::deleteElement
void deleteElement(size_t index)
Definition: pal_statistics_utils.cpp:191
pal_statistics::RegistrationsRAII::registrations_
std::vector< Registration > registrations_
Definition: pal_statistics_utils.h:143
StaticCircularBuffer::size
size_t size() const
Definition: static_circular_buffer.h:86
pal_statistics::RegistrationList::setEnabled
void setEnabled(const IdType &id, bool enabled)
Definition: pal_statistics_utils.cpp:51
pal_statistics::RegistrationList::RegistrationList
RegistrationList(size_t internal_buffer_capacity=100)
Definition: pal_statistics_utils.cpp:33
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
pal_statistics::RegistrationsRAII::enable
bool enable(const std::string &name)
Definition: pal_statistics_utils.cpp:312
pal_statistics::RegistrationsRAII::remove
bool remove(const std::string &name)
Definition: pal_statistics_utils.cpp:278
pal_statistics::RegistrationList::doUpdate
void doUpdate()
Definition: pal_statistics_utils.cpp:88
StaticCircularBuffer::push_back
T & push_back()
push_back Increases the buffer size (not capacity) by one, and returns a reference to the last item i...
Definition: static_circular_buffer.h:109
pal_statistics::RegistrationList::unregisterVariable
void unregisterVariable(const IdType &id)
Definition: pal_statistics_utils.cpp:39
pal_statistics::RegistrationsRAII::disableAll
bool disableAll()
Definition: pal_statistics_utils.cpp:346
pal_statistics::RegistrationList::all_enabled_
bool all_enabled_
Definition: pal_statistics_utils.h:273
pal_statistics::RegistrationList::buffer_size_
size_t buffer_size_
Definition: pal_statistics_utils.h:256
pal_statistics::RegistrationList::references_
std::vector< VariableHolder > references_
Definition: pal_statistics_utils.h:259
pal_statistics::RegistrationsRAII::RegistrationsRAII
RegistrationsRAII()
Definition: pal_statistics_utils.cpp:267
pal_statistics::Registration::~Registration
~Registration()
Definition: pal_statistics_utils.cpp:26
StaticCircularBuffer::capacity
size_t capacity() const
Definition: static_circular_buffer.h:81
pal_statistics::RegistrationsRAII::removeAll
void removeAll()
Definition: pal_statistics_utils.cpp:307
pal_statistics::RegistrationList::names_version_
unsigned int names_version_
Definition: pal_statistics_utils.h:248
pal_statistics::RegistrationList::NameValues
Definition: pal_statistics_utils.h:262
pal_statistics::RegistrationsRAII::disable
bool disable(const std::string &name)
Definition: pal_statistics_utils.cpp:334
pal_statistics::RegistrationsRAII::add
void add(Registration &&registration)
Definition: pal_statistics_utils.cpp:272
pal_statistics::Registration::obj_
boost::weak_ptr< StatisticsRegistry > obj_
Definition: pal_statistics_utils.h:106
pal_statistics::RegistrationList::name_id_
NameIdBiMap name_id_
Definition: pal_statistics_utils.h:254
pal_statistics::Registration
The Registration class is a handle to a registered variable, when out of scope unregisters the variab...
Definition: pal_statistics_utils.h:94
pal_statistics::RegistrationsRAII::mutex_
boost::mutex mutex_
Definition: pal_statistics_utils.h:142
pal_statistics::RegistrationList::ids_
std::vector< IdType > ids_
Definition: pal_statistics_utils.h:258
pal_statistics::RegistrationList::overwritten_data_count_
unsigned int overwritten_data_count_
Definition: pal_statistics_utils.h:241
pal_statistics.h
pal_statistics::RegistrationsRAII::find
std::vector< Registration >::iterator find(const std::string &name)
Definition: pal_statistics_utils.cpp:242
pal_statistics
Definition: extract_rosbag_signals.h:14
pal_statistics::Registration::Registration
Registration(const std::string &name, IdType id, const boost::weak_ptr< StatisticsRegistry > &obj)
Definition: pal_statistics_utils.cpp:14
pal_statistics::RegistrationList::names_
std::vector< std::string > names_
Definition: pal_statistics_utils.h:257
pal_statistics::RegistrationList::smartFillMsg
bool smartFillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &values)
smartFillMsg Attempts to minimize the amount of string copies
Definition: pal_statistics_utils.cpp:155
pal_statistics::RegistrationList::fillMsg
void fillMsg(pal_statistics_msgs::StatisticsNames &names, pal_statistics_msgs::StatisticsValues &value)
fills message with the last captured values.
Definition: pal_statistics_utils.cpp:132
pal_statistics::RegistrationList::last_values_buffer_
StaticCircularBuffer< LastValuesStamped > last_values_buffer_
Definition: pal_statistics_utils.h:274
pal_statistics::Registration::id_
IdType id_
Definition: pal_statistics_utils.h:105
pal_statistics::RegistrationList::registrationsChanged
void registrationsChanged()
Definition: pal_statistics_utils.cpp:213
ros::Time
pal_statistics::RegistrationList::last_id_
int last_id_
Definition: pal_statistics_utils.h:247
pal_statistics::RegistrationList::registerVariable
int registerVariable(const std::string &name, VariableHolder &&holder, bool enabled=true)
Definition: pal_statistics_utils.cpp:219
pal_statistics::RegistrationList::hasPendingData
bool hasPendingData() const
Definition: pal_statistics_utils.cpp:186
StaticCircularBuffer::set_capacity
void set_capacity(size_t max_size, const T &val)
set_capacity Allocates memory for max_size copies of val
Definition: static_circular_buffer.h:74
pal_statistics::RegistrationList::registrations_changed_
bool registrations_changed_
Definition: pal_statistics_utils.h:276
StaticCircularBuffer::pop_front
void pop_front()
pop_front Reduces buffer size by one, advancing the begin iterator
Definition: static_circular_buffer.h:128
StaticCircularBuffer::front
T & front()
Definition: static_circular_buffer.h:96
pal_statistics::RegistrationList::enabled_
std::vector< bool > enabled_
Definition: pal_statistics_utils.h:260
pal_statistics_utils.h
pal_statistics::RegistrationsRAII::enableAll
bool enableAll()
Definition: pal_statistics_utils.cpp:324
StaticCircularBuffer::clear
void clear()
clear Change the size of the buffer to 0 (not capacity) Only modifies internal iterators
Definition: static_circular_buffer.h:62
pal_statistics::RegistrationList::LastValuesStamped
std::pair< NameValues, ros::Time > LastValuesStamped
Definition: pal_statistics_utils.h:272
pal_statistics::RegistrationList::size
size_t size() const
Definition: pal_statistics_utils.cpp:181
pal_statistics::VariableHolder
Definition: pal_statistics_utils.h:147
ros::Time::now
static Time now()
pal_statistics::IdType
unsigned int IdType
Definition: pal_statistics_utils.h:46


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