Go to the documentation of this file.
4 #ifndef ROSBAG_FANCY_TOPIC_CONFIG_MANAGER_H
5 #define ROSBAG_FANCY_TOPIC_CONFIG_MANAGER_H
66 static constexpr
float LOG05 = -0.6931471805599453f;
80 float expL = std::exp(-
DECAY * tDelta);
91 float expL = std::exp(-
DECAY * tDelta);
94 float t0Delta = (time -
T0).toSec();
95 float S = (1.0f +
DECAY * t0Delta) * std::exp(-
DECAY * t0Delta);
109 void addTopic(
const std::string& topic,
float rateLimit = 0.0f,
int flags = 0);
Topic(const std::string &name, std::size_t id, float rateLimit=0.0f, int flags=0)
unsigned int numPublishers
static const ros::WallTime T0
std::vector< Topic > m_topics
static constexpr float HALF_LIFE
Topic & operator=(const Topic &other)=delete
std::vector< Topic > & topics()
void notifyMessage(std::uint64_t bytes)
decltype(sizeof(void *)) typede size_t)
std::uint64_t bytesInStatsPeriod
void addTopic(const std::string &topic, float rateLimit=0.0f, int flags=0)
float messageRateAt(const ros::WallTime &time)
std::uint64_t totalMessages
std::uint64_t dropCounter
std::uint64_t messagesInStatsPeriod
ros::Time lastMessageReceivedROSTime
ros::WallTime lastMessageTime
ros::Time lastMessageROSTime
static constexpr float LOG05
static constexpr float DECAY
rosbag_fancy
Author(s):
autogenerated on Tue Feb 20 2024 03:20:59