topic_manager.cpp
Go to the documentation of this file.
1 // Contains the topic configuration & status
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "topic_manager.h"
5 
6 #include <ros/node_handle.h>
7 #include <rosfmt/rosfmt.h>
8 
9 #include <ros/names.h>
10 
11 namespace rosbag_fancy
12 {
13 
14 constexpr float STAT_TIME = 0.5;
15 
17 
19 {
20  ros::NodeHandle nh;
22  boost::bind(&TopicManager::updateStatistics, this)
23  );
24 }
25 
26 void TopicManager::addTopic(const std::string& topic, float rateLimit, int flags)
27 {
28  std::string resolvedName = ros::names::resolve(topic);
29 
30  auto it = std::find_if(m_topics.begin(), m_topics.end(), [&](Topic& t){
31  return t.name == resolvedName;
32  });
33 
34  if(it != m_topics.end())
35  {
37  "You tried to record topic '{}' twice. I'll ignore that (and use the first rate limit given, if applicable)",
38  resolvedName
39  );
40  return;
41  }
42 
43  m_topics.emplace_back(resolvedName, m_topics.size(), rateLimit, flags);
44 }
45 
47 {
48  for(auto& topic : m_topics)
49  {
50  topic.messageRate = topic.messagesInStatsPeriod / STAT_TIME;
51  topic.messagesInStatsPeriod = 0;
52 
53  topic.bandwidth = topic.bytesInStatsPeriod / STAT_TIME;
54  topic.bytesInStatsPeriod = 0;
55  }
56 }
57 
58 }
rosfmt.h
node_handle.h
rosbag_fancy::TopicManager::TopicManager
TopicManager()
Definition: topic_manager.cpp:18
rosbag_fancy::Topic::T0
static const ros::WallTime T0
Definition: topic_manager.h:68
rosbag_fancy::TopicManager::m_topics
std::vector< Topic > m_topics
Definition: topic_manager.h:113
rosbag_fancy
Definition: bag_reader.cpp:240
ROSFMT_WARN
#define ROSFMT_WARN(...)
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
topic_manager.h
rosbag_fancy::TopicManager::updateStatistics
void updateStatistics()
Definition: topic_manager.cpp:46
rosbag_fancy::TopicManager::m_timer
ros::SteadyTimer m_timer
Definition: topic_manager.h:114
ros::WallTime::now
static WallTime now()
rosbag_fancy::TopicManager::addTopic
void addTopic(const std::string &topic, float rateLimit=0.0f, int flags=0)
Definition: topic_manager.cpp:26
ros::WallTime
names.h
ros::NodeHandle::createSteadyTimer
SteadyTimer createSteadyTimer(SteadyTimerOptions &ops) const
rosbag_fancy::STAT_TIME
constexpr float STAT_TIME
Definition: topic_manager.cpp:14
rosbag_fancy::Topic
Definition: topic_manager.h:15
ros::WallDuration
ros::NodeHandle


rosbag_fancy
Author(s):
autogenerated on Tue Feb 20 2024 03:20:59