Go to the documentation of this file.
14 #include <type_traits>
33 template <typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
43 template <typename M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value,
bool> =
true>
44 TopicStatus(const ::std::string& name, const ::cras::TopicStatusParam<Message>& params) :
47 this->
freqTask = ::std::make_unique<::diagnostic_updater::FrequencyStatus>(this->
origParams);
60 template <typename M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value,
bool> =
true>
62 const double minRate = 0.0,
const double maxRate = ::std::numeric_limits<double>::infinity(),
63 const double rateTolerance = 0.1,
const int rateWindowSize = 5) :
74 template <typename M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value,
bool> =
true>
75 TopicStatus(const ::std::string& name, const ::cras::TopicStatusParam<Message>& params) :
78 this->
freqTask = ::std::make_unique<::diagnostic_updater::FrequencyStatus>(this->
origParams);
79 this->
stampTask = ::std::make_unique<::diagnostic_updater::SlowTimeStampStatus>(this->
origParams);
96 template <typename M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value,
bool> =
true>
98 const double minRate = 0.0,
const double maxRate = ::std::numeric_limits<double>::infinity(),
99 const double rateTolerance = 0.1,
const int rateWindowSize = 5,
100 const double minDelay = -1.0,
const double maxDelay = 5.0) :
102 minRate, maxRate, rateTolerance, rateWindowSize, minDelay, maxDelay))
111 TopicStatus(const ::std::string& name, const ::cras::SimpleTopicStatusParam<Message>& params) :
124 virtual void tick(const ::ros::Time& stamp)
135 virtual void tick(
const Message& message)
146 virtual void tick(
const typename Message::Ptr& message)
148 this->
tick(*message);
155 virtual void tick(
const typename Message::ConstPtr& message)
157 this->
tick(*message);
164 virtual void tick(const ::ros::MessageEvent<Message>& event)
166 this->
tick(*event.getConstMessage());
221 template <typename M = Message, typename = ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value>>
224 return ::ros::Duration(this->
origParams.min_acceptable_);
232 template <typename M = Message, typename = ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value>>
235 return ::ros::Duration(this->
origParams.max_acceptable_);
240 ::std::unique_ptr<::diagnostic_updater::FrequencyStatus>
freqTask;
243 ::std::unique_ptr<::diagnostic_updater::SlowTimeStampStatus>
stampTask;
249 template <
typename Message>
void addTask(DiagnosticTask *t)
Utilities for working with ROS message files.
::std::unique_ptr<::diagnostic_updater::FrequencyStatus > freqTask
The frequency-checking diagnostic task. This will always be non-null.
::ros::Duration getMaxDelay() const
Max acceptable delay (in s). It can be negative if timestamps in future are expected.
TopicStatus(const ::std::string &name, const double minRate=0.0, const double maxRate=::std::numeric_limits< double >::infinity(), const double rateTolerance=0.1, const int rateWindowSize=5)
Create the diagnostic task for a header-less message (checking frequency only).
TopicStatus(const ::std::string &name, const ::cras::TopicStatusParam< Message > ¶ms)
Create the diagnostic task for a header-less message (checking frequency only).
::std::unique_ptr<::diagnostic_updater::SlowTimeStampStatus > stampTask
The delay-checking diagnostic task. It will be non-null only for messages with header.
::ros::Rate getMaxRate() const
Maximum allowed frequency.
Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatu...
::ros::Duration getMinDelay() const
Min acceptable delay (in s). It can be negative if timestamps in future are expected.
int getRateWindowSize() const
Number of updates during which the frequency is computed.
virtual void tick(const ::ros::Time &stamp)
Record that a message has arrived now with the given timestamp.
virtual void tick(const Message &message)
Record that a message has arrived.
::cras::TopicStatusParam< Message > origParams
The parameters via which this task has been configured.
::ros::Rate getExpectedRate() const
Get the expected/average rate. If min and max are the same, their value will be returned....
virtual void tick(const ::ros::MessageEvent< Message > &event)
Record that a message has arrived.
::ros::Rate getMinRate() const
Minimum allowed frequency.
TopicStatus(const ::std::string &name, const ::cras::SimpleTopicStatusParam< Message > ¶ms)
Create the diagnostic task checking frequency of messages and timestamp delay (if the message has hea...
::ros::Rate safeRate(double frequency)
Return a rate representing the given frequency. If the frequency is zero or too small,...
virtual void tick(const typename Message::ConstPtr &message)
Record that a message has arrived.
::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::TopicStatusParamWithHeader, ::cras::FrequencyStatusParam > TopicStatusParam
Helper struct for automatic choosing of the correct topic status parameter object based on whether th...
Utilities for working with time.
TopicStatus(const ::std::string &name, const double minRate=0.0, const double maxRate=::std::numeric_limits< double >::infinity(), const double rateTolerance=0.1, const int rateWindowSize=5, const double minDelay=-1.0, const double maxDelay=5.0)
Create the diagnostic task for a message with header (checking frequency and timestamp delay).
CompositeDiagnosticTask(const std::string name)
virtual void tick(const typename Message::Ptr &message)
Record that a message has arrived.
double getRateTolerance() const
Tolerance of frequency.
::std::shared_ptr<::cras::TopicStatus< Message > > TopicStatusPtr
Definitions of parameters for a TopicStatus diagnostic task.
typename ::ros::ParameterAdapter< M >::Message BaseMessage
Return the base message type of M (i.e. removes MessageEvent, const, &, shared_ptr etc....
cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 5 2024 03:50:30